diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Inc/usbd_audio.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Inc/usbd_audio.h
new file mode 100644
index 0000000000..dbb71cd7ad
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Inc/usbd_audio.h
@@ -0,0 +1,218 @@
+/**
+ ******************************************************************************
+ * @file usbd_audio.h
+ * @author MCD Application Team
+ * @brief header file for the usbd_audio.c file.
+ ******************************************************************************
+ * @attention
+ *
+ *
© Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_AUDIO_H
+#define __USB_AUDIO_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_AUDIO
+ * @brief This file is the Header file for usbd_audio.c
+ * @{
+ */
+
+
+/** @defgroup USBD_AUDIO_Exported_Defines
+ * @{
+ */
+#ifndef USBD_AUDIO_FREQ
+/* AUDIO Class Config */
+#define USBD_AUDIO_FREQ 48000U
+#endif /* USBD_AUDIO_FREQ */
+
+#ifndef USBD_MAX_NUM_INTERFACES
+#define USBD_MAX_NUM_INTERFACES 1U
+#endif /* USBD_AUDIO_FREQ */
+
+#ifndef AUDIO_HS_BINTERVAL
+#define AUDIO_HS_BINTERVAL 0x01U
+#endif /* AUDIO_HS_BINTERVAL */
+
+#ifndef AUDIO_FS_BINTERVAL
+#define AUDIO_FS_BINTERVAL 0x01U
+#endif /* AUDIO_FS_BINTERVAL */
+
+#define AUDIO_OUT_EP 0x01U
+#define USB_AUDIO_CONFIG_DESC_SIZ 0x6DU
+#define AUDIO_INTERFACE_DESC_SIZE 0x09U
+#define USB_AUDIO_DESC_SIZ 0x09U
+#define AUDIO_STANDARD_ENDPOINT_DESC_SIZE 0x09U
+#define AUDIO_STREAMING_ENDPOINT_DESC_SIZE 0x07U
+
+#define AUDIO_DESCRIPTOR_TYPE 0x21U
+#define USB_DEVICE_CLASS_AUDIO 0x01U
+#define AUDIO_SUBCLASS_AUDIOCONTROL 0x01U
+#define AUDIO_SUBCLASS_AUDIOSTREAMING 0x02U
+#define AUDIO_PROTOCOL_UNDEFINED 0x00U
+#define AUDIO_STREAMING_GENERAL 0x01U
+#define AUDIO_STREAMING_FORMAT_TYPE 0x02U
+
+/* Audio Descriptor Types */
+#define AUDIO_INTERFACE_DESCRIPTOR_TYPE 0x24U
+#define AUDIO_ENDPOINT_DESCRIPTOR_TYPE 0x25U
+
+/* Audio Control Interface Descriptor Subtypes */
+#define AUDIO_CONTROL_HEADER 0x01U
+#define AUDIO_CONTROL_INPUT_TERMINAL 0x02U
+#define AUDIO_CONTROL_OUTPUT_TERMINAL 0x03U
+#define AUDIO_CONTROL_FEATURE_UNIT 0x06U
+
+#define AUDIO_INPUT_TERMINAL_DESC_SIZE 0x0CU
+#define AUDIO_OUTPUT_TERMINAL_DESC_SIZE 0x09U
+#define AUDIO_STREAMING_INTERFACE_DESC_SIZE 0x07U
+
+#define AUDIO_CONTROL_MUTE 0x0001U
+
+#define AUDIO_FORMAT_TYPE_I 0x01U
+#define AUDIO_FORMAT_TYPE_III 0x03U
+
+#define AUDIO_ENDPOINT_GENERAL 0x01U
+
+#define AUDIO_REQ_GET_CUR 0x81U
+#define AUDIO_REQ_SET_CUR 0x01U
+
+#define AUDIO_OUT_STREAMING_CTRL 0x02U
+
+#define AUDIO_OUT_TC 0x01U
+#define AUDIO_IN_TC 0x02U
+
+
+#define AUDIO_OUT_PACKET (uint16_t)(((USBD_AUDIO_FREQ * 2U * 2U) / 1000U))
+#define AUDIO_DEFAULT_VOLUME 70U
+
+/* Number of sub-packets in the audio transfer buffer. You can modify this value but always make sure
+ that it is an even number and higher than 3 */
+#define AUDIO_OUT_PACKET_NUM 80U
+/* Total size of the audio transfer buffer */
+#define AUDIO_TOTAL_BUF_SIZE ((uint16_t)(AUDIO_OUT_PACKET * AUDIO_OUT_PACKET_NUM))
+
+/* Audio Commands enumeration */
+typedef enum
+{
+ AUDIO_CMD_START = 1,
+ AUDIO_CMD_PLAY,
+ AUDIO_CMD_STOP,
+} AUDIO_CMD_TypeDef;
+
+
+typedef enum
+{
+ AUDIO_OFFSET_NONE = 0,
+ AUDIO_OFFSET_HALF,
+ AUDIO_OFFSET_FULL,
+ AUDIO_OFFSET_UNKNOWN,
+} AUDIO_OffsetTypeDef;
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+typedef struct
+{
+ uint8_t cmd;
+ uint8_t data[USB_MAX_EP0_SIZE];
+ uint8_t len;
+ uint8_t unit;
+} USBD_AUDIO_ControlTypeDef;
+
+
+typedef struct
+{
+ uint32_t alt_setting;
+ uint8_t buffer[AUDIO_TOTAL_BUF_SIZE];
+ AUDIO_OffsetTypeDef offset;
+ uint8_t rd_enable;
+ uint16_t rd_ptr;
+ uint16_t wr_ptr;
+ USBD_AUDIO_ControlTypeDef control;
+} USBD_AUDIO_HandleTypeDef;
+
+
+typedef struct
+{
+ int8_t (*Init)(uint32_t AudioFreq, uint32_t Volume, uint32_t options);
+ int8_t (*DeInit)(uint32_t options);
+ int8_t (*AudioCmd)(uint8_t *pbuf, uint32_t size, uint8_t cmd);
+ int8_t (*VolumeCtl)(uint8_t vol);
+ int8_t (*MuteCtl)(uint8_t cmd);
+ int8_t (*PeriodicTC)(uint8_t *pbuf, uint32_t size, uint8_t cmd);
+ int8_t (*GetState)(void);
+} USBD_AUDIO_ItfTypeDef;
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_AUDIO;
+#define USBD_AUDIO_CLASS &USBD_AUDIO
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+uint8_t USBD_AUDIO_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_AUDIO_ItfTypeDef *fops);
+
+void USBD_AUDIO_Sync(USBD_HandleTypeDef *pdev, AUDIO_OffsetTypeDef offset);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_AUDIO_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Inc/usbd_audio_if_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Inc/usbd_audio_if_template.h
new file mode 100644
index 0000000000..21cee0d720
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Inc/usbd_audio_if_template.h
@@ -0,0 +1,45 @@
+/**
+ ******************************************************************************
+ * @file usbd_audio_if_template.h
+ * @author MCD Application Team
+ * @brief Header for usbd_audio_if_template.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_AUDIO_IF_TEMPLATE_H
+#define __USBD_AUDIO_IF_TEMPLATE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_audio.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+extern USBD_AUDIO_ItfTypeDef USBD_AUDIO_Template_fops;
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_AUDIO_IF_TEMPLATE_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Src/usbd_audio.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Src/usbd_audio.c
new file mode 100644
index 0000000000..1dce51a31a
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Src/usbd_audio.c
@@ -0,0 +1,844 @@
+/**
+ ******************************************************************************
+ * @file usbd_audio.c
+ * @author MCD Application Team
+ * @brief This file provides the Audio core functions.
+ *
+ * @verbatim
+ *
+ * ===================================================================
+ * AUDIO Class Description
+ * ===================================================================
+ * This driver manages the Audio Class 1.0 following the "USB Device Class Definition for
+ * Audio Devices V1.0 Mar 18, 98".
+ * This driver implements the following aspects of the specification:
+ * - Device descriptor management
+ * - Configuration descriptor management
+ * - Standard AC Interface Descriptor management
+ * - 1 Audio Streaming Interface (with single channel, PCM, Stereo mode)
+ * - 1 Audio Streaming Endpoint
+ * - 1 Audio Terminal Input (1 channel)
+ * - Audio Class-Specific AC Interfaces
+ * - Audio Class-Specific AS Interfaces
+ * - AudioControl Requests: only SET_CUR and GET_CUR requests are supported (for Mute)
+ * - Audio Feature Unit (limited to Mute control)
+ * - Audio Synchronization type: Asynchronous
+ * - Single fixed audio sampling rate (configurable in usbd_conf.h file)
+ * The current audio class version supports the following audio features:
+ * - Pulse Coded Modulation (PCM) format
+ * - sampling rate: 48KHz.
+ * - Bit resolution: 16
+ * - Number of channels: 2
+ * - No volume control
+ * - Mute/Unmute capability
+ * - Asynchronous Endpoints
+ *
+ * @note In HS mode and when the DMA is used, all variables and data structures
+ * dealing with the DMA during the transaction process should be 32-bit aligned.
+ *
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+- "stm32xxxxx_{eval}{discovery}_audio.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_audio.h"
+#include "usbd_ctlreq.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_AUDIO
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_AUDIO_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_AUDIO_Private_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_AUDIO_Private_Macros
+ * @{
+ */
+#define AUDIO_SAMPLE_FREQ(frq) (uint8_t)(frq), (uint8_t)((frq >> 8)), (uint8_t)((frq >> 16))
+
+#define AUDIO_PACKET_SZE(frq) (uint8_t)(((frq * 2U * 2U)/1000U) & 0xFFU), \
+ (uint8_t)((((frq * 2U * 2U)/1000U) >> 8) & 0xFFU)
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_AUDIO_Private_FunctionPrototypes
+ * @{
+ */
+static uint8_t USBD_AUDIO_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_AUDIO_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+
+static uint8_t USBD_AUDIO_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req);
+
+static uint8_t *USBD_AUDIO_GetCfgDesc(uint16_t *length);
+static uint8_t *USBD_AUDIO_GetDeviceQualifierDesc(uint16_t *length);
+static uint8_t USBD_AUDIO_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_AUDIO_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_AUDIO_EP0_RxReady(USBD_HandleTypeDef *pdev);
+static uint8_t USBD_AUDIO_EP0_TxReady(USBD_HandleTypeDef *pdev);
+static uint8_t USBD_AUDIO_SOF(USBD_HandleTypeDef *pdev);
+
+static uint8_t USBD_AUDIO_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_AUDIO_IsoOutIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static void AUDIO_REQ_GetCurrent(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void AUDIO_REQ_SetCurrent(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_AUDIO_Private_Variables
+ * @{
+ */
+
+USBD_ClassTypeDef USBD_AUDIO =
+{
+ USBD_AUDIO_Init,
+ USBD_AUDIO_DeInit,
+ USBD_AUDIO_Setup,
+ USBD_AUDIO_EP0_TxReady,
+ USBD_AUDIO_EP0_RxReady,
+ USBD_AUDIO_DataIn,
+ USBD_AUDIO_DataOut,
+ USBD_AUDIO_SOF,
+ USBD_AUDIO_IsoINIncomplete,
+ USBD_AUDIO_IsoOutIncomplete,
+ USBD_AUDIO_GetCfgDesc,
+ USBD_AUDIO_GetCfgDesc,
+ USBD_AUDIO_GetCfgDesc,
+ USBD_AUDIO_GetDeviceQualifierDesc,
+};
+
+/* USB AUDIO device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_AUDIO_CfgDesc[USB_AUDIO_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ /* Configuration 1 */
+ 0x09, /* bLength */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType */
+ LOBYTE(USB_AUDIO_CONFIG_DESC_SIZ), /* wTotalLength 109 bytes*/
+ HIBYTE(USB_AUDIO_CONFIG_DESC_SIZ),
+ 0x02, /* bNumInterfaces */
+ 0x01, /* bConfigurationValue */
+ 0x00, /* iConfiguration */
+ 0xC0, /* bmAttributes BUS Powred*/
+ 0x32, /* bMaxPower = 100 mA*/
+ /* 09 byte*/
+
+ /* USB Speaker Standard interface descriptor */
+ AUDIO_INTERFACE_DESC_SIZE, /* bLength */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType */
+ 0x00, /* bInterfaceNumber */
+ 0x00, /* bAlternateSetting */
+ 0x00, /* bNumEndpoints */
+ USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */
+ AUDIO_SUBCLASS_AUDIOCONTROL, /* bInterfaceSubClass */
+ AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */
+ 0x00, /* iInterface */
+ /* 09 byte*/
+
+ /* USB Speaker Class-specific AC Interface Descriptor */
+ AUDIO_INTERFACE_DESC_SIZE, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_CONTROL_HEADER, /* bDescriptorSubtype */
+ 0x00, /* 1.00 */ /* bcdADC */
+ 0x01,
+ 0x27, /* wTotalLength = 39*/
+ 0x00,
+ 0x01, /* bInCollection */
+ 0x01, /* baInterfaceNr */
+ /* 09 byte*/
+
+ /* USB Speaker Input Terminal Descriptor */
+ AUDIO_INPUT_TERMINAL_DESC_SIZE, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_CONTROL_INPUT_TERMINAL, /* bDescriptorSubtype */
+ 0x01, /* bTerminalID */
+ 0x01, /* wTerminalType AUDIO_TERMINAL_USB_STREAMING 0x0101 */
+ 0x01,
+ 0x00, /* bAssocTerminal */
+ 0x01, /* bNrChannels */
+ 0x00, /* wChannelConfig 0x0000 Mono */
+ 0x00,
+ 0x00, /* iChannelNames */
+ 0x00, /* iTerminal */
+ /* 12 byte*/
+
+ /* USB Speaker Audio Feature Unit Descriptor */
+ 0x09, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_CONTROL_FEATURE_UNIT, /* bDescriptorSubtype */
+ AUDIO_OUT_STREAMING_CTRL, /* bUnitID */
+ 0x01, /* bSourceID */
+ 0x01, /* bControlSize */
+ AUDIO_CONTROL_MUTE, /* bmaControls(0) */
+ 0, /* bmaControls(1) */
+ 0x00, /* iTerminal */
+ /* 09 byte*/
+
+ /*USB Speaker Output Terminal Descriptor */
+ 0x09, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_CONTROL_OUTPUT_TERMINAL, /* bDescriptorSubtype */
+ 0x03, /* bTerminalID */
+ 0x01, /* wTerminalType 0x0301*/
+ 0x03,
+ 0x00, /* bAssocTerminal */
+ 0x02, /* bSourceID */
+ 0x00, /* iTerminal */
+ /* 09 byte*/
+
+ /* USB Speaker Standard AS Interface Descriptor - Audio Streaming Zero Bandwith */
+ /* Interface 1, Alternate Setting 0 */
+ AUDIO_INTERFACE_DESC_SIZE, /* bLength */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType */
+ 0x01, /* bInterfaceNumber */
+ 0x00, /* bAlternateSetting */
+ 0x00, /* bNumEndpoints */
+ USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */
+ AUDIO_SUBCLASS_AUDIOSTREAMING, /* bInterfaceSubClass */
+ AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */
+ 0x00, /* iInterface */
+ /* 09 byte*/
+
+ /* USB Speaker Standard AS Interface Descriptor - Audio Streaming Operational */
+ /* Interface 1, Alternate Setting 1 */
+ AUDIO_INTERFACE_DESC_SIZE, /* bLength */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType */
+ 0x01, /* bInterfaceNumber */
+ 0x01, /* bAlternateSetting */
+ 0x01, /* bNumEndpoints */
+ USB_DEVICE_CLASS_AUDIO, /* bInterfaceClass */
+ AUDIO_SUBCLASS_AUDIOSTREAMING, /* bInterfaceSubClass */
+ AUDIO_PROTOCOL_UNDEFINED, /* bInterfaceProtocol */
+ 0x00, /* iInterface */
+ /* 09 byte*/
+
+ /* USB Speaker Audio Streaming Interface Descriptor */
+ AUDIO_STREAMING_INTERFACE_DESC_SIZE, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_STREAMING_GENERAL, /* bDescriptorSubtype */
+ 0x01, /* bTerminalLink */
+ 0x01, /* bDelay */
+ 0x01, /* wFormatTag AUDIO_FORMAT_PCM 0x0001 */
+ 0x00,
+ /* 07 byte*/
+
+ /* USB Speaker Audio Type III Format Interface Descriptor */
+ 0x0B, /* bLength */
+ AUDIO_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_STREAMING_FORMAT_TYPE, /* bDescriptorSubtype */
+ AUDIO_FORMAT_TYPE_I, /* bFormatType */
+ 0x02, /* bNrChannels */
+ 0x02, /* bSubFrameSize : 2 Bytes per frame (16bits) */
+ 16, /* bBitResolution (16-bits per sample) */
+ 0x01, /* bSamFreqType only one frequency supported */
+ AUDIO_SAMPLE_FREQ(USBD_AUDIO_FREQ), /* Audio sampling frequency coded on 3 bytes */
+ /* 11 byte*/
+
+ /* Endpoint 1 - Standard Descriptor */
+ AUDIO_STANDARD_ENDPOINT_DESC_SIZE, /* bLength */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType */
+ AUDIO_OUT_EP, /* bEndpointAddress 1 out endpoint */
+ USBD_EP_TYPE_ISOC, /* bmAttributes */
+ AUDIO_PACKET_SZE(USBD_AUDIO_FREQ), /* wMaxPacketSize in Bytes (Freq(Samples)*2(Stereo)*2(HalfWord)) */
+ AUDIO_FS_BINTERVAL, /* bInterval */
+ 0x00, /* bRefresh */
+ 0x00, /* bSynchAddress */
+ /* 09 byte*/
+
+ /* Endpoint - Audio Streaming Descriptor*/
+ AUDIO_STREAMING_ENDPOINT_DESC_SIZE, /* bLength */
+ AUDIO_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType */
+ AUDIO_ENDPOINT_GENERAL, /* bDescriptor */
+ 0x00, /* bmAttributes */
+ 0x00, /* bLockDelayUnits */
+ 0x00, /* wLockDelay */
+ 0x00,
+ /* 07 byte*/
+} ;
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_AUDIO_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x40,
+ 0x01,
+ 0x00,
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_AUDIO_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_AUDIO_Init
+ * Initialize the AUDIO interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+ USBD_AUDIO_HandleTypeDef *haudio;
+
+ /* Allocate Audio structure */
+ haudio = USBD_malloc(sizeof(USBD_AUDIO_HandleTypeDef));
+
+ if (haudio == NULL)
+ {
+ pdev->pClassData = NULL;
+ return (uint8_t)USBD_EMEM;
+ }
+
+ pdev->pClassData = (void *)haudio;
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ pdev->ep_out[AUDIO_OUT_EP & 0xFU].bInterval = AUDIO_HS_BINTERVAL;
+ }
+ else /* LOW and FULL-speed endpoints */
+ {
+ pdev->ep_out[AUDIO_OUT_EP & 0xFU].bInterval = AUDIO_FS_BINTERVAL;
+ }
+
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, AUDIO_OUT_EP, USBD_EP_TYPE_ISOC, AUDIO_OUT_PACKET);
+ pdev->ep_out[AUDIO_OUT_EP & 0xFU].is_used = 1U;
+
+ haudio->alt_setting = 0U;
+ haudio->offset = AUDIO_OFFSET_UNKNOWN;
+ haudio->wr_ptr = 0U;
+ haudio->rd_ptr = 0U;
+ haudio->rd_enable = 0U;
+
+ /* Initialize the Audio output Hardware layer */
+ if (((USBD_AUDIO_ItfTypeDef *)pdev->pUserData)->Init(USBD_AUDIO_FREQ,
+ AUDIO_DEFAULT_VOLUME,
+ 0U) != 0U)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ /* Prepare Out endpoint to receive 1st packet */
+ (void)USBD_LL_PrepareReceive(pdev, AUDIO_OUT_EP, haudio->buffer,
+ AUDIO_OUT_PACKET);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_AUDIO_Init
+ * DeInitialize the AUDIO layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ /* Open EP OUT */
+ (void)USBD_LL_CloseEP(pdev, AUDIO_OUT_EP);
+ pdev->ep_out[AUDIO_OUT_EP & 0xFU].is_used = 0U;
+ pdev->ep_out[AUDIO_OUT_EP & 0xFU].bInterval = 0U;
+
+ /* DeInit physical Interface components */
+ if (pdev->pClassData != NULL)
+ {
+ ((USBD_AUDIO_ItfTypeDef *)pdev->pUserData)->DeInit(0U);
+ (void)USBD_free(pdev->pClassData);
+ pdev->pClassData = NULL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_AUDIO_Setup
+ * Handle the AUDIO specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req)
+{
+ USBD_AUDIO_HandleTypeDef *haudio;
+ uint16_t len;
+ uint8_t *pbuf;
+ uint16_t status_info = 0U;
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ haudio = (USBD_AUDIO_HandleTypeDef *)pdev->pClassData;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS:
+ switch (req->bRequest)
+ {
+ case AUDIO_REQ_GET_CUR:
+ AUDIO_REQ_GetCurrent(pdev, req);
+ break;
+
+ case AUDIO_REQ_SET_CUR:
+ AUDIO_REQ_SetCurrent(pdev, req);
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_DESCRIPTOR:
+ if ((req->wValue >> 8) == AUDIO_DESCRIPTOR_TYPE)
+ {
+ pbuf = USBD_AUDIO_CfgDesc + 18;
+ len = MIN(USB_AUDIO_DESC_SIZ, req->wLength);
+
+ (void)USBD_CtlSendData(pdev, pbuf, len);
+ }
+ break;
+
+ case USB_REQ_GET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&haudio->alt_setting, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ if ((uint8_t)(req->wValue) <= USBD_MAX_NUM_INTERFACES)
+ {
+ haudio->alt_setting = (uint8_t)(req->wValue);
+ }
+ else
+ {
+ /* Call the error management function (command will be nacked */
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+
+/**
+ * @brief USBD_AUDIO_GetCfgDesc
+ * return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_AUDIO_GetCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_AUDIO_CfgDesc);
+
+ return USBD_AUDIO_CfgDesc;
+}
+
+/**
+ * @brief USBD_AUDIO_DataIn
+ * handle data IN Stage
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ UNUSED(pdev);
+ UNUSED(epnum);
+
+ /* Only OUT data are processed */
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_AUDIO_EP0_RxReady
+ * handle EP0 Rx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_EP0_RxReady(USBD_HandleTypeDef *pdev)
+{
+ USBD_AUDIO_HandleTypeDef *haudio;
+ haudio = (USBD_AUDIO_HandleTypeDef *)pdev->pClassData;
+
+ if (haudio->control.cmd == AUDIO_REQ_SET_CUR)
+ {
+ /* In this driver, to simplify code, only SET_CUR request is managed */
+
+ if (haudio->control.unit == AUDIO_OUT_STREAMING_CTRL)
+ {
+ ((USBD_AUDIO_ItfTypeDef *)pdev->pUserData)->MuteCtl(haudio->control.data[0]);
+ haudio->control.cmd = 0U;
+ haudio->control.len = 0U;
+ }
+ }
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_AUDIO_EP0_TxReady
+ * handle EP0 TRx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_EP0_TxReady(USBD_HandleTypeDef *pdev)
+{
+ UNUSED(pdev);
+
+ /* Only OUT control data are processed */
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_AUDIO_SOF
+ * handle SOF event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_SOF(USBD_HandleTypeDef *pdev)
+{
+ UNUSED(pdev);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_AUDIO_SOF
+ * handle SOF event
+ * @param pdev: device instance
+ * @retval status
+ */
+void USBD_AUDIO_Sync(USBD_HandleTypeDef *pdev, AUDIO_OffsetTypeDef offset)
+{
+ USBD_AUDIO_HandleTypeDef *haudio;
+ uint32_t BufferSize = AUDIO_TOTAL_BUF_SIZE / 2U;
+
+ if (pdev->pClassData == NULL)
+ {
+ return;
+ }
+
+ haudio = (USBD_AUDIO_HandleTypeDef *)pdev->pClassData;
+
+ haudio->offset = offset;
+
+ if (haudio->rd_enable == 1U)
+ {
+ haudio->rd_ptr += (uint16_t)BufferSize;
+
+ if (haudio->rd_ptr == AUDIO_TOTAL_BUF_SIZE)
+ {
+ /* roll back */
+ haudio->rd_ptr = 0U;
+ }
+ }
+
+ if (haudio->rd_ptr > haudio->wr_ptr)
+ {
+ if ((haudio->rd_ptr - haudio->wr_ptr) < AUDIO_OUT_PACKET)
+ {
+ BufferSize += 4U;
+ }
+ else
+ {
+ if ((haudio->rd_ptr - haudio->wr_ptr) > (AUDIO_TOTAL_BUF_SIZE - AUDIO_OUT_PACKET))
+ {
+ BufferSize -= 4U;
+ }
+ }
+ }
+ else
+ {
+ if ((haudio->wr_ptr - haudio->rd_ptr) < AUDIO_OUT_PACKET)
+ {
+ BufferSize -= 4U;
+ }
+ else
+ {
+ if ((haudio->wr_ptr - haudio->rd_ptr) > (AUDIO_TOTAL_BUF_SIZE - AUDIO_OUT_PACKET))
+ {
+ BufferSize += 4U;
+ }
+ }
+ }
+
+ if (haudio->offset == AUDIO_OFFSET_FULL)
+ {
+ ((USBD_AUDIO_ItfTypeDef *)pdev->pUserData)->AudioCmd(&haudio->buffer[0],
+ BufferSize, AUDIO_CMD_PLAY);
+ haudio->offset = AUDIO_OFFSET_NONE;
+ }
+}
+
+/**
+ * @brief USBD_AUDIO_IsoINIncomplete
+ * handle data ISO IN Incomplete event
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ UNUSED(pdev);
+ UNUSED(epnum);
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_AUDIO_IsoOutIncomplete
+ * handle data ISO OUT Incomplete event
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_IsoOutIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ UNUSED(pdev);
+ UNUSED(epnum);
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_AUDIO_DataOut
+ * handle data OUT Stage
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_AUDIO_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ uint16_t PacketSize;
+ USBD_AUDIO_HandleTypeDef *haudio;
+
+ haudio = (USBD_AUDIO_HandleTypeDef *)pdev->pClassData;
+
+ if (epnum == AUDIO_OUT_EP)
+ {
+ /* Get received data packet length */
+ PacketSize = (uint16_t)USBD_LL_GetRxDataSize(pdev, epnum);
+
+ /* Packet received Callback */
+ ((USBD_AUDIO_ItfTypeDef *)pdev->pUserData)->PeriodicTC(&haudio->buffer[haudio->wr_ptr],
+ PacketSize, AUDIO_OUT_TC);
+
+ /* Increment the Buffer pointer or roll it back when all buffers are full */
+ haudio->wr_ptr += PacketSize;
+
+ if (haudio->wr_ptr == AUDIO_TOTAL_BUF_SIZE)
+ {
+ /* All buffers are full: roll back */
+ haudio->wr_ptr = 0U;
+
+ if (haudio->offset == AUDIO_OFFSET_UNKNOWN)
+ {
+ ((USBD_AUDIO_ItfTypeDef *)pdev->pUserData)->AudioCmd(&haudio->buffer[0],
+ AUDIO_TOTAL_BUF_SIZE / 2U,
+ AUDIO_CMD_START);
+ haudio->offset = AUDIO_OFFSET_NONE;
+ }
+ }
+
+ if (haudio->rd_enable == 0U)
+ {
+ if (haudio->wr_ptr == (AUDIO_TOTAL_BUF_SIZE / 2U))
+ {
+ haudio->rd_enable = 1U;
+ }
+ }
+
+ /* Prepare Out endpoint to receive next audio packet */
+ (void)USBD_LL_PrepareReceive(pdev, AUDIO_OUT_EP,
+ &haudio->buffer[haudio->wr_ptr],
+ AUDIO_OUT_PACKET);
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief AUDIO_Req_GetCurrent
+ * Handles the GET_CUR Audio control request.
+ * @param pdev: instance
+ * @param req: setup class request
+ * @retval status
+ */
+static void AUDIO_REQ_GetCurrent(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_AUDIO_HandleTypeDef *haudio;
+ haudio = (USBD_AUDIO_HandleTypeDef *)pdev->pClassData;
+
+ (void)USBD_memset(haudio->control.data, 0, 64U);
+
+ /* Send the current mute state */
+ (void)USBD_CtlSendData(pdev, haudio->control.data, req->wLength);
+}
+
+/**
+ * @brief AUDIO_Req_SetCurrent
+ * Handles the SET_CUR Audio control request.
+ * @param pdev: instance
+ * @param req: setup class request
+ * @retval status
+ */
+static void AUDIO_REQ_SetCurrent(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_AUDIO_HandleTypeDef *haudio;
+ haudio = (USBD_AUDIO_HandleTypeDef *)pdev->pClassData;
+
+ if (req->wLength != 0U)
+ {
+ /* Prepare the reception of the buffer over EP0 */
+ (void)USBD_CtlPrepareRx(pdev, haudio->control.data, req->wLength);
+
+ haudio->control.cmd = AUDIO_REQ_SET_CUR; /* Set the request value */
+ haudio->control.len = (uint8_t)req->wLength; /* Set the request data length */
+ haudio->control.unit = HIBYTE(req->wIndex); /* Set the request target unit */
+ }
+}
+
+
+/**
+* @brief DeviceQualifierDescriptor
+* return Device Qualifier descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+static uint8_t *USBD_AUDIO_GetDeviceQualifierDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_AUDIO_DeviceQualifierDesc);
+
+ return USBD_AUDIO_DeviceQualifierDesc;
+}
+
+/**
+* @brief USBD_AUDIO_RegisterInterface
+* @param fops: Audio interface callback
+* @retval status
+*/
+uint8_t USBD_AUDIO_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_AUDIO_ItfTypeDef *fops)
+{
+ if (fops == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ pdev->pUserData = fops;
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Src/usbd_audio_if_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Src/usbd_audio_if_template.c
new file mode 100644
index 0000000000..7c97c751ca
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/AUDIO/Src/usbd_audio_if_template.c
@@ -0,0 +1,201 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_if_template.c
+ * @author MCD Application Team
+ * @brief Generic media access Layer.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+- "stm32xxxxx_{eval}{discovery}_audio.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_audio_if_template.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_AUDIO
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_AUDIO_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_AUDIO_Private_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_AUDIO_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_AUDIO_Private_FunctionPrototypes
+ * @{
+ */
+
+static int8_t TEMPLATE_Init(uint32_t AudioFreq, uint32_t Volume, uint32_t options);
+static int8_t TEMPLATE_DeInit(uint32_t options);
+static int8_t TEMPLATE_AudioCmd(uint8_t *pbuf, uint32_t size, uint8_t cmd);
+static int8_t TEMPLATE_VolumeCtl(uint8_t vol);
+static int8_t TEMPLATE_MuteCtl(uint8_t cmd);
+static int8_t TEMPLATE_PeriodicTC(uint8_t *pbuf, uint32_t size, uint8_t cmd);
+static int8_t TEMPLATE_GetState(void);
+
+USBD_AUDIO_ItfTypeDef USBD_AUDIO_Template_fops =
+{
+ TEMPLATE_Init,
+ TEMPLATE_DeInit,
+ TEMPLATE_AudioCmd,
+ TEMPLATE_VolumeCtl,
+ TEMPLATE_MuteCtl,
+ TEMPLATE_PeriodicTC,
+ TEMPLATE_GetState,
+};
+
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief TEMPLATE_Init
+ * Initializes the AUDIO media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_Init(uint32_t AudioFreq, uint32_t Volume, uint32_t options)
+{
+ UNUSED(AudioFreq);
+ UNUSED(Volume);
+ UNUSED(options);
+
+ /*
+ Add your initialization code here
+ */
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_DeInit
+ * DeInitializes the AUDIO media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_DeInit(uint32_t options)
+{
+ UNUSED(options);
+
+ /*
+ Add your deinitialization code here
+ */
+ return (0);
+}
+
+
+/**
+ * @brief TEMPLATE_AudioCmd
+ * AUDIO command handler
+ * @param Buf: Buffer of data to be sent
+ * @param size: Number of data to be sent (in bytes)
+ * @param cmd: command opcode
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_AudioCmd(uint8_t *pbuf, uint32_t size, uint8_t cmd)
+{
+ UNUSED(pbuf);
+ UNUSED(size);
+ UNUSED(cmd);
+
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_VolumeCtl
+ * @param vol: volume level (0..100)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_VolumeCtl(uint8_t vol)
+{
+ UNUSED(vol);
+
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_MuteCtl
+ * @param cmd: vmute command
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_MuteCtl(uint8_t cmd)
+{
+ UNUSED(cmd);
+
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_PeriodicTC
+ * @param cmd
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_PeriodicTC(uint8_t *pbuf, uint32_t size, uint8_t cmd)
+{
+ UNUSED(pbuf);
+ UNUSED(size);
+ UNUSED(cmd);
+
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_GetState
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_GetState(void)
+{
+ return (0);
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/BillBoard/Inc/usbd_billboard.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/BillBoard/Inc/usbd_billboard.h
new file mode 100644
index 0000000000..8bff7b3550
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/BillBoard/Inc/usbd_billboard.h
@@ -0,0 +1,163 @@
+/**
+ ******************************************************************************
+ * @file usbd_billboard.h
+ * @author MCD Application Team
+ * @brief Header file for the usbd_billboard.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_BB_H
+#define __USB_BB_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+#include "usbd_desc.h"
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_BB
+ * @brief This file is the Header file for usbd_billboard.c
+ * @{
+ */
+
+/** @defgroup USBD_BB_Exported_Defines
+ * @{
+ */
+#define USB_BB_CONFIG_DESC_SIZ 18U
+
+#ifndef USB_BB_MAX_NUM_ALT_MODE
+#define USB_BB_MAX_NUM_ALT_MODE 0x2U
+#endif /* USB_BB_MAX_NUM_ALT_MODE */
+
+#ifndef USBD_BB_IF_STRING_INDEX
+#define USBD_BB_IF_STRING_INDEX 0x10U
+#endif /* USBD_BB_IF_STRING_INDEX */
+
+
+#define USBD_BILLBOARD_CAPABILITY 0x0DU
+#define USBD_BILLBOARD_ALTMODE_CAPABILITY 0x0FU
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+typedef struct _BB_DescHeader
+{
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint8_t bDevCapabilityType;
+}
+USBD_BB_DescHeader_t;
+
+typedef struct
+{
+ uint16_t wSVID;
+ uint8_t bAlternateMode;
+ uint8_t iAlternateModeString;
+} USBD_BB_AltModeTypeDef;
+
+typedef struct
+{
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint8_t bDevCapabilityType;
+ uint8_t bIndex;
+ uint32_t dwAlternateModeVdo;
+} USBD_BB_AltModeCapDescTypeDef;
+
+typedef struct
+{
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint8_t bDevCapabilityType;
+ uint8_t iAddtionalInfoURL;
+ uint8_t bNbrOfAltModes;
+ uint8_t bPreferredAltMode;
+ uint16_t VconnPwr;
+ uint8_t bmConfigured[32];
+ uint16_t bcdVersion;
+ uint8_t bAdditionalFailureInfo;
+ uint8_t bReserved;
+ USBD_BB_AltModeTypeDef wSVID[USB_BB_MAX_NUM_ALT_MODE];
+} USBD_BosBBCapDescTypedef;
+
+typedef enum
+{
+ UNSPECIFIED_ERROR = 0,
+ CONFIGURATION_NOT_ATTEMPTED,
+ CONFIGURATION_UNSUCCESSFUL,
+ CONFIGURATION_SUCCESSFUL,
+} BB_AltModeState;
+
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_BB;
+#define USBD_BB_CLASS &USBD_BB
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+
+#if (USBD_CLASS_BOS_ENABLED == 1)
+void *USBD_BB_GetCapDesc(USBD_HandleTypeDef *pdev, uint8_t *buf);
+void *USBD_BB_GetAltModeDesc(USBD_HandleTypeDef *pdev, uint8_t *buf, uint8_t idx);
+#endif
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_BB_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/BillBoard/Src/usbd_billboard.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/BillBoard/Src/usbd_billboard.c
new file mode 100644
index 0000000000..b9e6d1906c
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/BillBoard/Src/usbd_billboard.c
@@ -0,0 +1,496 @@
+/**
+ ******************************************************************************
+ * @file usbd_billboard.c
+ * @author MCD Application Team
+ * @brief This file provides the high layer firmware functions to manage the
+ * following functionalities of the USB BillBoard Class:
+ * - Initialization and Configuration of high and low layer
+ * - Enumeration as BillBoard Device
+ * - Error management
+ * @verbatim
+ *
+ * ===================================================================
+ * BillBoard Class Description
+ * ===================================================================
+ * This module manages the BillBoard class V1.2.1 following the "Device Class Definition
+ * for BillBoard Devices (BB) Version R1.2.1 Sept 08, 2016".
+ * This driver implements the following aspects of the specification:
+ * - Device descriptor management
+ * - Configuration descriptor management
+ * - Enumeration as an USB BillBoard device
+ * - Enumeration & management of BillBoard device supported alternate modes
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_billboard.h"
+#include "usbd_ctlreq.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_BB
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_BB_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_BB_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_BB_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_BB_Private_FunctionPrototypes
+ * @{
+ */
+
+static uint8_t USBD_BB_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_BB_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_BB_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static uint8_t USBD_BB_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_BB_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_BB_EP0_RxReady(USBD_HandleTypeDef *pdev);
+
+static uint8_t *USBD_BB_GetCfgDesc(uint16_t *length);
+static uint8_t *USBD_BB_GetDeviceQualifierDesc(uint16_t *length);
+static uint8_t *USBD_BB_GetOtherSpeedCfgDesc(uint16_t *length);
+
+#if (USBD_CLASS_BOS_ENABLED == 1)
+USBD_BB_DescHeader_t *USBD_BB_GetNextDesc(uint8_t *pbuf, uint16_t *ptr);
+#endif
+
+
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_BB_Private_Variables
+ * @{
+ */
+USBD_ClassTypeDef USBD_BB =
+{
+ USBD_BB_Init, /* Init */
+ USBD_BB_DeInit, /* DeInit */
+ USBD_BB_Setup, /* Setup */
+ NULL, /* EP0_TxSent */
+ USBD_BB_EP0_RxReady, /* EP0_RxReady */
+ USBD_BB_DataIn, /* DataIn */
+ USBD_BB_DataOut, /* DataOut */
+ NULL, /* SOF */
+ NULL,
+ NULL,
+ USBD_BB_GetCfgDesc,
+ USBD_BB_GetCfgDesc,
+ USBD_BB_GetOtherSpeedCfgDesc,
+ USBD_BB_GetDeviceQualifierDesc,
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+ NULL,
+#endif
+};
+
+/* USB Standard Device Qualifier Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_BB_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC, /* bLength */
+ USB_DESC_TYPE_DEVICE_QUALIFIER, /* bDescriptorType */
+ 0x01, /* bcdUSB */
+ 0x20,
+ 0x11, /* bDeviceClass */
+ 0x00, /* bDeviceSubClass */
+ 0x00, /* bDeviceProtocol */
+ 0x40, /* bMaxPacketSize0 */
+ 0x01, /* bNumConfigurations */
+ 0x00, /* bReserved */
+};
+
+/* USB device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_BB_CfgDesc[USB_BB_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_BB_CONFIG_DESC_SIZ, /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ USBD_IDX_CONFIG_STR, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: bus powered and Support Remote Wake-up */
+ 0x00, /* MaxPower 100 mA: this current is used for detecting Vbus */
+ /* 09 */
+
+ /************** Descriptor of BillBoard interface ****************/
+ /* 09 */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x00, /* bNumEndpoints */
+ 0x11, /* bInterfaceClass: billboard */
+ 0x00, /* bInterfaceSubClass */
+ 0x00, /* nInterfaceProtocol */
+ USBD_BB_IF_STRING_INDEX, /* iInterface: Index of string descriptor */
+};
+
+/* USB device Other Speed Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_BB_OtherSpeedCfgDesc[USB_BB_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuation Descriptor size */
+ USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION,
+ USB_BB_CONFIG_DESC_SIZ,
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: */
+ USBD_IDX_CONFIG_STR, /* iConfiguration: */
+ 0xC0, /* bmAttributes: */
+ 0x00, /* MaxPower 100 mA */
+
+ /************** Descriptor of BillBoard interface ****************/
+ /* 09 */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x00, /* bNumEndpoints*/
+ 0x11, /* bInterfaceClass: billboard */
+ 0x00, /* bInterfaceSubClass */
+ 0x00, /* nInterfaceProtocol */
+ USBD_BB_IF_STRING_INDEX, /* iInterface: Index of string descriptor */
+} ;
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_BB_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_BB_Init
+ * Initialize the BB interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_BB_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ /* Prevent unused argument compilation warning */
+ UNUSED(pdev);
+ UNUSED(cfgidx);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_BB_Init
+ * DeInitialize the BB layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_BB_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ /* Prevent unused argument compilation warning */
+ UNUSED(pdev);
+ UNUSED(cfgidx);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_BB_Setup
+ * Handle the BB specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_BB_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_StatusTypeDef ret = USBD_OK;
+ uint16_t status_info = 0U;
+ uint16_t AltSetting = 0U;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS:
+ break;
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&AltSetting, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ case USB_REQ_CLEAR_FEATURE:
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+/**
+ * @brief USBD_BB_DataIn
+ * Data sent on non-control IN endpoint
+ * @param pdev: device instance
+ * @param epnum: endpoint number
+ * @retval status
+ */
+static uint8_t USBD_BB_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ /* Prevent unused argument compilation warning */
+ UNUSED(pdev);
+ UNUSED(epnum);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_BB_DataOut
+ * Data received on non-control Out endpoint
+ * @param pdev: device instance
+ * @param epnum: endpoint number
+ * @retval status
+ */
+static uint8_t USBD_BB_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ /* Prevent unused argument compilation warning */
+ UNUSED(pdev);
+ UNUSED(epnum);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_BB_EP0_RxReady
+ * Handle EP0 Rx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_BB_EP0_RxReady(USBD_HandleTypeDef *pdev)
+{
+ /* Prevent unused argument compilation warning */
+ UNUSED(pdev);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_BB_GetCfgDesc
+ * return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_BB_GetCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_BB_CfgDesc);
+ return USBD_BB_CfgDesc;
+}
+
+/**
+ * @brief USBD_BB_GetOtherSpeedCfgDesc
+ * return other speed configuration descriptor
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+uint8_t *USBD_BB_GetOtherSpeedCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_BB_OtherSpeedCfgDesc);
+ return USBD_BB_OtherSpeedCfgDesc;
+}
+
+/**
+ * @brief DeviceQualifierDescriptor
+ * return Device Qualifier descriptor
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_BB_GetDeviceQualifierDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_BB_DeviceQualifierDesc);
+ return USBD_BB_DeviceQualifierDesc;
+}
+
+
+#if (USBD_CLASS_BOS_ENABLED == 1U)
+/**
+ * @brief USBD_BB_GetNextDesc
+ * This function return the next descriptor header
+ * @param buf: Buffer where the descriptor is available
+ * @param ptr: data pointer inside the descriptor
+ * @retval next header
+ */
+USBD_BB_DescHeader_t *USBD_BB_GetNextDesc(uint8_t *pbuf, uint16_t *ptr)
+{
+ USBD_BB_DescHeader_t *pnext = (USBD_BB_DescHeader_t *)pbuf;
+
+ *ptr += pnext->bLength;
+ pnext = (USBD_BB_DescHeader_t *)(pbuf + pnext->bLength);
+
+ return (pnext);
+}
+
+
+/**
+ * @brief USBD_BB_GetCapDesc
+ * This function return the Billboard Capability descriptor
+ * @param pdev: device instance
+ * @param pBosDesc: pointer to Bos descriptor
+ * @retval pointer to Billboard Capability descriptor
+ */
+void *USBD_BB_GetCapDesc(USBD_HandleTypeDef *pdev, uint8_t *pBosDesc)
+{
+ UNUSED(pdev);
+
+ USBD_BB_DescHeader_t *pdesc = (USBD_BB_DescHeader_t *)pBosDesc;
+ USBD_BosDescTypedef *desc = (USBD_BosDescTypedef *)pBosDesc;
+ USBD_BosBBCapDescTypedef *pCapDesc = NULL;
+ uint16_t ptr;
+
+ if (desc->wTotalLength > desc->bLength)
+ {
+ ptr = desc->bLength;
+
+ while (ptr < desc->wTotalLength)
+ {
+ pdesc = USBD_BB_GetNextDesc((uint8_t *)pdesc, &ptr);
+
+ if (pdesc->bDevCapabilityType == USBD_BILLBOARD_CAPABILITY)
+ {
+ pCapDesc = (USBD_BosBBCapDescTypedef *)pdesc;
+ break;
+ }
+ }
+ }
+ return (void *)pCapDesc;
+}
+
+
+/**
+ * @brief USBD_BB_GetAltModeDesc
+ * This function return the Billboard Alternate Mode descriptor
+ * @param pdev: device instance
+ * @param pBosDesc: pointer to Bos descriptor
+ * @param idx: Index of requested Alternate Mode descriptor
+ * @retval pointer to Alternate Mode descriptor
+ */
+void *USBD_BB_GetAltModeDesc(USBD_HandleTypeDef *pdev, uint8_t *pBosDesc, uint8_t idx)
+{
+ UNUSED(pdev);
+
+ USBD_BB_DescHeader_t *pdesc = (USBD_BB_DescHeader_t *)pBosDesc;
+ USBD_BosDescTypedef *desc = (USBD_BosDescTypedef *)pBosDesc;
+ USBD_BB_AltModeCapDescTypeDef *pAltModDesc = NULL;
+ uint8_t cnt = 0U;
+ uint16_t ptr;
+
+ if (desc->wTotalLength > desc->bLength)
+ {
+ ptr = desc->bLength;
+
+ while (ptr < desc->wTotalLength)
+ {
+ pdesc = USBD_BB_GetNextDesc((uint8_t *)pdesc, &ptr);
+
+ if (pdesc->bDevCapabilityType == USBD_BILLBOARD_ALTMODE_CAPABILITY)
+ {
+ if (cnt == idx)
+ {
+ pAltModDesc = (USBD_BB_AltModeCapDescTypeDef *)pdesc;
+ break;
+ }
+ else
+ {
+ cnt++;
+ }
+ }
+ }
+ }
+ return (void *)pAltModDesc;
+}
+#endif
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/usbd_cdc.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/usbd_cdc.h
new file mode 100644
index 0000000000..b484218e0f
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/usbd_cdc.h
@@ -0,0 +1,174 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc.h
+ * @author MCD Application Team
+ * @brief header file for the usbd_cdc.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_CDC_H
+#define __USB_CDC_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup usbd_cdc
+ * @brief This file is the Header file for usbd_cdc.c
+ * @{
+ */
+
+
+/** @defgroup usbd_cdc_Exported_Defines
+ * @{
+ */
+#define CDC_IN_EP 0x81U /* EP1 for data IN */
+#define CDC_OUT_EP 0x01U /* EP1 for data OUT */
+#define CDC_CMD_EP 0x82U /* EP2 for CDC commands */
+
+#ifndef CDC_HS_BINTERVAL
+#define CDC_HS_BINTERVAL 0x10U
+#endif /* CDC_HS_BINTERVAL */
+
+#ifndef CDC_FS_BINTERVAL
+#define CDC_FS_BINTERVAL 0x10U
+#endif /* CDC_FS_BINTERVAL */
+
+/* CDC Endpoints parameters: you can fine tune these values depending on the needed baudrates and performance. */
+#define CDC_DATA_HS_MAX_PACKET_SIZE 512U /* Endpoint IN & OUT Packet size */
+#define CDC_DATA_FS_MAX_PACKET_SIZE 64U /* Endpoint IN & OUT Packet size */
+#define CDC_CMD_PACKET_SIZE 8U /* Control Endpoint Packet size */
+
+#define USB_CDC_CONFIG_DESC_SIZ 67U
+#define CDC_DATA_HS_IN_PACKET_SIZE CDC_DATA_HS_MAX_PACKET_SIZE
+#define CDC_DATA_HS_OUT_PACKET_SIZE CDC_DATA_HS_MAX_PACKET_SIZE
+
+#define CDC_DATA_FS_IN_PACKET_SIZE CDC_DATA_FS_MAX_PACKET_SIZE
+#define CDC_DATA_FS_OUT_PACKET_SIZE CDC_DATA_FS_MAX_PACKET_SIZE
+
+/*---------------------------------------------------------------------*/
+/* CDC definitions */
+/*---------------------------------------------------------------------*/
+#define CDC_SEND_ENCAPSULATED_COMMAND 0x00U
+#define CDC_GET_ENCAPSULATED_RESPONSE 0x01U
+#define CDC_SET_COMM_FEATURE 0x02U
+#define CDC_GET_COMM_FEATURE 0x03U
+#define CDC_CLEAR_COMM_FEATURE 0x04U
+#define CDC_SET_LINE_CODING 0x20U
+#define CDC_GET_LINE_CODING 0x21U
+#define CDC_SET_CONTROL_LINE_STATE 0x22U
+#define CDC_SEND_BREAK 0x23U
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+typedef struct
+{
+ uint32_t bitrate;
+ uint8_t format;
+ uint8_t paritytype;
+ uint8_t datatype;
+} USBD_CDC_LineCodingTypeDef;
+
+typedef struct _USBD_CDC_Itf
+{
+ int8_t (* Init)(void);
+ int8_t (* DeInit)(void);
+ int8_t (* Control)(uint8_t cmd, uint8_t *pbuf, uint16_t length);
+ int8_t (* Receive)(uint8_t *Buf, uint32_t *Len);
+ int8_t (* TransmitCplt)(uint8_t *Buf, uint32_t *Len, uint8_t epnum);
+} USBD_CDC_ItfTypeDef;
+
+
+typedef struct
+{
+ uint32_t data[CDC_DATA_HS_MAX_PACKET_SIZE / 4U]; /* Force 32bits alignment */
+ uint8_t CmdOpCode;
+ uint8_t CmdLength;
+ uint8_t *RxBuffer;
+ uint8_t *TxBuffer;
+ uint32_t RxLength;
+ uint32_t TxLength;
+
+ __IO uint32_t TxState;
+ __IO uint32_t RxState;
+} USBD_CDC_HandleTypeDef;
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_CDC;
+#define USBD_CDC_CLASS &USBD_CDC
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+uint8_t USBD_CDC_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_CDC_ItfTypeDef *fops);
+
+uint8_t USBD_CDC_SetTxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff,
+ uint32_t length);
+
+uint8_t USBD_CDC_SetRxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff);
+uint8_t USBD_CDC_ReceivePacket(USBD_HandleTypeDef *pdev);
+uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_CDC_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/usbd_cdc_if_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/usbd_cdc_if_template.h
new file mode 100644
index 0000000000..158ad40c2f
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/usbd_cdc_if_template.h
@@ -0,0 +1,45 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_if_template.h
+ * @author MCD Application Team
+ * @brief Header for usbd_cdc_if_template.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CDC_IF_TEMPLATE_H
+#define __USBD_CDC_IF_TEMPLATE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+extern USBD_CDC_ItfTypeDef USBD_CDC_Template_fops;
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_CDC_IF_TEMPLATE_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c
new file mode 100644
index 0000000000..017e4cdc9e
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c
@@ -0,0 +1,935 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc.c
+ * @author MCD Application Team
+ * @brief This file provides the high layer firmware functions to manage the
+ * following functionalities of the USB CDC Class:
+ * - Initialization and Configuration of high and low layer
+ * - Enumeration as CDC Device (and enumeration for each implemented memory interface)
+ * - OUT/IN data transfer
+ * - Command IN transfer (class requests management)
+ * - Error management
+ *
+ * @verbatim
+ *
+ * ===================================================================
+ * CDC Class Driver Description
+ * ===================================================================
+ * This driver manages the "Universal Serial Bus Class Definitions for Communications Devices
+ * Revision 1.2 November 16, 2007" and the sub-protocol specification of "Universal Serial Bus
+ * Communications Class Subclass Specification for PSTN Devices Revision 1.2 February 9, 2007"
+ * This driver implements the following aspects of the specification:
+ * - Device descriptor management
+ * - Configuration descriptor management
+ * - Enumeration as CDC device with 2 data endpoints (IN and OUT) and 1 command endpoint (IN)
+ * - Requests management (as described in section 6.2 in specification)
+ * - Abstract Control Model compliant
+ * - Union Functional collection (using 1 IN endpoint for control)
+ * - Data interface class
+ *
+ * These aspects may be enriched or modified for a specific user application.
+ *
+ * This driver doesn't implement the following aspects of the specification
+ * (but it is possible to manage these features with some modifications on this driver):
+ * - Any class-specific aspect relative to communication classes should be managed by user application.
+ * - All communication classes other than PSTN are not managed
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc.h"
+#include "usbd_ctlreq.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_CDC
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_CDC_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_Private_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_Private_FunctionPrototypes
+ * @{
+ */
+
+static uint8_t USBD_CDC_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_CDC_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_CDC_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static uint8_t USBD_CDC_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_CDC_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_CDC_EP0_RxReady(USBD_HandleTypeDef *pdev);
+
+static uint8_t *USBD_CDC_GetFSCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_GetHSCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_GetOtherSpeedCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_GetOtherSpeedCfgDesc(uint16_t *length);
+uint8_t *USBD_CDC_GetDeviceQualifierDescriptor(uint16_t *length);
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x40,
+ 0x01,
+ 0x00,
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_Variables
+ * @{
+ */
+
+
+/* CDC interface class callbacks structure */
+USBD_ClassTypeDef USBD_CDC =
+{
+ USBD_CDC_Init,
+ USBD_CDC_DeInit,
+ USBD_CDC_Setup,
+ NULL, /* EP0_TxSent, */
+ USBD_CDC_EP0_RxReady,
+ USBD_CDC_DataIn,
+ USBD_CDC_DataOut,
+ NULL,
+ NULL,
+ NULL,
+ USBD_CDC_GetHSCfgDesc,
+ USBD_CDC_GetFSCfgDesc,
+ USBD_CDC_GetOtherSpeedCfgDesc,
+ USBD_CDC_GetDeviceQualifierDescriptor,
+};
+
+/* USB CDC device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_CfgHSDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ /* Configuration Descriptor */
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_CDC_CONFIG_DESC_SIZ, /* wTotalLength:no of returned bytes */
+ 0x00,
+ 0x02, /* bNumInterfaces: 2 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: self powered */
+ 0x32, /* MaxPower 0 mA */
+
+ /*---------------------------------------------------------------------------*/
+
+ /* Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface */
+ /* Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoints used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x02, /* bInterfaceSubClass: Abstract Control Model */
+ 0x01, /* bInterfaceProtocol: Common AT commands */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header Func Desc */
+ 0x10, /* bcdCDC: spec release number */
+ 0x01,
+
+ /* Call Management Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x01, /* bDescriptorSubtype: Call Management Func Desc */
+ 0x00, /* bmCapabilities: D0+D1 */
+ 0x01, /* bDataInterface: 1 */
+
+ /* ACM Functional Descriptor */
+ 0x04, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x02, /* bDescriptorSubtype: Abstract Control Management desc */
+ 0x02, /* bmCapabilities */
+
+ /* Union Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union func desc */
+ 0x00, /* bMasterInterface: Communication class interface */
+ 0x01, /* bSlaveInterface0: Data Class Interface */
+
+ /* Endpoint 2 Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_CMD_PACKET_SIZE),
+ CDC_HS_BINTERVAL, /* bInterval: */
+ /*---------------------------------------------------------------------------*/
+
+ /* Data class interface descriptor */
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ 0x01, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /* Endpoint OUT Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_DATA_HS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_DATA_HS_MAX_PACKET_SIZE),
+ 0x00, /* bInterval: ignore for Bulk transfer */
+
+ /* Endpoint IN Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_DATA_HS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_DATA_HS_MAX_PACKET_SIZE),
+ 0x00 /* bInterval: ignore for Bulk transfer */
+};
+
+
+/* USB CDC device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_CfgFSDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ /* Configuration Descriptor */
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_CDC_CONFIG_DESC_SIZ, /* wTotalLength:no of returned bytes */
+ 0x00,
+ 0x02, /* bNumInterfaces: 2 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: self powered */
+ 0x32, /* MaxPower 0 mA */
+
+ /*---------------------------------------------------------------------------*/
+
+ /* Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface */
+ /* Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoints used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x02, /* bInterfaceSubClass: Abstract Control Model */
+ 0x01, /* bInterfaceProtocol: Common AT commands */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header Func Desc */
+ 0x10, /* bcdCDC: spec release number */
+ 0x01,
+
+ /* Call Management Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x01, /* bDescriptorSubtype: Call Management Func Desc */
+ 0x00, /* bmCapabilities: D0+D1 */
+ 0x01, /* bDataInterface: 1 */
+
+ /* ACM Functional Descriptor */
+ 0x04, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x02, /* bDescriptorSubtype: Abstract Control Management desc */
+ 0x02, /* bmCapabilities */
+
+ /* Union Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union func desc */
+ 0x00, /* bMasterInterface: Communication class interface */
+ 0x01, /* bSlaveInterface0: Data Class Interface */
+
+ /* Endpoint 2 Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_CMD_PACKET_SIZE),
+ CDC_FS_BINTERVAL, /* bInterval: */
+ /*---------------------------------------------------------------------------*/
+
+ /* Data class interface descriptor */
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ 0x01, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /* Endpoint OUT Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_DATA_FS_MAX_PACKET_SIZE),
+ 0x00, /* bInterval: ignore for Bulk transfer */
+
+ /* Endpoint IN Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_DATA_FS_MAX_PACKET_SIZE),
+ 0x00 /* bInterval: ignore for Bulk transfer */
+};
+
+__ALIGN_BEGIN static uint8_t USBD_CDC_OtherSpeedCfgDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuation Descriptor size */
+ USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION,
+ USB_CDC_CONFIG_DESC_SIZ,
+ 0x00,
+ 0x02, /* bNumInterfaces: 2 interfaces */
+ 0x01, /* bConfigurationValue: */
+ 0x04, /* iConfiguration: */
+ 0xC0, /* bmAttributes: */
+ 0x32, /* MaxPower 100 mA */
+
+ /*Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface */
+ /* Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoints used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x02, /* bInterfaceSubClass: Abstract Control Model */
+ 0x01, /* bInterfaceProtocol: Common AT commands */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header Func Desc */
+ 0x10, /* bcdCDC: spec release number */
+ 0x01,
+
+ /*Call Management Functional Descriptor*/
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x01, /* bDescriptorSubtype: Call Management Func Desc */
+ 0x00, /* bmCapabilities: D0+D1 */
+ 0x01, /* bDataInterface: 1 */
+
+ /*ACM Functional Descriptor*/
+ 0x04, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x02, /* bDescriptorSubtype: Abstract Control Management desc */
+ 0x02, /* bmCapabilities */
+
+ /*Union Functional Descriptor*/
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union func desc */
+ 0x00, /* bMasterInterface: Communication class interface */
+ 0x01, /* bSlaveInterface0: Data Class Interface */
+
+ /*Endpoint 2 Descriptor*/
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_CMD_PACKET_SIZE),
+ CDC_FS_BINTERVAL, /* bInterval: */
+
+ /*---------------------------------------------------------------------------*/
+
+ /*Data class interface descriptor*/
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ 0x01, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /*Endpoint OUT Descriptor*/
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ 0x40, /* wMaxPacketSize: */
+ 0x00,
+ 0x00, /* bInterval: ignore for Bulk transfer */
+
+ /*Endpoint IN Descriptor*/
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ 0x40, /* wMaxPacketSize: */
+ 0x00,
+ 0x00 /* bInterval */
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_CDC_Init
+ * Initialize the CDC interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_CDC_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+ USBD_CDC_HandleTypeDef *hcdc;
+
+ hcdc = USBD_malloc(sizeof(USBD_CDC_HandleTypeDef));
+
+ if (hcdc == NULL)
+ {
+ pdev->pClassData = NULL;
+ return (uint8_t)USBD_EMEM;
+ }
+
+ pdev->pClassData = (void *)hcdc;
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, CDC_IN_EP, USBD_EP_TYPE_BULK,
+ CDC_DATA_HS_IN_PACKET_SIZE);
+
+ pdev->ep_in[CDC_IN_EP & 0xFU].is_used = 1U;
+
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, CDC_OUT_EP, USBD_EP_TYPE_BULK,
+ CDC_DATA_HS_OUT_PACKET_SIZE);
+
+ pdev->ep_out[CDC_OUT_EP & 0xFU].is_used = 1U;
+
+ /* Set bInterval for CDC CMD Endpoint */
+ pdev->ep_in[CDC_CMD_EP & 0xFU].bInterval = CDC_HS_BINTERVAL;
+ }
+ else
+ {
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, CDC_IN_EP, USBD_EP_TYPE_BULK,
+ CDC_DATA_FS_IN_PACKET_SIZE);
+
+ pdev->ep_in[CDC_IN_EP & 0xFU].is_used = 1U;
+
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, CDC_OUT_EP, USBD_EP_TYPE_BULK,
+ CDC_DATA_FS_OUT_PACKET_SIZE);
+
+ pdev->ep_out[CDC_OUT_EP & 0xFU].is_used = 1U;
+
+ /* Set bInterval for CMD Endpoint */
+ pdev->ep_in[CDC_CMD_EP & 0xFU].bInterval = CDC_FS_BINTERVAL;
+ }
+
+ /* Open Command IN EP */
+ (void)USBD_LL_OpenEP(pdev, CDC_CMD_EP, USBD_EP_TYPE_INTR, CDC_CMD_PACKET_SIZE);
+ pdev->ep_in[CDC_CMD_EP & 0xFU].is_used = 1U;
+
+ /* Init physical Interface components */
+ ((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Init();
+
+ /* Init Xfer states */
+ hcdc->TxState = 0U;
+ hcdc->RxState = 0U;
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ /* Prepare Out endpoint to receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_OUT_EP, hcdc->RxBuffer,
+ CDC_DATA_HS_OUT_PACKET_SIZE);
+ }
+ else
+ {
+ /* Prepare Out endpoint to receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_OUT_EP, hcdc->RxBuffer,
+ CDC_DATA_FS_OUT_PACKET_SIZE);
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_Init
+ * DeInitialize the CDC layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_CDC_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+ uint8_t ret = 0U;
+
+ /* Close EP IN */
+ (void)USBD_LL_CloseEP(pdev, CDC_IN_EP);
+ pdev->ep_in[CDC_IN_EP & 0xFU].is_used = 0U;
+
+ /* Close EP OUT */
+ (void)USBD_LL_CloseEP(pdev, CDC_OUT_EP);
+ pdev->ep_out[CDC_OUT_EP & 0xFU].is_used = 0U;
+
+ /* Close Command IN EP */
+ (void)USBD_LL_CloseEP(pdev, CDC_CMD_EP);
+ pdev->ep_in[CDC_CMD_EP & 0xFU].is_used = 0U;
+ pdev->ep_in[CDC_CMD_EP & 0xFU].bInterval = 0U;
+
+ /* DeInit physical Interface components */
+ if (pdev->pClassData != NULL)
+ {
+ ((USBD_CDC_ItfTypeDef *)pdev->pUserData)->DeInit();
+ (void)USBD_free(pdev->pClassData);
+ pdev->pClassData = NULL;
+ }
+
+ return ret;
+}
+
+/**
+ * @brief USBD_CDC_Setup
+ * Handle the CDC specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_CDC_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req)
+{
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)pdev->pClassData;
+ uint8_t ifalt = 0U;
+ uint16_t status_info = 0U;
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS:
+ if (req->wLength != 0U)
+ {
+ if ((req->bmRequest & 0x80U) != 0U)
+ {
+ ((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest,
+ (uint8_t *)hcdc->data,
+ req->wLength);
+
+ (void)USBD_CtlSendData(pdev, (uint8_t *)hcdc->data, req->wLength);
+ }
+ else
+ {
+ hcdc->CmdOpCode = req->bRequest;
+ hcdc->CmdLength = (uint8_t)req->wLength;
+
+ (void)USBD_CtlPrepareRx(pdev, (uint8_t *)hcdc->data, req->wLength);
+ }
+ }
+ else
+ {
+ ((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest,
+ (uint8_t *)req, 0U);
+ }
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, &ifalt, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ if (pdev->dev_state != USBD_STATE_CONFIGURED)
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+/**
+ * @brief USBD_CDC_DataIn
+ * Data sent on non-control IN endpoint
+ * @param pdev: device instance
+ * @param epnum: endpoint number
+ * @retval status
+ */
+static uint8_t USBD_CDC_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ USBD_CDC_HandleTypeDef *hcdc;
+ PCD_HandleTypeDef *hpcd = pdev->pData;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ hcdc = (USBD_CDC_HandleTypeDef *)pdev->pClassData;
+
+ if ((pdev->ep_in[epnum].total_length > 0U) &&
+ ((pdev->ep_in[epnum].total_length % hpcd->IN_ep[epnum].maxpacket) == 0U))
+ {
+ /* Update the packet total length */
+ pdev->ep_in[epnum].total_length = 0U;
+
+ /* Send ZLP */
+ (void)USBD_LL_Transmit(pdev, epnum, NULL, 0U);
+ }
+ else
+ {
+ hcdc->TxState = 0U;
+ ((USBD_CDC_ItfTypeDef *)pdev->pUserData)->TransmitCplt(hcdc->TxBuffer, &hcdc->TxLength, epnum);
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_DataOut
+ * Data received on non-control Out endpoint
+ * @param pdev: device instance
+ * @param epnum: endpoint number
+ * @retval status
+ */
+static uint8_t USBD_CDC_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)pdev->pClassData;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ /* Get the received data length */
+ hcdc->RxLength = USBD_LL_GetRxDataSize(pdev, epnum);
+
+ /* USB data will be immediately processed, this allow next USB traffic being
+ NAKed till the end of the application Xfer */
+
+ ((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Receive(hcdc->RxBuffer, &hcdc->RxLength);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_EP0_RxReady
+ * Handle EP0 Rx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_CDC_EP0_RxReady(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)pdev->pClassData;
+
+ if ((pdev->pUserData != NULL) && (hcdc->CmdOpCode != 0xFFU))
+ {
+ ((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(hcdc->CmdOpCode,
+ (uint8_t *)hcdc->data,
+ (uint16_t)hcdc->CmdLength);
+ hcdc->CmdOpCode = 0xFFU;
+
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_GetFSCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_GetFSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CDC_CfgFSDesc);
+
+ return USBD_CDC_CfgFSDesc;
+}
+
+/**
+ * @brief USBD_CDC_GetHSCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_GetHSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CDC_CfgHSDesc);
+
+ return USBD_CDC_CfgHSDesc;
+}
+
+/**
+ * @brief USBD_CDC_GetCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_GetOtherSpeedCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CDC_OtherSpeedCfgDesc);
+
+ return USBD_CDC_OtherSpeedCfgDesc;
+}
+
+/**
+* @brief DeviceQualifierDescriptor
+* return Device Qualifier descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+uint8_t *USBD_CDC_GetDeviceQualifierDescriptor(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CDC_DeviceQualifierDesc);
+
+ return USBD_CDC_DeviceQualifierDesc;
+}
+
+/**
+* @brief USBD_CDC_RegisterInterface
+ * @param pdev: device instance
+ * @param fops: CD Interface callback
+ * @retval status
+ */
+uint8_t USBD_CDC_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_CDC_ItfTypeDef *fops)
+{
+ if (fops == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ pdev->pUserData = fops;
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_SetTxBuffer
+ * @param pdev: device instance
+ * @param pbuff: Tx Buffer
+ * @retval status
+ */
+uint8_t USBD_CDC_SetTxBuffer(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuff, uint32_t length)
+{
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)pdev->pClassData;
+
+ hcdc->TxBuffer = pbuff;
+ hcdc->TxLength = length;
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_SetRxBuffer
+ * @param pdev: device instance
+ * @param pbuff: Rx Buffer
+ * @retval status
+ */
+uint8_t USBD_CDC_SetRxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff)
+{
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)pdev->pClassData;
+
+ hcdc->RxBuffer = pbuff;
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_TransmitPacket
+ * Transmit packet on IN endpoint
+ * @param pdev: device instance
+ * @retval status
+ */
+uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)pdev->pClassData;
+ USBD_StatusTypeDef ret = USBD_BUSY;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ if (hcdc->TxState == 0U)
+ {
+ /* Tx Transfer in progress */
+ hcdc->TxState = 1U;
+
+ /* Update the packet total length */
+ pdev->ep_in[CDC_IN_EP & 0xFU].total_length = hcdc->TxLength;
+
+ /* Transmit next packet */
+ (void)USBD_LL_Transmit(pdev, CDC_IN_EP, hcdc->TxBuffer, hcdc->TxLength);
+
+ ret = USBD_OK;
+ }
+
+ return (uint8_t)ret;
+}
+
+
+/**
+ * @brief USBD_CDC_ReceivePacket
+ * prepare OUT Endpoint for reception
+ * @param pdev: device instance
+ * @retval status
+ */
+uint8_t USBD_CDC_ReceivePacket(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef *)pdev->pClassData;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ /* Prepare Out endpoint to receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_OUT_EP, hcdc->RxBuffer,
+ CDC_DATA_HS_OUT_PACKET_SIZE);
+ }
+ else
+ {
+ /* Prepare Out endpoint to receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_OUT_EP, hcdc->RxBuffer,
+ CDC_DATA_FS_OUT_PACKET_SIZE);
+ }
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc_if_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc_if_template.c
new file mode 100644
index 0000000000..60748c39ff
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc_if_template.c
@@ -0,0 +1,248 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_if_template.c
+ * @author MCD Application Team
+ * @brief Generic media access Layer.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc_if_template.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_CDC
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_CDC_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_Private_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_Private_FunctionPrototypes
+ * @{
+ */
+
+static int8_t TEMPLATE_Init(void);
+static int8_t TEMPLATE_DeInit(void);
+static int8_t TEMPLATE_Control(uint8_t cmd, uint8_t *pbuf, uint16_t length);
+static int8_t TEMPLATE_Receive(uint8_t *pbuf, uint32_t *Len);
+static int8_t TEMPLATE_TransmitCplt(uint8_t *pbuf, uint32_t *Len, uint8_t epnum);
+
+USBD_CDC_ItfTypeDef USBD_CDC_Template_fops =
+{
+ TEMPLATE_Init,
+ TEMPLATE_DeInit,
+ TEMPLATE_Control,
+ TEMPLATE_Receive,
+ TEMPLATE_TransmitCplt
+};
+
+USBD_CDC_LineCodingTypeDef linecoding =
+{
+ 115200, /* baud rate*/
+ 0x00, /* stop bits-1*/
+ 0x00, /* parity - none*/
+ 0x08 /* nb. of bits 8*/
+};
+
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief TEMPLATE_Init
+ * Initializes the CDC media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_Init(void)
+{
+ /*
+ Add your initialization code here
+ */
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_DeInit
+ * DeInitializes the CDC media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_DeInit(void)
+{
+ /*
+ Add your deinitialization code here
+ */
+ return (0);
+}
+
+
+/**
+ * @brief TEMPLATE_Control
+ * Manage the CDC class requests
+ * @param Cmd: Command code
+ * @param Buf: Buffer containing command data (request parameters)
+ * @param Len: Number of data to be sent (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_Control(uint8_t cmd, uint8_t *pbuf, uint16_t length)
+{
+ switch (cmd)
+ {
+ case CDC_SEND_ENCAPSULATED_COMMAND:
+ /* Add your code here */
+ break;
+
+ case CDC_GET_ENCAPSULATED_RESPONSE:
+ /* Add your code here */
+ break;
+
+ case CDC_SET_COMM_FEATURE:
+ /* Add your code here */
+ break;
+
+ case CDC_GET_COMM_FEATURE:
+ /* Add your code here */
+ break;
+
+ case CDC_CLEAR_COMM_FEATURE:
+ /* Add your code here */
+ break;
+
+ case CDC_SET_LINE_CODING:
+ linecoding.bitrate = (uint32_t)(pbuf[0] | (pbuf[1] << 8) | \
+ (pbuf[2] << 16) | (pbuf[3] << 24));
+ linecoding.format = pbuf[4];
+ linecoding.paritytype = pbuf[5];
+ linecoding.datatype = pbuf[6];
+
+ /* Add your code here */
+ break;
+
+ case CDC_GET_LINE_CODING:
+ pbuf[0] = (uint8_t)(linecoding.bitrate);
+ pbuf[1] = (uint8_t)(linecoding.bitrate >> 8);
+ pbuf[2] = (uint8_t)(linecoding.bitrate >> 16);
+ pbuf[3] = (uint8_t)(linecoding.bitrate >> 24);
+ pbuf[4] = linecoding.format;
+ pbuf[5] = linecoding.paritytype;
+ pbuf[6] = linecoding.datatype;
+
+ /* Add your code here */
+ break;
+
+ case CDC_SET_CONTROL_LINE_STATE:
+ /* Add your code here */
+ break;
+
+ case CDC_SEND_BREAK:
+ /* Add your code here */
+ break;
+
+ default:
+ break;
+ }
+
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_Receive
+ * Data received over USB OUT endpoint are sent over CDC interface
+ * through this function.
+ *
+ * @note
+ * This function will issue a NAK packet on any OUT packet received on
+ * USB endpoint until exiting this function. If you exit this function
+ * before transfer is complete on CDC interface (ie. using DMA controller)
+ * it will result in receiving more data while previous ones are still
+ * not sent.
+ *
+ * @param Buf: Buffer of data to be received
+ * @param Len: Number of data received (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_Receive(uint8_t *Buf, uint32_t *Len)
+{
+ UNUSED(Buf);
+ UNUSED(Len);
+
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_TransmitCplt
+ * Data transmited callback
+ *
+ * @note
+ * This function is IN transfer complete callback used to inform user that
+ * the submitted Data is successfully sent over USB.
+ *
+ * @param Buf: Buffer of data to be received
+ * @param Len: Number of data received (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_TransmitCplt(uint8_t *Buf, uint32_t *Len, uint8_t epnum)
+{
+ UNUSED(Buf);
+ UNUSED(Len);
+ UNUSED(epnum);
+
+ return (0);
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Inc/usbd_cdc_ecm.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Inc/usbd_cdc_ecm.h
new file mode 100644
index 0000000000..f4bef2c718
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Inc/usbd_cdc_ecm.h
@@ -0,0 +1,255 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_ecm.h
+ * @author MCD Application Team
+ * @brief header file for the usbd_cdc_ecm.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_CDC_ECM_H
+#define __USB_CDC_ECM_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup usbd_cdc_ecm
+ * @brief This file is the Header file for usbd_cdc_ecm.c
+ * @{
+ */
+
+
+/** @defgroup usbd_cdc_ecm_Exported_Defines
+ * @{
+ */
+/* Comment this define in order to disable the CDC ECM Notification pipe */
+
+
+#define CDC_ECM_IN_EP 0x81U /* EP1 for data IN */
+#define CDC_ECM_OUT_EP 0x01U /* EP1 for data OUT */
+#define CDC_ECM_CMD_EP 0x82U /* EP2 for CDC ECM commands */
+
+#ifndef CDC_ECM_CMD_ITF_NBR
+#define CDC_ECM_CMD_ITF_NBR 0x00U /* Command Interface Number 0 */
+#endif /* CDC_ECM_CMD_ITF_NBR */
+
+#ifndef CDC_ECM_COM_ITF_NBR
+#define CDC_ECM_COM_ITF_NBR 0x01U /* Communication Interface Number 0 */
+#endif /* CDC_ECM_CMD_ITF_NBR */
+
+#ifndef CDC_ECM_HS_BINTERVAL
+#define CDC_ECM_HS_BINTERVAL 0x10U
+#endif /* CDC_ECM_HS_BINTERVAL */
+
+#ifndef CDC_ECM_FS_BINTERVAL
+#define CDC_ECM_FS_BINTERVAL 0x10U
+#endif /* CDC_ECM_FS_BINTERVAL */
+
+#ifndef USBD_SUPPORT_USER_STRING_DESC
+#define USBD_SUPPORT_USER_STRING_DESC 1U
+#endif /* USBD_SUPPORT_USER_STRING_DESC */
+
+/* CDC_ECM Endpoints parameters: you can fine tune these values depending on the needed baudrates and performance. */
+#define CDC_ECM_DATA_HS_MAX_PACKET_SIZE 512U /* Endpoint IN & OUT Packet size */
+#define CDC_ECM_DATA_FS_MAX_PACKET_SIZE 64U /* Endpoint IN & OUT Packet size */
+#define CDC_ECM_CMD_PACKET_SIZE 16U /* Control Endpoint Packet size */
+
+#define CDC_ECM_CONFIG_DESC_SIZ 79U
+
+#define CDC_ECM_DATA_HS_IN_PACKET_SIZE CDC_ECM_DATA_HS_MAX_PACKET_SIZE
+#define CDC_ECM_DATA_HS_OUT_PACKET_SIZE CDC_ECM_DATA_HS_MAX_PACKET_SIZE
+
+#define CDC_ECM_DATA_FS_IN_PACKET_SIZE CDC_ECM_DATA_FS_MAX_PACKET_SIZE
+#define CDC_ECM_DATA_FS_OUT_PACKET_SIZE CDC_ECM_DATA_FS_MAX_PACKET_SIZE
+
+/*---------------------------------------------------------------------*/
+/* CDC_ECM definitions */
+/*---------------------------------------------------------------------*/
+#define CDC_ECM_SEND_ENCAPSULATED_COMMAND 0x00U
+#define CDC_ECM_GET_ENCAPSULATED_RESPONSE 0x01U
+#define CDC_ECM_SET_ETH_MULTICAST_FILTERS 0x40U
+#define CDC_ECM_SET_ETH_PWRM_PATTERN_FILTER 0x41U
+#define CDC_ECM_GET_ETH_PWRM_PATTERN_FILTER 0x42U
+#define CDC_ECM_SET_ETH_PACKET_FILTER 0x43U
+#define CDC_ECM_GET_ETH_STATISTIC 0x44U
+
+#define CDC_ECM_NET_DISCONNECTED 0x00U
+#define CDC_ECM_NET_CONNECTED 0x01U
+
+
+/* Ethernet statistics definitions */
+#define CDC_ECM_XMIT_OK_VAL CDC_ECM_ETH_STATS_VAL_ENABLED
+#define CDC_ECM_XMIT_OK 0x01U
+#define CDC_ECM_RVC_OK 0x02U
+#define CDC_ECM_XMIT_ERROR 0x04U
+#define CDC_ECM_RCV_ERROR 0x08U
+#define CDC_ECM_RCV_NO_BUFFER 0x10U
+#define CDC_ECM_DIRECTED_BYTES_XMIT 0x20U
+#define CDC_ECM_DIRECTED_FRAMES_XMIT 0x40U
+#define CDC_ECM_MULTICAST_BYTES_XMIT 0x80U
+
+#define CDC_ECM_MULTICAST_FRAMES_XMIT 0x01U
+#define CDC_ECM_BROADCAST_BYTES_XMIT 0x02U
+#define CDC_ECM_BROADCAST_FRAMES_XMIT 0x04U
+#define CDC_ECM_DIRECTED_BYTES_RCV 0x08U
+#define CDC_ECM_DIRECTED_FRAMES_RCV 0x10U
+#define CDC_ECM_MULTICAST_BYTES_RCV 0x20U
+#define CDC_ECM_MULTICAST_FRAMES_RCV 0x40U
+#define CDC_ECM_BROADCAST_BYTES_RCV 0x80U
+
+#define CDC_ECM_BROADCAST_FRAMES_RCV 0x01U
+#define CDC_ECM_RCV_CRC_ERROR 0x02U
+#define CDC_ECM_TRANSMIT_QUEUE_LENGTH 0x04U
+#define CDC_ECM_RCV_ERROR_ALIGNMENT 0x08U
+#define CDC_ECM_XMIT_ONE_COLLISION 0x10U
+#define CDC_ECM_XMIT_MORE_COLLISIONS 0x20U
+#define CDC_ECM_XMIT_DEFERRED 0x40U
+#define CDC_ECM_XMIT_MAX_COLLISIONS 0x80U
+
+#define CDC_ECM_RCV_OVERRUN 0x40U
+#define CDC_ECM_XMIT_UNDERRUN 0x40U
+#define CDC_ECM_XMIT_HEARTBEAT_FAILURE 0x40U
+#define CDC_ECM_XMIT_TIMES_CRS_LOST 0x40U
+#define CDC_ECM_XMIT_LATE_COLLISIONS 0x40U
+
+#define CDC_ECM_ETH_STATS_RESERVED 0xE0U
+#define CDC_ECM_BMREQUEST_TYPE_ECM 0xA1U
+
+/* MAC String index */
+#define CDC_ECM_MAC_STRING_INDEX 6U
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+typedef struct
+{
+ int8_t (* Init)(void);
+ int8_t (* DeInit)(void);
+ int8_t (* Control)(uint8_t cmd, uint8_t *pbuf, uint16_t length);
+ int8_t (* Receive)(uint8_t *Buf, uint32_t *Len);
+ int8_t (* TransmitCplt)(uint8_t *Buf, uint32_t *Len, uint8_t epnum);
+ int8_t (* Process)(USBD_HandleTypeDef *pdev);
+ const uint8_t *pStrDesc;
+} USBD_CDC_ECM_ItfTypeDef;
+
+typedef struct
+{
+ uint8_t bmRequest;
+ uint8_t bRequest;
+ uint16_t wValue;
+ uint16_t wIndex;
+ uint16_t wLength;
+ uint8_t data[8];
+} USBD_CDC_ECM_NotifTypeDef;
+
+typedef struct
+{
+ uint32_t data[2000 / 4]; /* Force 32bits alignment */
+ uint8_t CmdOpCode;
+ uint8_t CmdLength;
+ uint8_t Reserved1; /* Reserved Byte to force 4 bytes alignment of following fields */
+ uint8_t Reserved2; /* Reserved Byte to force 4 bytes alignment of following fields */
+ uint8_t *RxBuffer;
+ uint8_t *TxBuffer;
+ uint32_t RxLength;
+ uint32_t TxLength;
+
+ __IO uint32_t TxState;
+ __IO uint32_t RxState;
+
+ __IO uint32_t MaxPcktLen;
+ __IO uint32_t LinkStatus;
+ __IO uint32_t NotificationStatus;
+ USBD_CDC_ECM_NotifTypeDef Req;
+} USBD_CDC_ECM_HandleTypeDef;
+
+typedef enum
+{
+ NETWORK_CONNECTION = 0x00,
+ RESPONSE_AVAILABLE = 0x01,
+ CONNECTION_SPEED_CHANGE = 0x2A
+} USBD_CDC_ECM_NotifCodeTypeDef;
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_CDC_ECM;
+#define USBD_CDC_ECM_CLASS &USBD_CDC_ECM
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+uint8_t USBD_CDC_ECM_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_CDC_ECM_ItfTypeDef *fops);
+
+uint8_t USBD_CDC_ECM_SetTxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff,
+ uint32_t length);
+
+uint8_t USBD_CDC_ECM_SetRxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff);
+
+uint8_t USBD_CDC_ECM_ReceivePacket(USBD_HandleTypeDef *pdev);
+
+uint8_t USBD_CDC_ECM_TransmitPacket(USBD_HandleTypeDef *pdev);
+
+uint8_t USBD_CDC_ECM_SendNotification(USBD_HandleTypeDef *pdev,
+ USBD_CDC_ECM_NotifCodeTypeDef Notif,
+ uint16_t bVal, uint8_t *pData);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_CDC_ECM_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Inc/usbd_cdc_ecm_if_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Inc/usbd_cdc_ecm_if_template.h
new file mode 100644
index 0000000000..7ce8714dfb
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Inc/usbd_cdc_ecm_if_template.h
@@ -0,0 +1,82 @@
+/**
+ ******************************************************************************
+ * @file Inc/usbd_cdc_ecm_if_template.h
+ * @author MCD Application Team
+ * @brief Header for usbd_cdc_ecm_if_template.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CDC_ECM_IF_H
+#define __USBD_CDC_ECM_IF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc_ecm.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* Ensure this MAC address value is same as MAC_ADDRx declared in STM32xxx_conf.h */
+#define CDC_ECM_MAC_STR_DESC (uint8_t *)"000202030000"
+#define CDC_ECM_MAC_ADDR0 0x00U /* 01 */
+#define CDC_ECM_MAC_ADDR1 0x02U /* 02 */
+#define CDC_ECM_MAC_ADDR2 0x02U /* 03 */
+#define CDC_ECM_MAC_ADDR3 0x03U /* 00 */
+#define CDC_ECM_MAC_ADDR4 0x00U /* 00 */
+#define CDC_ECM_MAC_ADDR5 0x00U /* 00 */
+
+/* Max Number of Trials waiting for Tx ready */
+#define CDC_ECM_MAX_TX_WAIT_TRIALS 1000000U
+
+#define CDC_ECM_ETH_STATS_BYTE0 0U
+/*(uint8_t)(CDC_ECM_XMIT_OK_VAL | CDC_ECM_RVC_OK_VAL | CDC_ECM_XMIT_ERROR_VAL | \
+ CDC_ECM_RCV_ERROR_VAL | CDC_ECM_RCV_NO_BUFFER_VAL | CDC_ECM_DIRECTED_BYTES_XMIT_VAL | \
+ CDC_ECM_DIRECTED_FRAMES_XMIT_VAL | CDC_ECM_MULTICAST_BYTES_XMIT_VAL) */
+
+#define CDC_ECM_ETH_STATS_BYTE1 0U
+/*(uint8_t)(CDC_ECM_MULTICAST_FRAMES_XMIT_VAL | CDC_ECM_BROADCAST_BYTES_XMIT_VAL | \
+ CDC_ECM_BROADCAST_FRAMES_XMIT_VAL | CDC_ECM_DIRECTED_BYTES_RCV_VAL | \
+ CDC_ECM_DIRECTED_FRAMES_RCV_VAL | CDC_ECM_MULTICAST_BYTES_RCV_VAL | \
+ CDC_ECM_MULTICAST_FRAMES_RCV_VAL | CDC_ECM_BROADCAST_BYTES_RCV_VAL) */
+
+#define CDC_ECM_ETH_STATS_BYTE2 0U
+/*(uint8_t)(CDC_ECM_BROADCAST_FRAMES_RCV_VAL | CDC_ECM_RCV_CRC_ERROR_VAL | \
+ CDC_ECM_TRANSMIT_QUEUE_LENGTH_VAL | CDC_ECM_RCV_ERROR_ALIGNMENT_VAL | \
+ CDC_ECM_XMIT_ONE_COLLISION_VAL | CDC_ECM_XMIT_MORE_COLLISIONS_VAL | \
+ CDC_ECM_XMIT_DEFERRED_VAL | CDC_ECM_XMIT_MAX_COLLISIONS_VAL) */
+
+#define CDC_ECM_ETH_STATS_BYTE3 0U
+/*(uint8_t)(CDC_ECM_RCV_OVERRUN_VAL | CDC_ECM_XMIT_UNDERRUN_VAL | CDC_ECM_XMIT_HEARTBEAT_FAILURE_VAL | \
+ CDC_ECM_XMIT_TIMES_CRS_LOST_VAL | CDC_ECM_XMIT_LATE_COLLISIONS_VAL | CDC_ECM_ETH_STATS_RESERVED) */
+
+/* Ethernet Maximum Segment size, typically 1514 bytes */
+#define CDC_ECM_ETH_MAX_SEGSZE 1514U
+
+/* Number of Ethernet multicast filters */
+#define CDC_ECM_ETH_NBR_MACFILTERS 0U
+
+/* Number of wakeup power filters */
+#define CDC_ECM_ETH_NBR_PWRFILTERS 0U
+
+
+#define CDC_ECM_CONNECT_SPEED_UPSTREAM 0x004C4B40U /* 5Mbps */
+#define CDC_ECM_CONNECT_SPEED_DOWNSTREAM 0x004C4B40U /* 5Mbps */
+
+extern USBD_CDC_ECM_ItfTypeDef USBD_CDC_ECM_fops;
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+#endif /* __USBD_CDC_ECM_IF_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Src/usbd_cdc_ecm.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Src/usbd_cdc_ecm.c
new file mode 100644
index 0000000000..edc5d220d0
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Src/usbd_cdc_ecm.c
@@ -0,0 +1,1091 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_ecm.c
+ * @author MCD Application Team
+ * @brief This file provides the high layer firmware functions to manage the
+ * following functionalities of the USB CDC_ECM Class:
+ * - Initialization and Configuration of high and low layer
+ * - Enumeration as CDC_ECM Device (and enumeration for each implemented memory interface)
+ * - OUT/IN data transfer
+ * - Command IN transfer (class requests management)
+ * - Error management
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc_ecm.h"
+#include "usbd_ctlreq.h"
+
+#ifndef __USBD_CDC_ECM_IF_H
+#include "usbd_cdc_ecm_if_template.h"
+#endif
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_CDC_ECM
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_CDC_ECM_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_ECM_Private_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_ECM_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_ECM_Private_FunctionPrototypes
+ * @{
+ */
+
+static uint8_t USBD_CDC_ECM_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_CDC_ECM_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_CDC_ECM_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_CDC_ECM_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_CDC_ECM_EP0_RxReady(USBD_HandleTypeDef *pdev);
+static uint8_t USBD_CDC_ECM_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req);
+
+static uint8_t *USBD_CDC_ECM_GetFSCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_ECM_GetHSCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_ECM_GetOtherSpeedCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_ECM_GetOtherSpeedCfgDesc(uint16_t *length);
+
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+static uint8_t *USBD_CDC_ECM_USRStringDescriptor(USBD_HandleTypeDef *pdev,
+ uint8_t index, uint16_t *length);
+#endif
+
+uint8_t *USBD_CDC_ECM_GetDeviceQualifierDescriptor(uint16_t *length);
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_ECM_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x40,
+ 0x01,
+ 0x00,
+};
+
+static uint32_t ConnSpeedTab[2] = {CDC_ECM_CONNECT_SPEED_UPSTREAM,
+ CDC_ECM_CONNECT_SPEED_DOWNSTREAM};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_ECM_Private_Variables
+ * @{
+ */
+
+
+/* CDC_ECM interface class callbacks structure */
+USBD_ClassTypeDef USBD_CDC_ECM =
+{
+ USBD_CDC_ECM_Init,
+ USBD_CDC_ECM_DeInit,
+ USBD_CDC_ECM_Setup,
+ NULL, /* EP0_TxSent, */
+ USBD_CDC_ECM_EP0_RxReady,
+ USBD_CDC_ECM_DataIn,
+ USBD_CDC_ECM_DataOut,
+ NULL,
+ NULL,
+ NULL,
+ USBD_CDC_ECM_GetHSCfgDesc,
+ USBD_CDC_ECM_GetFSCfgDesc,
+ USBD_CDC_ECM_GetOtherSpeedCfgDesc,
+ USBD_CDC_ECM_GetDeviceQualifierDescriptor,
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+ USBD_CDC_ECM_USRStringDescriptor,
+#endif
+};
+
+/* USB CDC_ECM device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_ECM_CfgHSDesc[] __ALIGN_END =
+{
+ /* Configuration Descriptor */
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ LOBYTE(CDC_ECM_CONFIG_DESC_SIZ), /* wTotalLength:no of returned bytes */
+ HIBYTE(CDC_ECM_CONFIG_DESC_SIZ),
+ 0x02, /* bNumInterfaces: 2 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: self powered */
+ 0x32, /* MaxPower 0 mA */
+
+ /*---------------------------------------------------------------------------*/
+
+ /* IAD descriptor */
+ 0x08, /* bLength */
+ 0x0B, /* bDescriptorType */
+ 0x00, /* bFirstInterface */
+ 0x02, /* bInterfaceCount */
+ 0x02, /* bFunctionClass (Wireless Controller) */
+ 0x06, /* bFunctionSubClass */
+ 0x00, /* bFunctionProtocol */
+ 0x00, /* iFunction */
+
+ /* Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ CDC_ECM_CMD_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoint used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x06, /* bInterfaceSubClass: Ethernet Control Model */
+ 0x00, /* bInterfaceProtocol: No specific protocol required */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header functional descriptor */
+ 0x10, /* bcd CDC_ECM: spec release number: 1.10 */
+ 0x01,
+
+ /* CDC_ECM Functional Descriptor */
+ 0x0D, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x0F, /* Ethernet Networking functional descriptor subtype */
+ CDC_ECM_MAC_STRING_INDEX, /* Device's MAC string index */
+ CDC_ECM_ETH_STATS_BYTE3, /* Ethernet statistics byte 3 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE2, /* Ethernet statistics byte 2 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE1, /* Ethernet statistics byte 1 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE0, /* Ethernet statistics byte 0 (bitmap) */
+ LOBYTE(CDC_ECM_ETH_MAX_SEGSZE),
+ HIBYTE(CDC_ECM_ETH_MAX_SEGSZE), /* wMaxSegmentSize: Ethernet Maximum Segment size, typically 1514 bytes */
+ LOBYTE(CDC_ECM_ETH_NBR_MACFILTERS),
+ HIBYTE(CDC_ECM_ETH_NBR_MACFILTERS), /* wNumberMCFilters: the number of multicast filters */
+ CDC_ECM_ETH_NBR_PWRFILTERS, /* bNumberPowerFilters: the number of wakeup power filters */
+
+ /* Union Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union functional descriptor */
+ 0x00, /* bMasterInterface: Communication class interface */
+ 0x01, /* bSlaveInterface0: Data Class Interface */
+
+ /* Communication Endpoint Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_ECM_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_ECM_CMD_PACKET_SIZE),
+ CDC_ECM_HS_BINTERVAL, /* bInterval */
+
+ /*----------------------*/
+
+ /* Data class interface descriptor */
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ CDC_ECM_COM_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /* Endpoint OUT Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_ECM_DATA_HS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_ECM_DATA_HS_MAX_PACKET_SIZE),
+ 0xFF, /* bInterval: ignore for Bulk transfer */
+
+ /* Endpoint IN Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_ECM_DATA_HS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_ECM_DATA_HS_MAX_PACKET_SIZE),
+ 0xFF /* bInterval: ignore for Bulk transfer */
+};
+
+
+/* USB CDC_ECM device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_ECM_CfgFSDesc[] __ALIGN_END =
+{
+ /* Configuration Descriptor */
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ LOBYTE(CDC_ECM_CONFIG_DESC_SIZ), /* wTotalLength: Total size of the Config descriptor */
+ HIBYTE(CDC_ECM_CONFIG_DESC_SIZ),
+ 0x02, /* bNumInterfaces: 2 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: self powered */
+ 0x32, /* MaxPower 0 mA */
+
+ /*---------------------------------------------------------------------------*/
+ /* IAD descriptor */
+ 0x08, /* bLength */
+ 0x0B, /* bDescriptorType */
+ 0x00, /* bFirstInterface */
+ 0x02, /* bInterfaceCount */
+ 0x02, /* bFunctionClass (Wireless Controller) */
+ 0x06, /* bFunctionSubClass */
+ 0x00, /* bFunctionProtocol */
+ 0x00, /* iFunction */
+
+ /* Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ CDC_ECM_CMD_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoint used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x06, /* bInterfaceSubClass: Ethernet Control Model */
+ 0x00, /* bInterfaceProtocol: No specific protocol required */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header functional descriptor */
+ 0x10, /* bcd CDC_ECM : spec release number: 1.20 */
+ 0x01,
+
+ /* Union Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union functional descriptor */
+ CDC_ECM_CMD_ITF_NBR, /* bMasterInterface: Communication class interface */
+ CDC_ECM_COM_ITF_NBR, /* bSlaveInterface0: Data Class Interface */
+
+ /* CDC_ECM Functional Descriptor */
+ 0x0D, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x0F, /* Ethernet Networking functional descriptor subtype */
+ CDC_ECM_MAC_STRING_INDEX, /* Device's MAC string index */
+ CDC_ECM_ETH_STATS_BYTE3, /* Ethernet statistics byte 3 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE2, /* Ethernet statistics byte 2 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE1, /* Ethernet statistics byte 1 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE0, /* Ethernet statistics byte 0 (bitmap) */
+ LOBYTE(CDC_ECM_ETH_MAX_SEGSZE),
+ HIBYTE(CDC_ECM_ETH_MAX_SEGSZE), /* wMaxSegmentSize: Ethernet Maximum Segment size, typically 1514 bytes */
+ LOBYTE(CDC_ECM_ETH_NBR_MACFILTERS),
+ HIBYTE(CDC_ECM_ETH_NBR_MACFILTERS), /* wNumberMCFilters: the number of multicast filters */
+ CDC_ECM_ETH_NBR_PWRFILTERS, /* bNumberPowerFilters: the number of wakeup power filters */
+
+
+ /* Communication Endpoint Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_ECM_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_ECM_CMD_PACKET_SIZE),
+ CDC_ECM_FS_BINTERVAL, /* bInterval */
+
+ /*----------------------*/
+
+ /* Data class interface descriptor */
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ CDC_ECM_COM_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC_ECM */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /* Endpoint OUT Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_ECM_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_ECM_DATA_FS_MAX_PACKET_SIZE),
+ 0xFF, /* bInterval: ignore for Bulk transfer */
+
+ /* Endpoint IN Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_ECM_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_ECM_DATA_FS_MAX_PACKET_SIZE),
+ 0xFF /* bInterval: ignore for Bulk transfer */
+} ;
+
+__ALIGN_BEGIN static uint8_t USBD_CDC_ECM_OtherSpeedCfgDesc[] __ALIGN_END =
+{
+ /* Configuration Descriptor */
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ LOBYTE(CDC_ECM_CONFIG_DESC_SIZ), /* wTotalLength:no of returned bytes */
+ HIBYTE(CDC_ECM_CONFIG_DESC_SIZ),
+ 0x02, /* bNumInterfaces: 2 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x04, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: self powered */
+ 0x32, /* MaxPower 0 mA */
+
+ /*--------------------------------------- ------------------------------------*/
+ /* IAD descriptor */
+ 0x08, /* bLength */
+ 0x0B, /* bDescriptorType */
+ 0x00, /* bFirstInterface */
+ 0x02, /* bInterfaceCount */
+ 0x02, /* bFunctionClass (Wireless Controller) */
+ 0x06, /* bFunctionSubClass */
+ 0x00, /* bFunctionProtocol */
+ 0x00, /* iFunction */
+
+ /* Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoint used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x06, /* bInterfaceSubClass: Ethernet Control Model */
+ 0x00, /* bInterfaceProtocol: No specific protocol required */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header functional descriptor */
+ 0x10, /* bcd CDC_ECM : spec release number: 1.20 */
+ 0x01,
+
+ /* CDC_ECM Functional Descriptor */
+ 0x0D, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x0F, /* Ethernet Networking functional descriptor subtype */
+ CDC_ECM_MAC_STRING_INDEX, /* Device's MAC string index */
+ CDC_ECM_ETH_STATS_BYTE3, /* Ethernet statistics byte 3 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE2, /* Ethernet statistics byte 2 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE1, /* Ethernet statistics byte 1 (bitmap) */
+ CDC_ECM_ETH_STATS_BYTE0, /* Ethernet statistics byte 0 (bitmap) */
+ LOBYTE(CDC_ECM_ETH_MAX_SEGSZE),
+ HIBYTE(CDC_ECM_ETH_MAX_SEGSZE), /* wMaxSegmentSize: Ethernet Maximum Segment size, typically 1514 bytes */
+ LOBYTE(CDC_ECM_ETH_NBR_MACFILTERS),
+ HIBYTE(CDC_ECM_ETH_NBR_MACFILTERS), /* wNumberMCFilters: the number of multicast filters */
+ CDC_ECM_ETH_NBR_PWRFILTERS, /* bNumberPowerFilters: the number of wakeup power filters */
+
+ /* Union Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union functional descriptor */
+ 0x00, /* bMasterInterface: Communication class interface */
+ 0x01, /* bSlaveInterface0: Data Class Interface */
+
+ /* Communication Endpoint Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_ECM_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_ECM_CMD_PACKET_SIZE),
+ CDC_ECM_FS_BINTERVAL, /* bInterval */
+
+ /*----------------------*/
+
+ /* Data class interface descriptor */
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ 0x01, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /* Endpoint OUT Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ 0x40, /* wMaxPacketSize: */
+ 0x00,
+ 0xFF, /* bInterval: ignore for Bulk transfer */
+
+ /* Endpoint IN Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_ECM_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ 0x40, /* wMaxPacketSize: */
+ 0x00,
+ 0xFF /* bInterval: ignore for Bulk transfer */
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_ECM_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_CDC_ECM_Init
+ * Initialize the CDC_ECM interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_CDC_ECM_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ USBD_CDC_ECM_HandleTypeDef *hcdc;
+
+ hcdc = USBD_malloc(sizeof(USBD_CDC_ECM_HandleTypeDef));
+
+ if (hcdc == NULL)
+ {
+ pdev->pClassData = NULL;
+ return (uint8_t)USBD_EMEM;
+ }
+
+ pdev->pClassData = (void *)hcdc;
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, CDC_ECM_IN_EP, USBD_EP_TYPE_BULK,
+ CDC_ECM_DATA_HS_IN_PACKET_SIZE);
+
+ pdev->ep_in[CDC_ECM_IN_EP & 0xFU].is_used = 1U;
+
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, CDC_ECM_OUT_EP, USBD_EP_TYPE_BULK,
+ CDC_ECM_DATA_HS_OUT_PACKET_SIZE);
+
+ pdev->ep_out[CDC_ECM_OUT_EP & 0xFU].is_used = 1U;
+
+ /* Set bInterval for CDC ECM CMD Endpoint */
+ pdev->ep_in[CDC_ECM_CMD_EP & 0xFU].bInterval = CDC_ECM_HS_BINTERVAL;
+ }
+ else
+ {
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, CDC_ECM_IN_EP, USBD_EP_TYPE_BULK,
+ CDC_ECM_DATA_FS_IN_PACKET_SIZE);
+
+ pdev->ep_in[CDC_ECM_IN_EP & 0xFU].is_used = 1U;
+
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, CDC_ECM_OUT_EP, USBD_EP_TYPE_BULK,
+ CDC_ECM_DATA_FS_OUT_PACKET_SIZE);
+
+ pdev->ep_out[CDC_ECM_OUT_EP & 0xFU].is_used = 1U;
+
+ /* Set bInterval for CDC ECM CMD Endpoint */
+ pdev->ep_in[CDC_ECM_CMD_EP & 0xFU].bInterval = CDC_ECM_FS_BINTERVAL;
+ }
+
+ /* Open Command IN EP */
+ (void)USBD_LL_OpenEP(pdev, CDC_ECM_CMD_EP, USBD_EP_TYPE_INTR, CDC_ECM_CMD_PACKET_SIZE);
+ pdev->ep_in[CDC_ECM_CMD_EP & 0xFU].is_used = 1U;
+
+ /* Init physical Interface components */
+ ((USBD_CDC_ECM_ItfTypeDef *)pdev->pUserData)->Init();
+
+ /* Init Xfer states */
+ hcdc->TxState = 0U;
+ hcdc->RxState = 0U;
+ hcdc->RxLength = 0U;
+ hcdc->TxLength = 0U;
+ hcdc->LinkStatus = 0U;
+ hcdc->NotificationStatus = 0U;
+ hcdc->MaxPcktLen = (pdev->dev_speed == USBD_SPEED_HIGH) ? CDC_ECM_DATA_HS_MAX_PACKET_SIZE : CDC_ECM_DATA_FS_MAX_PACKET_SIZE;
+
+ /* Prepare Out endpoint to receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_ECM_OUT_EP, hcdc->RxBuffer, hcdc->MaxPcktLen);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_ECM_DeInit
+ * DeInitialize the CDC_ECM layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_CDC_ECM_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ /* Close EP IN */
+ (void)USBD_LL_CloseEP(pdev, CDC_ECM_IN_EP);
+ pdev->ep_in[CDC_ECM_IN_EP & 0xFU].is_used = 0U;
+
+ /* Close EP OUT */
+ (void)USBD_LL_CloseEP(pdev, CDC_ECM_OUT_EP);
+ pdev->ep_out[CDC_ECM_OUT_EP & 0xFU].is_used = 0U;
+
+ /* Close Command IN EP */
+ (void)USBD_LL_CloseEP(pdev, CDC_ECM_CMD_EP);
+ pdev->ep_in[CDC_ECM_CMD_EP & 0xFU].is_used = 0U;
+ pdev->ep_in[CDC_ECM_CMD_EP & 0xFU].bInterval = 0U;
+
+ /* DeInit physical Interface components */
+ if (pdev->pClassData != NULL)
+ {
+ ((USBD_CDC_ECM_ItfTypeDef *)pdev->pUserData)->DeInit();
+ USBD_free(pdev->pClassData);
+ pdev->pClassData = NULL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_ECM_Setup
+ * Handle the CDC_ECM specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_CDC_ECM_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *) pdev->pClassData;
+ USBD_CDC_ECM_ItfTypeDef *EcmInterface = (USBD_CDC_ECM_ItfTypeDef *)pdev->pUserData;
+ USBD_StatusTypeDef ret = USBD_OK;
+ uint8_t ifalt = 0U;
+ uint16_t status_info = 0U;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS :
+ if (req->wLength != 0U)
+ {
+ if ((req->bmRequest & 0x80U) != 0U)
+ {
+ EcmInterface->Control(req->bRequest,
+ (uint8_t *)hcdc->data, req->wLength);
+
+ (void)USBD_CtlSendData(pdev, (uint8_t *)hcdc->data, req->wLength);
+ }
+ else
+ {
+ hcdc->CmdOpCode = req->bRequest;
+ hcdc->CmdLength = (uint8_t)req->wLength;
+
+ (void)USBD_CtlPrepareRx(pdev, (uint8_t *)hcdc->data, req->wLength);
+ }
+ }
+ else
+ {
+ EcmInterface->Control(req->bRequest, (uint8_t *)req, 0U);
+ }
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, &ifalt, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ if (pdev->dev_state != USBD_STATE_CONFIGURED)
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+/**
+ * @brief USBD_CDC_ECM_DataIn
+ * Data sent on non-control IN endpoint
+ * @param pdev: device instance
+ * @param epnum: endpoint number
+ * @retval status
+ */
+static uint8_t USBD_CDC_ECM_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *)pdev->pClassData;
+ PCD_HandleTypeDef *hpcd = pdev->pData;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ if (epnum == (CDC_ECM_IN_EP & 0x7FU))
+ {
+ if ((pdev->ep_in[epnum].total_length > 0U) &&
+ ((pdev->ep_in[epnum].total_length % hpcd->IN_ep[epnum].maxpacket) == 0U))
+ {
+ /* Update the packet total length */
+ pdev->ep_in[epnum].total_length = 0U;
+
+ /* Send ZLP */
+ (void)USBD_LL_Transmit(pdev, epnum, NULL, 0U);
+ }
+ else
+ {
+ hcdc->TxState = 0U;
+ ((USBD_CDC_ECM_ItfTypeDef *)pdev->pUserData)->TransmitCplt(hcdc->TxBuffer, &hcdc->TxLength, epnum);
+ }
+ }
+ else if (epnum == (CDC_ECM_CMD_EP & 0x7FU))
+ {
+ if (hcdc->NotificationStatus != 0U)
+ {
+ (void)USBD_CDC_ECM_SendNotification(pdev, CONNECTION_SPEED_CHANGE,
+ 0U, (uint8_t *)ConnSpeedTab);
+
+ hcdc->NotificationStatus = 0U;
+ }
+ }
+ else
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_ECM_DataOut
+ * Data received on non-control Out endpoint
+ * @param pdev: device instance
+ * @param epnum: endpoint number
+ * @retval status
+ */
+static uint8_t USBD_CDC_ECM_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *)pdev->pClassData;
+ uint32_t CurrPcktLen;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ if (epnum == CDC_ECM_OUT_EP)
+ {
+ /* Get the received data length */
+ CurrPcktLen = USBD_LL_GetRxDataSize(pdev, epnum);
+
+ /* Increment the frame length */
+ hcdc->RxLength += CurrPcktLen;
+
+ /* If the buffer size is less than max packet size: it is the last packet in current frame */
+ if ((CurrPcktLen < hcdc->MaxPcktLen) || (hcdc->RxLength >= CDC_ECM_ETH_MAX_SEGSZE))
+ {
+ /* USB data will be immediately processed, this allow next USB traffic being
+ NACKed till the end of the application Xfer */
+
+ /* Process data by application (ie. copy to app buffer or notify user)
+ hcdc->RxLength must be reset to zero at the end of the call of this function */
+ ((USBD_CDC_ECM_ItfTypeDef *)pdev->pUserData)->Receive(hcdc->RxBuffer, &hcdc->RxLength);
+ }
+ else
+ {
+ /* Prepare Out endpoint to receive next packet in current/new frame */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_ECM_OUT_EP,
+ (uint8_t *)(hcdc->RxBuffer + hcdc->RxLength),
+ hcdc->MaxPcktLen);
+ }
+ }
+ else
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_ECM_EP0_RxReady
+ * Handle EP0 Rx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_CDC_ECM_EP0_RxReady(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *)pdev->pClassData;
+
+ if ((pdev->pUserData != NULL) && (hcdc->CmdOpCode != 0xFFU))
+ {
+ ((USBD_CDC_ECM_ItfTypeDef *)pdev->pUserData)->Control(hcdc->CmdOpCode,
+ (uint8_t *)hcdc->data,
+ (uint16_t)hcdc->CmdLength);
+ hcdc->CmdOpCode = 0xFFU;
+
+ }
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_ECM_GetFSCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_ECM_GetFSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CDC_ECM_CfgFSDesc);
+
+ return USBD_CDC_ECM_CfgFSDesc;
+}
+
+/**
+ * @brief USBD_CDC_ECM_GetHSCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_ECM_GetHSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t) sizeof(USBD_CDC_ECM_CfgHSDesc);
+
+ return USBD_CDC_ECM_CfgHSDesc;
+}
+
+/**
+ * @brief USBD_CDC_ECM_GetCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_ECM_GetOtherSpeedCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CDC_ECM_OtherSpeedCfgDesc);
+
+ return USBD_CDC_ECM_OtherSpeedCfgDesc;
+}
+
+/**
+ * @brief DeviceQualifierDescriptor
+ * return Device Qualifier descriptor
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+uint8_t *USBD_CDC_ECM_GetDeviceQualifierDescriptor(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CDC_ECM_DeviceQualifierDesc);
+
+ return USBD_CDC_ECM_DeviceQualifierDesc;
+}
+
+/**
+ * @brief USBD_CDC_ECM_RegisterInterface
+ * @param pdev: device instance
+ * @param fops: CD Interface callback
+ * @retval status
+ */
+uint8_t USBD_CDC_ECM_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_CDC_ECM_ItfTypeDef *fops)
+{
+ if (fops == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ pdev->pUserData = fops;
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_ECM_USRStringDescriptor
+ * Manages the transfer of user string descriptors.
+ * @param speed : current device speed
+ * @param index: descriptor index
+ * @param length : pointer data length
+ * @retval pointer to the descriptor table or NULL if the descriptor is not supported.
+ */
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+static uint8_t *USBD_CDC_ECM_USRStringDescriptor(USBD_HandleTypeDef *pdev, uint8_t index, uint16_t *length)
+{
+ static uint8_t USBD_StrDesc[255];
+
+ /* Check if the requested string interface is supported */
+ if (index == CDC_ECM_MAC_STRING_INDEX)
+ {
+ USBD_GetString((uint8_t *)((USBD_CDC_ECM_ItfTypeDef *)pdev->pUserData)->pStrDesc, USBD_StrDesc, length);
+ return USBD_StrDesc;
+ }
+ /* Not supported Interface Descriptor index */
+ else
+ {
+ return NULL;
+ }
+}
+#endif
+
+/**
+ * @brief USBD_CDC_ECM_SetTxBuffer
+ * @param pdev: device instance
+ * @param pbuff: Tx Buffer
+ * @retval status
+ */
+uint8_t USBD_CDC_ECM_SetTxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff, uint32_t length)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *)pdev->pClassData;
+
+ hcdc->TxBuffer = pbuff;
+ hcdc->TxLength = length;
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_ECM_SetRxBuffer
+ * @param pdev: device instance
+ * @param pbuff: Rx Buffer
+ * @retval status
+ */
+uint8_t USBD_CDC_ECM_SetRxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *)pdev->pClassData;
+
+ hcdc->RxBuffer = pbuff;
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_ECM_TransmitPacket
+ * Transmit packet on IN endpoint
+ * @param pdev: device instance
+ * @retval status
+ */
+uint8_t USBD_CDC_ECM_TransmitPacket(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *)pdev->pClassData;
+ USBD_StatusTypeDef ret = USBD_BUSY;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ if (hcdc->TxState == 0U)
+ {
+ /* Tx Transfer in progress */
+ hcdc->TxState = 1U;
+
+ /* Update the packet total length */
+ pdev->ep_in[CDC_ECM_IN_EP & 0xFU].total_length = hcdc->TxLength;
+
+ /* Transmit next packet */
+ (void)USBD_LL_Transmit(pdev, CDC_ECM_IN_EP, hcdc->TxBuffer, hcdc->TxLength);
+
+ ret = USBD_OK;
+ }
+
+ return (uint8_t)ret;
+}
+
+
+/**
+ * @brief USBD_CDC_ECM_ReceivePacket
+ * prepare OUT Endpoint for reception
+ * @param pdev: device instance
+ * @retval status
+ */
+uint8_t USBD_CDC_ECM_ReceivePacket(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *)pdev->pClassData;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ /* Prepare Out endpoint to receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_ECM_OUT_EP,hcdc->RxBuffer, hcdc->MaxPcktLen);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_ECM_SendNotification
+ * Transmit Notification packet on CMD IN interrupt endpoint
+ * @param pdev: device instance
+ * Notif: value of the notification type (from CDC_ECM_Notification_TypeDef enumeration list)
+ * bVal: value of the notification switch (ie. 0x00 or 0x01 for Network Connection notification)
+ * pData: pointer to data buffer (ie. upstream and downstream connection speed values)
+ * @retval status
+ */
+uint8_t USBD_CDC_ECM_SendNotification(USBD_HandleTypeDef *pdev,
+ USBD_CDC_ECM_NotifCodeTypeDef Notif,
+ uint16_t bVal, uint8_t *pData)
+{
+ uint32_t Idx;
+ uint32_t ReqSize = 0U;
+ USBD_CDC_ECM_HandleTypeDef *hcdc = (USBD_CDC_ECM_HandleTypeDef *)pdev->pClassData;
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ /* Initialize the request fields */
+ (hcdc->Req).bmRequest = CDC_ECM_BMREQUEST_TYPE_ECM;
+ (hcdc->Req).bRequest = (uint8_t)Notif;
+
+ switch (Notif)
+ {
+ case NETWORK_CONNECTION:
+ (hcdc->Req).wValue = bVal;
+ (hcdc->Req).wIndex = CDC_ECM_CMD_ITF_NBR;
+ (hcdc->Req).wLength = 0U;
+
+ for (Idx = 0U; Idx < 8U; Idx++)
+ {
+ (hcdc->Req).data[Idx] = 0U;
+ }
+ ReqSize = 8U;
+ break;
+
+ case RESPONSE_AVAILABLE:
+ (hcdc->Req).wValue = 0U;
+ (hcdc->Req).wIndex = CDC_ECM_CMD_ITF_NBR;
+ (hcdc->Req).wLength = 0U;
+ for (Idx = 0U; Idx < 8U; Idx++)
+ {
+ (hcdc->Req).data[Idx] = 0U;
+ }
+ ReqSize = 8U;
+ break;
+
+ case CONNECTION_SPEED_CHANGE:
+ (hcdc->Req).wValue = 0U;
+ (hcdc->Req).wIndex = CDC_ECM_CMD_ITF_NBR;
+ (hcdc->Req).wLength = 0x0008U;
+ ReqSize = 16U;
+
+ /* Check pointer to data buffer */
+ if (pData != NULL)
+ {
+ for (Idx = 0U; Idx < 8U; Idx++)
+ {
+ (hcdc->Req).data[Idx] = pData[Idx];
+ }
+ }
+ break;
+
+ default:
+ ret = USBD_FAIL;
+ break;
+ }
+
+ /* Transmit notification packet */
+ if (ReqSize != 0U)
+ {
+ (void)USBD_LL_Transmit(pdev, CDC_ECM_CMD_EP, (uint8_t *)&(hcdc->Req), ReqSize);
+ }
+
+ return (uint8_t)ret;
+}
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Src/usbd_cdc_ecm_if_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Src/usbd_cdc_ecm_if_template.c
new file mode 100644
index 0000000000..9b96de8b4e
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_ECM/Src/usbd_cdc_ecm_if_template.c
@@ -0,0 +1,247 @@
+/**
+ ******************************************************************************
+ * @file Src/usbd_cdc_ecm_if_template.c
+ * @author MCD Application Team
+ * @brief Source file for USBD CDC_ECM interface
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+
+#include "main.h"
+/*
+
+ Include here LwIP files if used
+
+*/
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #pragma data_alignment=4
+#endif
+__ALIGN_BEGIN static uint8_t UserRxBuffer[CDC_ECM_ETH_MAX_SEGSZE + 100]__ALIGN_END; /* Received Data over USB are stored in this buffer */
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #pragma data_alignment=4
+#endif
+__ALIGN_BEGIN static uint8_t UserTxBuffer[CDC_ECM_ETH_MAX_SEGSZE + 100]__ALIGN_END; /* Received Data over CDC_ECM (CDC_ECM interface) are stored in this buffer */
+
+static uint8_t CDC_ECMInitialized = 0U;
+
+/* USB handler declaration */
+extern USBD_HandleTypeDef USBD_Device;
+
+/* Private function prototypes -----------------------------------------------*/
+static int8_t CDC_ECM_Itf_Init(void);
+static int8_t CDC_ECM_Itf_DeInit(void);
+static int8_t CDC_ECM_Itf_Control(uint8_t cmd, uint8_t *pbuf, uint16_t length);
+static int8_t CDC_ECM_Itf_Receive(uint8_t *pbuf, uint32_t *Len);
+static int8_t CDC_ECM_Itf_TransmitCplt(uint8_t *pbuf, uint32_t *Len, uint8_t epnum);
+static int8_t CDC_ECM_Itf_Process(USBD_HandleTypeDef *pdev);
+
+USBD_CDC_ECM_ItfTypeDef USBD_CDC_ECM_fops =
+{
+ CDC_ECM_Itf_Init,
+ CDC_ECM_Itf_DeInit,
+ CDC_ECM_Itf_Control,
+ CDC_ECM_Itf_Receive,
+ CDC_ECM_Itf_TransmitCplt,
+ CDC_ECM_Itf_Process,
+ (uint8_t *)CDC_ECM_MAC_STR_DESC,
+};
+
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief CDC_ECM_Itf_Init
+ * Initializes the CDC_ECM media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_ECM_Itf_Init(void)
+{
+ if (CDC_ECMInitialized == 0U)
+ {
+ /*
+ Initialize the TCP/IP stack here
+ */
+
+ CDC_ECMInitialized = 1U;
+ }
+
+ /* Set Application Buffers */
+ (void)USBD_CDC_ECM_SetTxBuffer(&USBD_Device, UserTxBuffer, 0U);
+ (void)USBD_CDC_ECM_SetRxBuffer(&USBD_Device, UserRxBuffer);
+
+ return (0);
+}
+
+/**
+ * @brief CDC_ECM_Itf_DeInit
+ * DeInitializes the CDC_ECM media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_ECM_Itf_DeInit(void)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc_cdc_ecm = (USBD_CDC_ECM_HandleTypeDef *)(USBD_Device.pClassData);
+
+ /* Notify application layer that link is down */
+ hcdc_cdc_ecm->LinkStatus = 0U;
+
+ return (0);
+}
+
+/**
+ * @brief CDC_ECM_Itf_Control
+ * Manage the CDC_ECM class requests
+ * @param Cmd: Command code
+ * @param Buf: Buffer containing command data (request parameters)
+ * @param Len: Number of data to be sent (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_ECM_Itf_Control(uint8_t cmd, uint8_t *pbuf, uint16_t length)
+{
+ USBD_CDC_ECM_HandleTypeDef *hcdc_cdc_ecm = (USBD_CDC_ECM_HandleTypeDef *)(USBD_Device.pClassData);
+
+ switch (cmd)
+ {
+ case CDC_ECM_SEND_ENCAPSULATED_COMMAND:
+ /* Add your code here */
+ break;
+
+ case CDC_ECM_GET_ENCAPSULATED_RESPONSE:
+ /* Add your code here */
+ break;
+
+ case CDC_ECM_SET_ETH_MULTICAST_FILTERS:
+ /* Add your code here */
+ break;
+
+ case CDC_ECM_SET_ETH_PWRM_PATTERN_FILTER:
+ /* Add your code here */
+ break;
+
+ case CDC_ECM_GET_ETH_PWRM_PATTERN_FILTER:
+ /* Add your code here */
+ break;
+
+ case CDC_ECM_SET_ETH_PACKET_FILTER:
+ /* Check if this is the first time we enter */
+ if (hcdc_cdc_ecm->LinkStatus == 0U)
+ {
+ /*
+ Setup the Link up at TCP/IP level
+ */
+ hcdc_cdc_ecm->LinkStatus = 1U;
+
+ /* Modification for MacOS which doesn't send SetInterface before receiving INs */
+ if (hcdc_cdc_ecm->NotificationStatus == 0U)
+ {
+ /* Send notification: NETWORK_CONNECTION Event */
+ (void)USBD_CDC_ECM_SendNotification(&USBD_Device, NETWORK_CONNECTION,
+ CDC_ECM_NET_CONNECTED, NULL);
+
+ /* Prepare for sending Connection Speed Change notification */
+ hcdc_cdc_ecm->NotificationStatus = 1U;
+ }
+ }
+ /* Add your code here */
+ break;
+
+ case CDC_ECM_GET_ETH_STATISTIC:
+ /* Add your code here */
+ break;
+
+ default:
+ break;
+ }
+ UNUSED(length);
+ UNUSED(pbuf);
+
+ return (0);
+}
+
+/**
+ * @brief CDC_ECM_Itf_Receive
+ * Data received over USB OUT endpoint are sent over CDC_ECM interface
+ * through this function.
+ * @param Buf: Buffer of data to be transmitted
+ * @param Len: Number of data received (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_ECM_Itf_Receive(uint8_t *Buf, uint32_t *Len)
+{
+ /* Get the CDC_ECM handler pointer */
+ USBD_CDC_ECM_HandleTypeDef *hcdc_cdc_ecm = (USBD_CDC_ECM_HandleTypeDef *)(USBD_Device.pClassData);
+
+ /* Call Eth buffer processing */
+ hcdc_cdc_ecm->RxState = 1U;
+
+ UNUSED(Len);
+ UNUSED(Buf);
+
+ return (0);
+}
+
+/**
+ * @brief CDC_ECM_Itf_TransmitCplt
+ * Data transmited callback
+ *
+ * @note
+ * This function is IN transfer complete callback used to inform user that
+ * the submitted Data is successfully sent over USB.
+ *
+ * @param Buf: Buffer of data to be received
+ * @param Len: Number of data received (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_ECM_Itf_TransmitCplt(uint8_t *Buf, uint32_t *Len, uint8_t epnum)
+{
+ UNUSED(Buf);
+ UNUSED(Len);
+ UNUSED(epnum);
+
+ return (0);
+}
+
+/**
+ * @brief CDC_ECM_Itf_Process
+ * Data received over USB OUT endpoint are sent over CDC_ECM interface
+ * through this function.
+ * @param pdef: pointer to the USB Device Handle
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_ECM_Itf_Process(USBD_HandleTypeDef *pdev)
+{
+ /* Get the CDC_ECM handler pointer */
+ USBD_CDC_ECM_HandleTypeDef *hcdc_cdc_ecm = (USBD_CDC_ECM_HandleTypeDef *)(pdev->pClassData);
+
+ if ((hcdc_cdc_ecm != NULL) && (hcdc_cdc_ecm->LinkStatus != 0U))
+ {
+ /*
+ Read a received packet from the Ethernet buffers and send it
+ to the lwIP for handling
+ Call here the TCP/IP background tasks.
+ */
+ }
+
+ return (0);
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Inc/usbd_cdc_rndis.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Inc/usbd_cdc_rndis.h
new file mode 100644
index 0000000000..ef76894400
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Inc/usbd_cdc_rndis.h
@@ -0,0 +1,529 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_rndis.h
+ * @author MCD Application Team
+ * @brief header file for the usbd_cdc_rndis.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_CDC_RNDIS_H
+#define __USB_CDC_RNDIS_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup usbd_cdc_rndis
+ * @brief This file is the Header file for usbd_cdc_rndis.c
+ * @{
+ */
+
+
+/** @defgroup usbd_cdc_rndis_Exported_Defines
+ * @{
+ */
+
+#define CDC_RNDIS_IN_EP 0x81U /* EP1 for data IN */
+#define CDC_RNDIS_OUT_EP 0x01U /* EP1 for data OUT */
+#define CDC_RNDIS_CMD_EP 0x82U /* EP2 for CDC_RNDIS commands */
+
+#ifndef CDC_RNDIS_CMD_ITF_NBR
+#define CDC_RNDIS_CMD_ITF_NBR 0x00U /* Command Interface Number 0 */
+#endif /* CDC_RNDIS_CMD_ITF_NBR */
+
+#ifndef CDC_RNDIS_COM_ITF_NBR
+#define CDC_RNDIS_COM_ITF_NBR 0x01U /* Communication Interface Number 0 */
+#endif /* CDC_RNDIS_CMD_ITF_NBR */
+
+#ifndef CDC_RNDIS_HS_BINTERVAL
+#define CDC_RNDIS_HS_BINTERVAL 0x10U
+#endif /* CDC_RNDIS_HS_BINTERVAL */
+
+#ifndef CDC_RNDIS_FS_BINTERVAL
+#define CDC_RNDIS_FS_BINTERVAL 0x10U
+#endif /* CDC_RNDIS_FS_BINTERVAL */
+
+
+/* CDC_RNDIS Endpoints parameters: you can fine tune these values
+ depending on the needed baudrates and performance. */
+#define CDC_RNDIS_DATA_HS_MAX_PACKET_SIZE 512U /* Endpoint IN & OUT Packet size */
+#define CDC_RNDIS_DATA_FS_MAX_PACKET_SIZE 64U /* Endpoint IN & OUT Packet size */
+#define CDC_RNDIS_CMD_PACKET_SIZE 16U /* Control Endpoint Packet size */
+
+#define CDC_RNDIS_CONFIG_DESC_SIZ 75U
+#define CDC_RNDIS_DATA_HS_IN_PACKET_SIZE CDC_RNDIS_DATA_HS_MAX_PACKET_SIZE
+#define CDC_RNDIS_DATA_HS_OUT_PACKET_SIZE CDC_RNDIS_DATA_HS_MAX_PACKET_SIZE
+
+#define CDC_RNDIS_DATA_FS_IN_PACKET_SIZE CDC_RNDIS_DATA_FS_MAX_PACKET_SIZE
+#define CDC_RNDIS_DATA_FS_OUT_PACKET_SIZE CDC_RNDIS_DATA_FS_MAX_PACKET_SIZE
+
+/*---------------------------------------------------------------------*/
+/* CDC_RNDIS definitions */
+/*---------------------------------------------------------------------*/
+
+/** Implemented CDC_RNDIS Version Major */
+#define CDC_RNDIS_VERSION_MAJOR 0x01U
+
+/* Implemented CDC_RNDIS Version Minor */
+#define CDC_RNDIS_VERSION_MINOR 0x00U
+
+/* Maximum size in bytes of a CDC_RNDIS control message
+ which can be sent or received */
+#define CDC_RNDIS_MESSAGE_BUFFER_SIZE 128U
+
+/* Maximum size in bytes of an Ethernet frame
+ according to the Ethernet standard */
+#define CDC_RNDIS_ETH_FRAME_SIZE_MAX 1536U
+
+/* Maximum size allocated for buffer
+ inside Query messages structures */
+#define CDC_RNDIS_MAX_INFO_BUFF_SZ 200U
+#define CDC_RNDIS_MAX_DATA_SZE 2000U
+
+/* Notification request value for a CDC_RNDIS
+ Response Available notification */
+#define CDC_RNDIS_NOTIFICATION_RESP_AVAILABLE 0x00000001UL
+
+
+#define CDC_RNDIS_PACKET_MSG_ID 0x00000001UL
+#define CDC_RNDIS_INITIALIZE_MSG_ID 0x00000002UL
+#define CDC_RNDIS_HALT_MSG_ID 0x00000003UL
+#define CDC_RNDIS_QUERY_MSG_ID 0x00000004UL
+#define CDC_RNDIS_SET_MSG_ID 0x00000005UL
+#define CDC_RNDIS_RESET_MSG_ID 0x00000006UL
+#define CDC_RNDIS_INDICATE_STATUS_MSG_ID 0x00000007UL
+#define CDC_RNDIS_KEEPALIVE_MSG_ID 0x00000008UL
+
+#define CDC_RNDIS_INITIALIZE_CMPLT_ID 0x80000002UL
+#define CDC_RNDIS_QUERY_CMPLT_ID 0x80000004UL
+#define CDC_RNDIS_SET_CMPLT_ID 0x80000005UL
+#define CDC_RNDIS_RESET_CMPLT_ID 0x80000006UL
+#define CDC_RNDIS_KEEPALIVE_CMPLT_ID 0x80000008UL
+
+#define CDC_RNDIS_STATUS_SUCCESS 0x00000000UL
+#define CDC_RNDIS_STATUS_FAILURE 0xC0000001UL
+#define CDC_RNDIS_STATUS_INVALID_DATA 0xC0010015UL
+#define CDC_RNDIS_STATUS_NOT_SUPPORTED 0xC00000BBUL
+#define CDC_RNDIS_STATUS_MEDIA_CONNECT 0x4001000BUL
+#define CDC_RNDIS_STATUS_MEDIA_DISCONNECT 0x4001000CUL
+/** Media state */
+#define CDC_RNDIS_MEDIA_STATE_CONNECTED 0x00000000UL
+#define CDC_RNDIS_MEDIA_STATE_DISCONNECTED 0x00000001UL
+
+/** Media types */
+#define CDC_RNDIS_MEDIUM_802_3 0x00000000UL
+
+#define CDC_RNDIS_DF_CONNECTIONLESS 0x00000001UL
+#define CDC_RNDIS_DF_CONNECTION_ORIENTED 0x00000002UL
+
+/** Hardware status of the underlying NIC */
+#define CDC_RNDIS_HW_STS_READY 0x00000000UL
+#define CDC_RNDIS_HW_STS_INITIALIZING 0x00000001UL
+#define CDC_RNDIS_HW_STS_RESET 0x00000002UL
+#define CDC_RNDIS_HW_STS_CLOSING 0x00000003UL
+#define CDC_RNDIS_HW_STS_NOT_READY 0x00000004UL
+
+/** Packet filter */
+#define CDC_RNDIS_PACKET_DIRECTED 0x00000001UL
+#define CDC_RNDIS_PACKET_MULTICAST 0x00000002UL
+#define CDC_RNDIS_PACKET_ALL_MULTICAST 0x00000004UL
+#define CDC_RNDIS_PACKET_BROADCAST 0x00000008UL
+#define CDC_RNDIS_PACKET_SOURCE_ROUTING 0x00000010UL
+#define CDC_RNDIS_PACKET_PROMISCUOUS 0x00000020UL
+#define CDC_RNDIS_PACKET_SMT 0x00000040UL
+#define CDC_RNDIS_PACKET_ALL_LOCAL 0x00000080UL
+#define CDC_RNDIS_PACKET_GROUP 0x00001000UL
+#define CDC_RNDIS_PACKET_ALL_FUNCTIONAL 0x00002000UL
+#define CDC_RNDIS_PACKET_FUNCTIONAL 0x00004000UL
+#define CDC_RNDIS_PACKET_MAC_FRAME 0x00008000UL
+
+#define OID_GEN_SUPPORTED_LIST 0x00010101UL
+#define OID_GEN_HARDWARE_STATUS 0x00010102UL
+#define OID_GEN_MEDIA_SUPPORTED 0x00010103UL
+#define OID_GEN_MEDIA_IN_USE 0x00010104UL
+#define OID_GEN_MAXIMUM_FRAME_SIZE 0x00010106UL
+#define OID_GEN_MAXIMUM_TOTAL_SIZE 0x00010111UL
+#define OID_GEN_LINK_SPEED 0x00010107UL
+#define OID_GEN_TRANSMIT_BLOCK_SIZE 0x0001010AUL
+#define OID_GEN_RECEIVE_BLOCK_SIZE 0x0001010BUL
+#define OID_GEN_VENDOR_ID 0x0001010CUL
+#define OID_GEN_VENDOR_DESCRIPTION 0x0001010DUL
+#define OID_GEN_CURRENT_PACKET_FILTER 0x0001010EUL
+#define OID_GEN_MEDIA_CONNECT_STATUS 0x00010114UL
+#define OID_GEN_MAXIMUM_SEND_PACKETS 0x00010115UL
+#define OID_GEN_PHYSICAL_MEDIUM 0x00010202UL
+#define OID_GEN_XMIT_OK 0x00020101UL
+#define OID_GEN_RCV_OK 0x00020102UL
+#define OID_GEN_XMIT_ERROR 0x00020103UL
+#define OID_GEN_RCV_ERROR 0x00020104UL
+#define OID_GEN_RCV_NO_BUFFER 0x00020105UL
+#define OID_GEN_CDC_RNDIS_CONFIG_PARAMETER 0x0001021BUL
+#define OID_802_3_PERMANENT_ADDRESS 0x01010101UL
+#define OID_802_3_CURRENT_ADDRESS 0x01010102UL
+#define OID_802_3_MULTICAST_LIST 0x01010103UL
+#define OID_802_3_MAXIMUM_LIST_SIZE 0x01010104UL
+#define OID_802_3_RCV_ERROR_ALIGNMENT 0x01020101UL
+#define OID_802_3_XMIT_ONE_COLLISION 0x01020102UL
+#define OID_802_3_XMIT_MORE_COLLISIONS 0x01020103UL
+
+
+#define CDC_RNDIS_SEND_ENCAPSULATED_COMMAND 0x00U
+#define CDC_RNDIS_GET_ENCAPSULATED_RESPONSE 0x01U
+
+#define CDC_RNDIS_NET_DISCONNECTED 0x00U
+#define CDC_RNDIS_NET_CONNECTED 0x01U
+
+#define CDC_RNDIS_BMREQUEST_TYPE_RNDIS 0xA1U
+#define CDC_RNDIS_PCKTMSG_DATAOFFSET_OFFSET 8U
+
+/* MAC String index */
+#define CDC_RNDIS_MAC_STRING_INDEX 6U
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+typedef struct _USBD_CDC_RNDIS_Itf
+{
+ int8_t (* Init)(void);
+ int8_t (* DeInit)(void);
+ int8_t (* Control)(uint8_t cmd, uint8_t *pbuf, uint16_t length);
+ int8_t (* Receive)(uint8_t *Buf, uint32_t *Len);
+ int8_t (* TransmitCplt)(uint8_t *Buf, uint32_t *Len, uint8_t epnum);
+ int8_t (* Process)(USBD_HandleTypeDef *pdev);
+ uint8_t *pStrDesc;
+} USBD_CDC_RNDIS_ItfTypeDef;
+
+/* CDC_RNDIS State values */
+typedef enum
+{
+ CDC_RNDIS_STATE_UNINITIALIZED = 0,
+ CDC_RNDIS_STATE_BUS_INITIALIZED = 1,
+ CDC_RNDIS_STATE_INITIALIZED = 2,
+ CDC_RNDIS_STATE_DATA_INITIALIZED = 3
+} USBD_CDC_RNDIS_StateTypeDef;
+
+typedef struct
+{
+ uint8_t bmRequest;
+ uint8_t bRequest;
+ uint16_t wValue;
+ uint16_t wIndex;
+ uint16_t wLength;
+ uint8_t data[8];
+} USBD_CDC_RNDIS_NotifTypeDef;
+
+typedef struct
+{
+ uint32_t data[2000 / 4]; /* Force 32bits alignment */
+ uint8_t CmdOpCode;
+ uint8_t CmdLength;
+ uint8_t ResponseRdy; /* Indicates if the Device Response to an CDC_RNDIS msg is ready */
+ uint8_t Reserved1; /* Reserved Byte to force 4 bytes alignment of following fields */
+ uint8_t *RxBuffer;
+ uint8_t *TxBuffer;
+ uint32_t RxLength;
+ uint32_t TxLength;
+
+ USBD_CDC_RNDIS_NotifTypeDef Req;
+ USBD_CDC_RNDIS_StateTypeDef State;
+
+ __IO uint32_t TxState;
+ __IO uint32_t RxState;
+
+ __IO uint32_t MaxPcktLen;
+ __IO uint32_t LinkStatus;
+ __IO uint32_t NotificationStatus;
+ __IO uint32_t PacketFilter;
+} USBD_CDC_RNDIS_HandleTypeDef;
+
+
+typedef enum
+{
+ NETWORK_CONNECTION = 0x00,
+ RESPONSE_AVAILABLE = 0x01,
+ CONNECTION_SPEED_CHANGE = 0x2A
+} USBD_CDC_RNDIS_NotifCodeTypeDef;
+
+
+/* Messages Sent by the Host ---------------------*/
+
+/* Type define for a CDC_RNDIS Initialize command message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+ uint32_t MajorVersion;
+ uint32_t MinorVersion;
+ uint32_t MaxTransferSize;
+} USBD_CDC_RNDIS_InitMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Halt Message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+} USBD_CDC_RNDIS_HaltMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Query command message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t RequestId;
+ uint32_t Oid;
+ uint32_t InfoBufLength;
+ uint32_t InfoBufOffset;
+ uint32_t DeviceVcHandle;
+ uint32_t InfoBuf[CDC_RNDIS_MAX_INFO_BUFF_SZ];
+} USBD_CDC_RNDIS_QueryMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Set command message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+ uint32_t Oid;
+ uint32_t InfoBufLength;
+ uint32_t InfoBufOffset;
+ uint32_t DeviceVcHandle;
+ uint32_t InfoBuf[CDC_RNDIS_MAX_INFO_BUFF_SZ];
+} USBD_CDC_RNDIS_SetMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Reset message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t Reserved;
+} USBD_CDC_RNDIS_ResetMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Keepalive command message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+} USBD_CDC_RNDIS_KpAliveMsgTypeDef;
+
+
+/* Messages Sent by the Device ---------------------*/
+
+/* Type define for a CDC_RNDIS Initialize complete response message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+ uint32_t Status;
+ uint32_t MajorVersion;
+ uint32_t MinorVersion;
+ uint32_t DeviceFlags;
+ uint32_t Medium;
+ uint32_t MaxPacketsPerTransfer;
+ uint32_t MaxTransferSize;
+ uint32_t PacketAlignmentFactor;
+ uint32_t AFListOffset;
+ uint32_t AFListSize;
+} USBD_CDC_RNDIS_InitCpltMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Query complete response message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+ uint32_t Status;
+ uint32_t InfoBufLength;
+ uint32_t InfoBufOffset;
+ uint32_t InfoBuf[CDC_RNDIS_MAX_INFO_BUFF_SZ];
+} USBD_CDC_RNDIS_QueryCpltMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Set complete response message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+ uint32_t Status;
+} USBD_CDC_RNDIS_SetCpltMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Reset complete message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t Status;
+ uint32_t AddrReset;
+} USBD_CDC_RNDIS_ResetCpltMsgTypeDef;
+
+/* Type define for CDC_RNDIS struct to indicate a change
+ in the status of the device */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t Status;
+ uint32_t StsBufLength;
+ uint32_t StsBufOffset;
+} USBD_CDC_RNDIS_StsChangeMsgTypeDef;
+
+/* Type define for a CDC_RNDIS Keepalive complete message */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+ uint32_t Status;
+} USBD_CDC_RNDIS_KpAliveCpltMsgTypeDef;
+
+
+/* Messages Sent by both Host and Device ---------------------*/
+
+/* Type define for a CDC_RNDIS packet message, used to encapsulate
+ Ethernet packets sent to and from the adapter */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t DataOffset;
+ uint32_t DataLength;
+ uint32_t OOBDataOffset;
+ uint32_t OOBDataLength;
+ uint32_t NumOOBDataElements;
+ uint32_t PerPacketInfoOffset;
+ uint32_t PerPacketInfoLength;
+ uint32_t VcHandle;
+ uint32_t Reserved;
+} USBD_CDC_RNDIS_PacketMsgTypeDef;
+
+/* Miscellaneous types used for parsing ---------------------*/
+
+/* The common part for all CDC_RNDIS messages Complete response */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+ uint32_t ReqId;
+ uint32_t Status;
+} USBD_CDC_RNDIS_CommonCpltMsgTypeDef;
+
+/* Type define for a single parameter structure */
+typedef struct
+{
+ uint32_t ParamNameOffset;
+ uint32_t ParamNameLength;
+ uint32_t ParamType;
+ uint32_t ParamValueOffset;
+ uint32_t ParamValueLength;
+} USBD_CDC_RNDIS_ParamStructTypeDef;
+
+
+/* Type define of a single CDC_RNDIS OOB data record */
+typedef struct
+{
+ uint32_t Size;
+ uint32_t Type;
+ uint32_t ClassInfoType;
+ uint32_t OOBData[sizeof(uint32_t)];
+} USBD_CDC_RNDIS_OOBPacketTypeDef;
+
+/* Type define for notification structure */
+typedef struct
+{
+ uint32_t notification;
+ uint32_t reserved;
+} USBD_CDC_RNDIS_NotifStructTypeDef;
+
+/* This structure will be used to store the type, the size and ID for any
+ received message from the control endpoint */
+typedef struct
+{
+ uint32_t MsgType;
+ uint32_t MsgLength;
+} USBD_CDC_RNDIS_CtrlMsgTypeDef;
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_CDC_RNDIS;
+#define USBD_CDC_RNDIS_CLASS &USBD_CDC_RNDIS
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+uint8_t USBD_CDC_RNDIS_SetRxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff);
+uint8_t USBD_CDC_RNDIS_ReceivePacket(USBD_HandleTypeDef *pdev);
+uint8_t USBD_CDC_RNDIS_TransmitPacket(USBD_HandleTypeDef *pdev);
+
+uint8_t USBD_CDC_RNDIS_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_ItfTypeDef *fops);
+
+uint8_t USBD_CDC_RNDIS_SetTxBuffer(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuff, uint32_t length);
+
+uint8_t USBD_CDC_RNDIS_SendNotification(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_NotifCodeTypeDef Notif,
+ uint16_t bVal, uint8_t *pData);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_CDC_RNDIS_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Inc/usbd_cdc_rndis_if_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Inc/usbd_cdc_rndis_if_template.h
new file mode 100644
index 0000000000..3cf0271654
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Inc/usbd_cdc_rndis_if_template.h
@@ -0,0 +1,60 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_rndis_if_template.h
+ * @author MCD Application Team
+ * @brief Header for usbd_cdc_rndis_if.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CDC_RNDIS_IF_H
+#define __USBD_CDC_RNDIS_IF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc_rndis.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* Ensure this MAC address value is same as MAC_ADDRx declared in STM32xxx_conf.h */
+#define CDC_RNDIS_MAC_STR_DESC (uint8_t *)"000202030000"
+#define CDC_RNDIS_MAC_ADDR0 0x00U /* 01 */
+#define CDC_RNDIS_MAC_ADDR1 0x02U /* 02 */
+#define CDC_RNDIS_MAC_ADDR2 0x02U /* 03 */
+#define CDC_RNDIS_MAC_ADDR3 0x03U /* 00 */
+#define CDC_RNDIS_MAC_ADDR4 0x00U /* 00 */
+#define CDC_RNDIS_MAC_ADDR5 0x00U /* 00 */
+
+#define USBD_CDC_RNDIS_VENDOR_DESC "STMicroelectronics"
+#define USBD_CDC_RNDIS_LINK_SPEED 100000U /* 10Mbps */
+#define USBD_CDC_RNDIS_VID 0x0483U
+
+/* Max Number of Trials waiting for Tx ready */
+#define CDC_RNDIS_MAX_TX_WAIT_TRIALS 1000000U
+
+/* Ethernet Maximum Segment size, typically 1514 bytes */
+#define CDC_RNDIS_ETH_MAX_SEGSZE 1514U
+
+#define CDC_RNDIS_CONNECT_SPEED_UPSTREAM 0x1E000000U
+#define CDC_RNDIS_CONNECT_SPEED_DOWNSTREAM 0x1E000000U
+
+
+extern USBD_CDC_RNDIS_ItfTypeDef USBD_CDC_RNDIS_fops;
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+#endif /* __USBD_CDC_RNDIS_IF_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Src/usbd_cdc_rndis.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Src/usbd_cdc_rndis.c
new file mode 100644
index 0000000000..946ed5018c
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Src/usbd_cdc_rndis.c
@@ -0,0 +1,1698 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_rndis.c
+ * @author MCD Application Team
+ * @brief This file provides the high layer firmware functions to manage the
+ * following functionalities of the USB CDC_RNDIS Class:
+ * - Initialization and Configuration of high and low layer
+ * - Enumeration as CDC_RNDIS Device (and enumeration for each implemented memory interface)
+ * - OUT/IN data transfer
+ * - Command IN transfer (class requests management)
+ * - Error management
+ *
+ * @verbatim
+ *
+ * ===================================================================
+ * CDC_RNDIS Class Driver Description
+ * ===================================================================
+ * This driver manages the "Universal Serial Bus Class Definitions for Communications Devices
+ * Revision 1.2 November 16, 2007" and the sub-protocol specification of "Universal Serial Bus
+ * Communications Class Subclass Specification for PSTN Devices Revision 1.2 February 9, 2007"
+ * This driver implements the following aspects of the specification:
+ * - Device descriptor management
+ * - Configuration descriptor management
+ * - Enumeration as CDC device with 2 data endpoints (IN and OUT) and 1 command endpoint (IN)
+ * - Requests management (as described in section 6.2 in specification)
+ * - Abstract Control Model compliant
+ * - Union Functional collection (using 1 IN endpoint for control)
+ * - Data interface class
+ *
+ * These aspects may be enriched or modified for a specific user application.
+ *
+ * This driver doesn't implement the following aspects of the specification
+ * (but it is possible to manage these features with some modifications on this driver):
+ * - Any class-specific aspect relative to communication classes should be managed by user application.
+ * - All communication classes other than PSTN are not managed
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_cdc_rndis.h"
+#include "usbd_ctlreq.h"
+
+#ifndef __USBD_CDC_RNDIS_IF_H
+#include "usbd_cdc_rndis_if_template.h"
+#endif
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_CDC_RNDIS
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_CDC_RNDIS_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_RNDIS_Private_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_RNDIS_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CDC_RNDIS_Private_FunctionPrototypes
+ * @{
+ */
+
+static uint8_t USBD_CDC_RNDIS_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_CDC_RNDIS_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+
+static uint8_t USBD_CDC_RNDIS_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req);
+
+static uint8_t USBD_CDC_RNDIS_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_CDC_RNDIS_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_CDC_RNDIS_EP0_RxReady(USBD_HandleTypeDef *pdev);
+static uint8_t *USBD_CDC_RNDIS_GetFSCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_RNDIS_GetHSCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_RNDIS_GetOtherSpeedCfgDesc(uint16_t *length);
+static uint8_t *USBD_CDC_RNDIS_GetOtherSpeedCfgDesc(uint16_t *length);
+
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+static uint8_t *USBD_CDC_RNDIS_USRStringDescriptor(USBD_HandleTypeDef *pdev, uint8_t index, uint16_t *length);
+#endif
+
+uint8_t *USBD_CDC_RNDIS_GetDeviceQualifierDescriptor(uint16_t *length);
+
+
+/* CDC_RNDIS Internal messages parsing and construction functions */
+static uint8_t USBD_CDC_RNDIS_MsgParsing(USBD_HandleTypeDef *pdev, uint8_t *RxBuff);
+static uint8_t USBD_CDC_RNDIS_ProcessInitMsg(USBD_HandleTypeDef *pdev, USBD_CDC_RNDIS_InitMsgTypeDef *Msg);
+static uint8_t USBD_CDC_RNDIS_ProcessHaltMsg(USBD_HandleTypeDef *pdev, USBD_CDC_RNDIS_HaltMsgTypeDef *Msg);
+static uint8_t USBD_CDC_RNDIS_ProcessKeepAliveMsg(USBD_HandleTypeDef *pdev, USBD_CDC_RNDIS_KpAliveMsgTypeDef *Msg);
+static uint8_t USBD_CDC_RNDIS_ProcessQueryMsg(USBD_HandleTypeDef *pdev, USBD_CDC_RNDIS_QueryMsgTypeDef *Msg);
+static uint8_t USBD_CDC_RNDIS_ProcessSetMsg(USBD_HandleTypeDef *pdev, USBD_CDC_RNDIS_SetMsgTypeDef *Msg);
+static uint8_t USBD_CDC_RNDIS_ProcessResetMsg(USBD_HandleTypeDef *pdev, USBD_CDC_RNDIS_ResetMsgTypeDef *Msg);
+static uint8_t USBD_CDC_RNDIS_ProcessPacketMsg(USBD_HandleTypeDef *pdev, USBD_CDC_RNDIS_PacketMsgTypeDef *Msg);
+static uint8_t USBD_CDC_RNDIS_ProcessUnsupportedMsg(USBD_HandleTypeDef *pdev, USBD_CDC_RNDIS_CtrlMsgTypeDef *Msg);
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_RNDIS_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x40,
+ 0x01,
+ 0x00,
+};
+
+static uint8_t MAC_StrDesc[6] = {CDC_RNDIS_MAC_ADDR0, CDC_RNDIS_MAC_ADDR1, CDC_RNDIS_MAC_ADDR2,
+ CDC_RNDIS_MAC_ADDR3, CDC_RNDIS_MAC_ADDR4, CDC_RNDIS_MAC_ADDR5};
+
+static uint32_t ConnSpeedTab[2] = {CDC_RNDIS_CONNECT_SPEED_UPSTREAM,
+ CDC_RNDIS_CONNECT_SPEED_DOWNSTREAM};
+
+static uint8_t EmptyResponse = 0x00U;
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_RNDIS_Private_Variables
+ * @{
+ */
+
+
+/* CDC_RNDIS interface class callbacks structure */
+USBD_ClassTypeDef USBD_CDC_RNDIS =
+{
+ USBD_CDC_RNDIS_Init,
+ USBD_CDC_RNDIS_DeInit,
+ USBD_CDC_RNDIS_Setup,
+ NULL, /* EP0_TxSent, */
+ USBD_CDC_RNDIS_EP0_RxReady,
+ USBD_CDC_RNDIS_DataIn,
+ USBD_CDC_RNDIS_DataOut,
+ NULL,
+ NULL,
+ NULL,
+ USBD_CDC_RNDIS_GetHSCfgDesc,
+ USBD_CDC_RNDIS_GetFSCfgDesc,
+ USBD_CDC_RNDIS_GetOtherSpeedCfgDesc,
+ USBD_CDC_RNDIS_GetDeviceQualifierDescriptor,
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+ USBD_CDC_RNDIS_USRStringDescriptor,
+#endif
+};
+
+/* USB CDC_RNDIS device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_RNDIS_CfgHSDesc[] __ALIGN_END =
+{
+ /* Configuration Descriptor */
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ LOBYTE(CDC_RNDIS_CONFIG_DESC_SIZ), /* wTotalLength: Total size of the Config descriptor */
+ HIBYTE(CDC_RNDIS_CONFIG_DESC_SIZ),
+ 0x02, /* bNumInterfaces: 2 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: self powered */
+ 0x32, /* MaxPower 0 mA */
+
+ /*---------------------------------------------------------------------------*/
+ /* IAD descriptor */
+ 0x08, /* bLength */
+ 0x0B, /* bDescriptorType */
+ 0x00, /* bFirstInterface */
+ 0x02, /* bInterfaceCount */
+ 0xE0, /* bFunctionClass (Wireless Controller) */
+ 0x01, /* bFunctionSubClass */
+ 0x03, /* bFunctionProtocol */
+ 0x00, /* iFunction */
+
+ /*---------------------------------------------------------------------------*/
+ /* Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ CDC_RNDIS_CMD_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoint used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x02, /* bInterfaceSubClass:Abstract Control Model */
+ 0xFF, /* bInterfaceProtocol: Common AT commands */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header functional descriptor */
+ 0x10, /* bcdCDC: spec release number: 1.20 */
+ 0x01,
+
+ /* Call Management Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x01, /* bDescriptorSubtype: Call Management Func Desc */
+ 0x00, /* bmCapabilities: D0+D1 */
+ CDC_RNDIS_COM_ITF_NBR, /* bDataInterface: 1 */
+
+ /* ACM Functional Descriptor */
+ 0x04, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x02, /* bDescriptorSubtype: Abstract Control Management desc */
+ 0x00, /* bmCapabilities */
+
+ /* Union Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union functional descriptor */
+ CDC_RNDIS_CMD_ITF_NBR, /* bMasterInterface: Communication class interface */
+ CDC_RNDIS_COM_ITF_NBR, /* bSlaveInterface0: Data Class Interface */
+
+ /* Notification Endpoint Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_RNDIS_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_RNDIS_CMD_PACKET_SIZE),
+ CDC_RNDIS_HS_BINTERVAL, /* bInterval */
+
+ /*---------------------------------------------------------------------------*/
+ /* Data class interface descriptor */
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ CDC_RNDIS_COM_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /* Endpoint OUT Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_RNDIS_DATA_HS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_RNDIS_DATA_HS_MAX_PACKET_SIZE),
+ 0xFF, /* bInterval: ignore for Bulk transfer */
+
+ /* Endpoint IN Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_RNDIS_DATA_HS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_RNDIS_DATA_HS_MAX_PACKET_SIZE),
+ 0xFF /* bInterval: ignore for Bulk transfer */
+};
+
+
+/* USB CDC device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CDC_RNDIS_CfgFSDesc[] __ALIGN_END =
+{
+ /* Configuration Descriptor */
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ LOBYTE(CDC_RNDIS_CONFIG_DESC_SIZ), /* wTotalLength: Total size of the Config descriptor */
+ HIBYTE(CDC_RNDIS_CONFIG_DESC_SIZ),
+ 0x02, /* bNumInterfaces: 2 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: self powered */
+ 0x32, /* MaxPower 0 mA */
+
+ /*---------------------------------------------------------------------------*/
+ /* IAD descriptor */
+ 0x08, /* bLength */
+ 0x0B, /* bDescriptorType */
+ 0x00, /* bFirstInterface */
+ 0x02, /* bInterfaceCount */
+ 0xE0, /* bFunctionClass (Wireless Controller) */
+ 0x01, /* bFunctionSubClass */
+ 0x03, /* bFunctionProtocol */
+ 0x00, /* iFunction */
+
+ /*---------------------------------------------------------------------------*/
+ /* Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ CDC_RNDIS_CMD_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoint used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x02, /* bInterfaceSubClass:Abstract Control Model */
+ 0xFF, /* bInterfaceProtocol: Common AT commands */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header functional descriptor */
+ 0x10, /* bcdCDC: spec release number: 1.20 */
+ 0x01,
+
+ /* Call Management Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x01, /* bDescriptorSubtype: Call Management Func Desc */
+ 0x00, /* bmCapabilities: D0+D1 */
+ CDC_RNDIS_COM_ITF_NBR, /* bDataInterface: 1 */
+
+ /* ACM Functional Descriptor */
+ 0x04, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x02, /* bDescriptorSubtype: Abstract Control Management desc */
+ 0x00, /* bmCapabilities */
+
+ /* Union Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union functional descriptor */
+ CDC_RNDIS_CMD_ITF_NBR, /* bMasterInterface: Communication class interface */
+ CDC_RNDIS_COM_ITF_NBR, /* bSlaveInterface0: Data Class Interface */
+
+ /* Notification Endpoint Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_RNDIS_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_RNDIS_CMD_PACKET_SIZE),
+ CDC_RNDIS_FS_BINTERVAL, /* bInterval */
+
+ /*---------------------------------------------------------------------------*/
+ /* Data class interface descriptor */
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ CDC_RNDIS_COM_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /* Endpoint OUT Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_RNDIS_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_RNDIS_DATA_FS_MAX_PACKET_SIZE),
+ 0xFF, /* bInterval: ignore for Bulk transfer */
+
+ /* Endpoint IN Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ LOBYTE(CDC_RNDIS_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_RNDIS_DATA_FS_MAX_PACKET_SIZE),
+ 0xFF /* bInterval: ignore for Bulk transfer */
+} ;
+
+__ALIGN_BEGIN static uint8_t USBD_CDC_RNDIS_OtherSpeedCfgDesc[] __ALIGN_END =
+{
+ /* Configuration Descriptor */
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ LOBYTE(CDC_RNDIS_CONFIG_DESC_SIZ), /* wTotalLength:no of returned bytes */
+ HIBYTE(CDC_RNDIS_CONFIG_DESC_SIZ),
+ 0x02, /* bNumInterfaces: 2 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x04, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: self powered */
+ 0x32, /* MaxPower 0 mA */
+
+ /*---------------------------------------------------------------------------*/
+ /* IAD descriptor */
+ 0x08, /* bLength */
+ 0x0B, /* bDescriptorType */
+ 0x00, /* bFirstInterface */
+ 0x02, /* bInterfaceCount */
+ 0xE0, /* bFunctionClass (Wireless Controller) */
+ 0x01, /* bFunctionSubClass */
+ 0x03, /* bFunctionProtocol */
+ 0x00, /* iFunction */
+
+ /*---------------------------------------------------------------------------*/
+ /* Interface Descriptor */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ CDC_RNDIS_CMD_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints: One endpoint used */
+ 0x02, /* bInterfaceClass: Communication Interface Class */
+ 0x02, /* bInterfaceSubClass:Abstract Control Model */
+ 0xFF, /* bInterfaceProtocol: Common AT commands */
+ 0x00, /* iInterface: */
+
+ /* Header Functional Descriptor */
+ 0x05, /* bLength: Endpoint Descriptor size */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x00, /* bDescriptorSubtype: Header functional descriptor */
+ 0x10, /* bcdCDC: spec release number: 1.20 */
+ 0x01,
+
+ /* Call Management Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x01, /* bDescriptorSubtype: Call Management Func Desc */
+ 0x00, /* bmCapabilities: D0+D1 */
+ CDC_RNDIS_COM_ITF_NBR, /* bDataInterface: 1 */
+
+ /* ACM Functional Descriptor */
+ 0x04, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x02, /* bDescriptorSubtype: Abstract Control Management desc */
+ 0x00, /* bmCapabilities */
+
+ /* Union Functional Descriptor */
+ 0x05, /* bFunctionLength */
+ 0x24, /* bDescriptorType: CS_INTERFACE */
+ 0x06, /* bDescriptorSubtype: Union functional descriptor */
+ CDC_RNDIS_CMD_ITF_NBR, /* bMasterInterface: Communication class interface */
+ CDC_RNDIS_COM_ITF_NBR, /* bSlaveInterface0: Data Class Interface */
+
+ /* Communication Endpoint Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_CMD_EP, /* bEndpointAddress */
+ 0x03, /* bmAttributes: Interrupt */
+ LOBYTE(CDC_RNDIS_CMD_PACKET_SIZE), /* wMaxPacketSize: */
+ HIBYTE(CDC_RNDIS_CMD_PACKET_SIZE),
+ CDC_RNDIS_FS_BINTERVAL, /* bInterval */
+
+ /*---------------------------------------------------------------------------*/
+ /* Data class interface descriptor */
+ 0x09, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
+ CDC_RNDIS_COM_ITF_NBR, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints: Two endpoints used */
+ 0x0A, /* bInterfaceClass: CDC */
+ 0x00, /* bInterfaceSubClass: */
+ 0x00, /* bInterfaceProtocol: */
+ 0x00, /* iInterface: */
+
+ /* Endpoint OUT Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_OUT_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ 0x40, /* wMaxPacketSize: */
+ 0x00,
+ 0xFF, /* bInterval: ignore for Bulk transfer */
+
+ /* Endpoint IN Descriptor */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
+ CDC_RNDIS_IN_EP, /* bEndpointAddress */
+ 0x02, /* bmAttributes: Bulk */
+ 0x40, /* wMaxPacketSize: */
+ 0x00,
+ 0xFF /* bInterval: ignore for Bulk transfer */
+};
+
+
+static const uint32_t CDC_RNDIS_SupportedOIDs[] =
+{
+ OID_GEN_SUPPORTED_LIST,
+ OID_GEN_HARDWARE_STATUS,
+ OID_GEN_MEDIA_SUPPORTED,
+ OID_GEN_MEDIA_IN_USE,
+ OID_GEN_MAXIMUM_FRAME_SIZE,
+ OID_GEN_LINK_SPEED,
+ OID_GEN_TRANSMIT_BLOCK_SIZE,
+ OID_GEN_RECEIVE_BLOCK_SIZE,
+ OID_GEN_VENDOR_ID,
+ OID_GEN_VENDOR_DESCRIPTION,
+ OID_GEN_CURRENT_PACKET_FILTER,
+ OID_GEN_MAXIMUM_TOTAL_SIZE,
+ OID_GEN_MEDIA_CONNECT_STATUS,
+ OID_GEN_MAXIMUM_SEND_PACKETS,
+ OID_802_3_PERMANENT_ADDRESS,
+ OID_802_3_CURRENT_ADDRESS,
+ OID_802_3_MULTICAST_LIST,
+ OID_802_3_MAXIMUM_LIST_SIZE,
+ OID_802_3_RCV_ERROR_ALIGNMENT,
+ OID_802_3_XMIT_ONE_COLLISION,
+ OID_802_3_XMIT_MORE_COLLISIONS,
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CDC_RNDIS_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_CDC_RNDIS_Init
+ * Initialize the CDC CDC_RNDIS interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc;
+
+ hcdc = USBD_malloc(sizeof(USBD_CDC_RNDIS_HandleTypeDef));
+
+ if (hcdc == NULL)
+ {
+ pdev->pClassData = NULL;
+ return (uint8_t)USBD_EMEM;
+ }
+
+ pdev->pClassData = (void *)hcdc;
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, CDC_RNDIS_IN_EP, USBD_EP_TYPE_BULK,
+ CDC_RNDIS_DATA_HS_IN_PACKET_SIZE);
+
+ pdev->ep_in[CDC_RNDIS_IN_EP & 0xFU].is_used = 1U;
+
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, CDC_RNDIS_OUT_EP, USBD_EP_TYPE_BULK,
+ CDC_RNDIS_DATA_HS_OUT_PACKET_SIZE);
+
+ pdev->ep_out[CDC_RNDIS_OUT_EP & 0xFU].is_used = 1U;
+
+ /* Set bInterval for CDC RNDIS CMD Endpoint */
+ pdev->ep_in[CDC_RNDIS_CMD_EP & 0xFU].bInterval = CDC_RNDIS_HS_BINTERVAL;
+ }
+ else
+ {
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, CDC_RNDIS_IN_EP, USBD_EP_TYPE_BULK,
+ CDC_RNDIS_DATA_FS_IN_PACKET_SIZE);
+
+ pdev->ep_in[CDC_RNDIS_IN_EP & 0xFU].is_used = 1U;
+
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, CDC_RNDIS_OUT_EP, USBD_EP_TYPE_BULK,
+ CDC_RNDIS_DATA_FS_OUT_PACKET_SIZE);
+
+ pdev->ep_out[CDC_RNDIS_OUT_EP & 0xFU].is_used = 1U;
+
+ /* Set bInterval for CDC RNDIS CMD Endpoint */
+ pdev->ep_in[CDC_RNDIS_CMD_EP & 0xFU].bInterval = CDC_RNDIS_FS_BINTERVAL;
+ }
+
+ /* Open Command IN EP */
+ (void)USBD_LL_OpenEP(pdev, CDC_RNDIS_CMD_EP, USBD_EP_TYPE_INTR, CDC_RNDIS_CMD_PACKET_SIZE);
+ pdev->ep_in[CDC_RNDIS_CMD_EP & 0xFU].is_used = 1U;
+
+ /* Init physical Interface components */
+ ((USBD_CDC_RNDIS_ItfTypeDef *)pdev->pUserData)->Init();
+
+ /* Init the CDC_RNDIS state */
+ hcdc->State = CDC_RNDIS_STATE_BUS_INITIALIZED;
+
+ /* Init Xfer states */
+ hcdc->TxState = 0U;
+ hcdc->RxState = 0U;
+ hcdc->RxLength = 0U;
+ hcdc->TxLength = 0U;
+ hcdc->LinkStatus = 0U;
+ hcdc->NotificationStatus = 0U;
+ hcdc->MaxPcktLen = (pdev->dev_speed == USBD_SPEED_HIGH) ? CDC_RNDIS_DATA_HS_MAX_PACKET_SIZE : CDC_RNDIS_DATA_FS_MAX_PACKET_SIZE;
+
+ /* Prepare Out endpoint to receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_RNDIS_OUT_EP,
+ hcdc->RxBuffer, hcdc->MaxPcktLen);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_DeInit
+ * DeInitialize the CDC layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ /* Close EP IN */
+ (void)USBD_LL_CloseEP(pdev, CDC_RNDIS_IN_EP);
+ pdev->ep_in[CDC_RNDIS_IN_EP & 0xFU].is_used = 0U;
+
+ /* Close EP OUT */
+ (void)USBD_LL_CloseEP(pdev, CDC_RNDIS_OUT_EP);
+ pdev->ep_out[CDC_RNDIS_OUT_EP & 0xFU].is_used = 0U;
+
+ /* Close Command IN EP */
+ (void)USBD_LL_CloseEP(pdev, CDC_RNDIS_CMD_EP);
+ pdev->ep_in[CDC_RNDIS_CMD_EP & 0xFU].is_used = 0U;
+ pdev->ep_in[CDC_RNDIS_CMD_EP & 0xFU].bInterval = 0U;
+
+ /* DeInit physical Interface components */
+ if (pdev->pClassData != NULL)
+ {
+ ((USBD_CDC_RNDIS_ItfTypeDef *)pdev->pUserData)->DeInit();
+ USBD_free(pdev->pClassData);
+ pdev->pClassData = NULL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_Setup
+ * Handle the CDC specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+ USBD_CDC_RNDIS_CtrlMsgTypeDef *Msg = (USBD_CDC_RNDIS_CtrlMsgTypeDef *)hcdc->data;
+ uint8_t ifalt = 0U;
+ uint16_t status_info = 0U;
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS :
+ if (req->wLength != 0U)
+ {
+ /* Control Request Data from Device to Host, send data prepared by device */
+ if ((req->bmRequest & 0x80U) != 0U)
+ {
+ /* Update opcode and length */
+ hcdc->CmdOpCode = req->bRequest;
+ hcdc->CmdLength = (uint8_t)req->wLength;
+
+ if (hcdc->CmdOpCode == CDC_RNDIS_GET_ENCAPSULATED_RESPONSE)
+ {
+ /* Data of Response Message has already been prepared by USBD_CDC_RNDIS_MsgParsing.
+ Just check that length is corresponding to right expected value */
+ if (req->wLength != Msg->MsgLength)
+ {
+ }
+ }
+
+ /* Allow application layer to pre-process data or add own processing before sending response */
+ ((USBD_CDC_RNDIS_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest,
+ (uint8_t *)hcdc->data,
+ req->wLength);
+ /* Check if Response is ready */
+ if (hcdc->ResponseRdy != 0U)
+ {
+ /* Clear Response Ready flag */
+ hcdc->ResponseRdy = 0U;
+
+ /* Send data on control endpoint */
+ (void)USBD_CtlSendData(pdev, (uint8_t *)hcdc->data, Msg->MsgLength);
+ }
+ else
+ {
+ /* CDC_RNDIS Specification says: If for some reason the device receives a GET ENCAPSULATED RESPONSE
+ and is unable to respond with a valid data on the Control endpoint,
+ then it should return a one-byte packet set to 0x00, rather than
+ stalling the Control endpoint */
+ (void)USBD_CtlSendData(pdev, &EmptyResponse, 1U);
+ }
+ }
+ /* Control Request Data from Host to Device: Prepare reception of control data stage */
+ else
+ {
+ hcdc->CmdOpCode = req->bRequest;
+ hcdc->CmdLength = (uint8_t)req->wLength;
+
+ (void)USBD_CtlPrepareRx(pdev, (uint8_t *)hcdc->data, req->wLength);
+ }
+ }
+ /* No Data control request: there is no such request for CDC_RNDIS protocol,
+ so let application layer manage this case */
+ else
+ {
+ ((USBD_CDC_RNDIS_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest,
+ (uint8_t *)req, 0U);
+ }
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, &ifalt, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ if (pdev->dev_state != USBD_STATE_CONFIGURED)
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_DataIn
+ * Data sent on non-control IN endpoint
+ * @param pdev: device instance
+ * @param epnum: endpoint number
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc;
+ PCD_HandleTypeDef *hpcd = pdev->pData;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ if (epnum == (CDC_RNDIS_IN_EP & 0x7FU))
+ {
+ if ((pdev->ep_in[epnum & 0xFU].total_length > 0U) &&
+ ((pdev->ep_in[epnum & 0xFU].total_length % hpcd->IN_ep[epnum & 0xFU].maxpacket) == 0U))
+ {
+ /* Update the packet total length */
+ pdev->ep_in[epnum & 0xFU].total_length = 0U;
+
+ /* Send ZLP */
+ (void)USBD_LL_Transmit(pdev, epnum, NULL, 0U);
+ }
+ else
+ {
+ hcdc->TxState = 0U;
+ ((USBD_CDC_RNDIS_ItfTypeDef *)pdev->pUserData)->TransmitCplt(hcdc->TxBuffer, &hcdc->TxLength, epnum);
+ }
+ }
+ else if (epnum == (CDC_RNDIS_CMD_EP & 0x7FU))
+ {
+ if (hcdc->NotificationStatus != 0U)
+ {
+ (void)USBD_CDC_RNDIS_SendNotification(pdev, CONNECTION_SPEED_CHANGE,
+ 0U, (uint8_t *)ConnSpeedTab);
+
+ hcdc->NotificationStatus = 0U;
+ }
+ }
+ else
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_DataOut
+ * Data received on non-control Out endpoint
+ * @param pdev: device instance
+ * @param epnum: endpoint number
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc;
+ uint32_t CurrPcktLen;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ if (epnum == CDC_RNDIS_OUT_EP)
+ {
+ /* Get the received data length */
+ CurrPcktLen = USBD_LL_GetRxDataSize(pdev, epnum);
+
+ /* Increment the frame length */
+ hcdc->RxLength += CurrPcktLen;
+
+ /* If the buffer size is less than max packet size: it is the last packet in current frame */
+ if ((CurrPcktLen < hcdc->MaxPcktLen) ||
+ (hcdc->RxLength >= (CDC_RNDIS_ETH_MAX_SEGSZE + sizeof(USBD_CDC_RNDIS_PacketMsgTypeDef))))
+ {
+ /* USB data will be immediately processed, this allow next USB traffic being
+ NACKed till the end of the application Xfer */
+
+ /* Call data packet message parsing and processing function */
+ (void)USBD_CDC_RNDIS_ProcessPacketMsg(pdev, (USBD_CDC_RNDIS_PacketMsgTypeDef *)hcdc->RxBuffer);
+ }
+ else
+ {
+ /* Prepare Out endpoint to receive next packet in current/new frame */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_RNDIS_OUT_EP,
+ (uint8_t *)(hcdc->RxBuffer + hcdc->RxLength),
+ hcdc->MaxPcktLen);
+ }
+ }
+ else
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_EP0_RxReady
+ * Handle EP0 Rx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_EP0_RxReady(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ if ((pdev->pUserData != NULL) && (hcdc->CmdOpCode != 0xFFU))
+ {
+ /* Check if the received command is SendEncapsulated command */
+ if (hcdc->CmdOpCode == CDC_RNDIS_SEND_ENCAPSULATED_COMMAND)
+ {
+ /* Process Received CDC_RNDIS Control Message */
+ (void)USBD_CDC_RNDIS_MsgParsing(pdev, (uint8_t *)(hcdc->data));
+
+ /* Reset the command opcode for next processing */
+ hcdc->CmdOpCode = 0xFFU;
+ }
+ else
+ {
+ /* Reset the command opcode for next processing */
+ hcdc->CmdOpCode = 0xFFU;
+
+ /* Ignore the command and return fail */
+ return (uint8_t)USBD_FAIL;
+ }
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_GetFSCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_RNDIS_GetFSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)(sizeof(USBD_CDC_RNDIS_CfgFSDesc));
+
+ return USBD_CDC_RNDIS_CfgFSDesc;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_GetHSCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_RNDIS_GetHSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)(sizeof(USBD_CDC_RNDIS_CfgHSDesc));
+
+ return USBD_CDC_RNDIS_CfgHSDesc;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_GetOtherSpeedCfgDesc
+ * Return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CDC_RNDIS_GetOtherSpeedCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)(sizeof(USBD_CDC_RNDIS_OtherSpeedCfgDesc));
+
+ return USBD_CDC_RNDIS_OtherSpeedCfgDesc;
+}
+
+/**
+ * @brief DeviceQualifierDescriptor
+ * return Device Qualifier descriptor
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+uint8_t *USBD_CDC_RNDIS_GetDeviceQualifierDescriptor(uint16_t *length)
+{
+ *length = (uint16_t)(sizeof(USBD_CDC_RNDIS_DeviceQualifierDesc));
+
+ return USBD_CDC_RNDIS_DeviceQualifierDesc;
+}
+
+/**
+ * @brief USBD_CDC_RNDIS_RegisterInterface
+ * @param pdev: device instance
+ * @param fops: CD Interface callback
+ * @retval status
+ */
+uint8_t USBD_CDC_RNDIS_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_ItfTypeDef *fops)
+{
+ if (fops == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ pdev->pUserData = fops;
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_USRStringDescriptor
+ * Manages the transfer of user string descriptors.
+ * @param speed : current device speed
+ * @param index: descriptor index
+ * @param length : pointer data length
+ * @retval pointer to the descriptor table or NULL if the descriptor is not supported.
+ */
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+static uint8_t *USBD_CDC_RNDIS_USRStringDescriptor(USBD_HandleTypeDef *pdev, uint8_t index, uint16_t *length)
+{
+ static uint8_t USBD_StrDesc[255];
+
+ /* Check if the requested string interface is supported */
+ if (index == CDC_RNDIS_MAC_STRING_INDEX)
+ {
+ USBD_GetString((uint8_t *)((USBD_CDC_RNDIS_ItfTypeDef *)pdev->pUserData)->pStrDesc, USBD_StrDesc, length);
+ return USBD_StrDesc;
+ }
+ /* Not supported Interface Descriptor index */
+ else
+ {
+ return NULL;
+ }
+}
+#endif /* USBD_SUPPORT_USER_STRING_DESC */
+
+/**
+ * @brief USBD_CDC_RNDIS_SetTxBuffer
+ * @param pdev: device instance
+ * @param pbuff: Tx Buffer
+ * @retval status
+ */
+uint8_t USBD_CDC_RNDIS_SetTxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff, uint32_t length)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ hcdc->TxBuffer = pbuff;
+ hcdc->TxLength = length;
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_SetRxBuffer
+ * @param pdev: device instance
+ * @param pbuff: Rx Buffer
+ * @retval status
+ */
+uint8_t USBD_CDC_RNDIS_SetRxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ hcdc->RxBuffer = pbuff;
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_TransmitPacket
+ * Transmit packet on IN endpoint
+ * @param pdev: device instance
+ * @retval status
+ */
+uint8_t USBD_CDC_RNDIS_TransmitPacket(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc;
+ USBD_CDC_RNDIS_PacketMsgTypeDef *PacketMsg;
+ USBD_StatusTypeDef ret = USBD_BUSY;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+ PacketMsg = (USBD_CDC_RNDIS_PacketMsgTypeDef *)hcdc->TxBuffer;
+
+ if (hcdc->TxState == 0U)
+ {
+ /* Tx Transfer in progress */
+ hcdc->TxState = 1U;
+
+ /* Format the packet information */
+ PacketMsg->MsgType = CDC_RNDIS_PACKET_MSG_ID;
+ PacketMsg->MsgLength = hcdc->TxLength;
+ PacketMsg->DataOffset = sizeof(USBD_CDC_RNDIS_PacketMsgTypeDef) - CDC_RNDIS_PCKTMSG_DATAOFFSET_OFFSET;
+ PacketMsg->DataLength = hcdc->TxLength - sizeof(USBD_CDC_RNDIS_PacketMsgTypeDef);
+ PacketMsg->OOBDataOffset = 0U;
+ PacketMsg->OOBDataLength = 0U;
+ PacketMsg->NumOOBDataElements = 0U;
+ PacketMsg->PerPacketInfoOffset = 0U;
+ PacketMsg->PerPacketInfoLength = 0U;
+ PacketMsg->VcHandle = 0U;
+ PacketMsg->Reserved = 0U;
+
+ /* Update the packet total length */
+ pdev->ep_in[CDC_RNDIS_IN_EP & 0xFU].total_length = hcdc->TxLength;
+
+ /* Transmit next packet */
+ (void)USBD_LL_Transmit(pdev, CDC_RNDIS_IN_EP, hcdc->TxBuffer, hcdc->TxLength);
+
+ ret = USBD_OK;
+ }
+
+ return (uint8_t)ret;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_ReceivePacket
+ * prepare OUT Endpoint for reception
+ * @param pdev: device instance
+ * @retval status
+ */
+uint8_t USBD_CDC_RNDIS_ReceivePacket(USBD_HandleTypeDef *pdev)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ /* Prepare Out endpoint to receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, CDC_RNDIS_OUT_EP,
+ hcdc->RxBuffer, hcdc->MaxPcktLen);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_SendNotification
+ * Transmit Notification packet on CMD IN interrupt endpoint
+ * @param pdev: device instance
+ * Notif: value of the notification type (from CDC_RNDIS_Notification_TypeDef enumeration list)
+ * bVal: value of the notification switch (ie. 0x00 or 0x01 for Network Connection notification)
+ * pData: pointer to data buffer (ie. upstream and downstream connection speed values)
+ * @retval status
+ */
+uint8_t USBD_CDC_RNDIS_SendNotification(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_NotifCodeTypeDef Notif,
+ uint16_t bVal, uint8_t *pData)
+{
+ uint32_t Idx;
+ uint16_t ReqSize = 0U;
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ UNUSED(bVal);
+ UNUSED(pData);
+
+ /* Initialize the request fields */
+ (hcdc->Req).bmRequest = CDC_RNDIS_BMREQUEST_TYPE_RNDIS;
+ (hcdc->Req).bRequest = (uint8_t)Notif;
+
+ switch (Notif)
+ {
+ case RESPONSE_AVAILABLE:
+ (hcdc->Req).wValue = 0U;
+ (hcdc->Req).wIndex = CDC_RNDIS_CMD_ITF_NBR;
+ (hcdc->Req).wLength = 0U;
+ for (Idx = 0U; Idx < 8U; Idx++)
+ {
+ (hcdc->Req).data[Idx] = 0U;
+ }
+ ReqSize = 8U;
+ break;
+
+ default:
+ ret = USBD_FAIL;
+ break;
+ }
+
+ /* Transmit notification packet */
+ if (ReqSize != 0U)
+ {
+ (void)USBD_LL_Transmit(pdev, CDC_RNDIS_CMD_EP, (uint8_t *)&(hcdc->Req), ReqSize);
+ }
+
+ return (uint8_t)ret;
+}
+
+
+/* ----------------------------- CDC_RNDIS Messages processing functions ----------------------- */
+/**
+ * @brief USBD_CDC_RNDIS_MsgParsing
+ * Parse received message and process it depending on its nature.
+ * @param pdev: USB Device Handle pointer
+ * @param RxBuff: Pointer to the message data extracted from SendEncapsulated command
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_MsgParsing(USBD_HandleTypeDef *pdev, uint8_t *RxBuff)
+{
+ USBD_CDC_RNDIS_CtrlMsgTypeDef *Msg = (USBD_CDC_RNDIS_CtrlMsgTypeDef *)RxBuff;
+ static uint8_t ret = (uint8_t)USBD_OK;
+
+ /* Check message type */
+ switch (Msg->MsgType)
+ {
+ /* CDC_RNDIS Initialize message */
+ case CDC_RNDIS_INITIALIZE_MSG_ID:
+ ret = USBD_CDC_RNDIS_ProcessInitMsg(pdev, (USBD_CDC_RNDIS_InitMsgTypeDef *)Msg);
+ break;
+
+ /* CDC_RNDIS Halt message */
+ case CDC_RNDIS_HALT_MSG_ID:
+ ret = USBD_CDC_RNDIS_ProcessHaltMsg(pdev, (USBD_CDC_RNDIS_HaltMsgTypeDef *)Msg);
+ break;
+
+ /* CDC_RNDIS Query message */
+ case CDC_RNDIS_QUERY_MSG_ID:
+ ret = USBD_CDC_RNDIS_ProcessQueryMsg(pdev, (USBD_CDC_RNDIS_QueryMsgTypeDef *)Msg);
+ break;
+
+ /* CDC_RNDIS Set message */
+ case CDC_RNDIS_SET_MSG_ID:
+ ret = USBD_CDC_RNDIS_ProcessSetMsg(pdev, (USBD_CDC_RNDIS_SetMsgTypeDef *)Msg);
+ break;
+
+ /* CDC_RNDIS Reset message */
+ case CDC_RNDIS_RESET_MSG_ID:
+ ret = USBD_CDC_RNDIS_ProcessResetMsg(pdev, (USBD_CDC_RNDIS_ResetMsgTypeDef *)Msg);
+ break;
+
+ /* CDC_RNDIS Keep-Alive message */
+ case CDC_RNDIS_KEEPALIVE_MSG_ID:
+ ret = USBD_CDC_RNDIS_ProcessKeepAliveMsg(pdev, (USBD_CDC_RNDIS_KpAliveMsgTypeDef *)Msg);
+ break;
+
+ /* CDC_RNDIS unsupported message */
+ default:
+ ret = USBD_CDC_RNDIS_ProcessUnsupportedMsg(pdev, (USBD_CDC_RNDIS_CtrlMsgTypeDef *)Msg);
+ break;
+ }
+
+ return ret;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_ProcessInitMsg
+ * Parse, extract data and check correctness of CDC_RNDIS INIT_MSG command.
+ * @param pdev: USB Device Handle pointer
+ * @param Msg: Pointer to the message data extracted from SendEncapsulated command
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_ProcessInitMsg(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_InitMsgTypeDef *Msg)
+{
+ /* Get the CDC_RNDIS handle pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ /* Get and format the Msg input */
+ USBD_CDC_RNDIS_InitMsgTypeDef *InitMessage = (USBD_CDC_RNDIS_InitMsgTypeDef *)Msg;
+
+ /* Use same Msg input buffer as response buffer */
+ USBD_CDC_RNDIS_InitCpltMsgTypeDef *InitResponse = (USBD_CDC_RNDIS_InitCpltMsgTypeDef *)Msg;
+
+ /* Store the Message Request ID */
+ uint32_t ReqId = InitMessage->ReqId;
+
+ /* Check correctness of the message (MsgType already checked by entry to this function) */
+ if ((InitMessage->MsgLength != sizeof(USBD_CDC_RNDIS_InitMsgTypeDef)) || \
+ (InitMessage->MajorVersion < CDC_RNDIS_VERSION_MAJOR))
+ {
+ InitResponse->Status = CDC_RNDIS_STATUS_FAILURE;
+ }
+ else
+ {
+ InitResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ }
+
+ /* Setup the response buffer content */
+ InitResponse->MsgType = CDC_RNDIS_INITIALIZE_CMPLT_ID;
+ InitResponse->MsgLength = sizeof(USBD_CDC_RNDIS_InitCpltMsgTypeDef);
+ InitResponse->ReqId = ReqId;
+ InitResponse->MajorVersion = CDC_RNDIS_VERSION_MAJOR;
+ InitResponse->MinorVersion = CDC_RNDIS_VERSION_MINOR;
+ InitResponse->DeviceFlags = CDC_RNDIS_DF_CONNECTIONLESS;
+ InitResponse->Medium = CDC_RNDIS_MEDIUM_802_3;
+ InitResponse->MaxPacketsPerTransfer = 1U;
+ InitResponse->MaxTransferSize = (sizeof(USBD_CDC_RNDIS_PacketMsgTypeDef) + CDC_RNDIS_ETH_FRAME_SIZE_MAX);
+ InitResponse->PacketAlignmentFactor = 2U; /* Not needed as single packet by transfer set */
+ InitResponse->AFListOffset = 0U; /* Reserved for connection-oriented devices. Set value to zero. */
+ InitResponse->AFListSize = 0U; /* Reserved for connection-oriented devices. Set value to zero. */
+
+ /* Set CDC_RNDIS state to INITIALIZED */
+ hcdc->State = CDC_RNDIS_STATE_INITIALIZED;
+
+ /* Set Response Ready field in order to send response during next control request */
+ hcdc->ResponseRdy = 1U;
+
+ /* Send Notification on Interrupt EP to inform Host that response is ready */
+ (void)USBD_CDC_RNDIS_SendNotification(pdev, RESPONSE_AVAILABLE, 0U, NULL);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_ProcessHaltMsg
+ * Parse, extract data and check correctness of CDC_RNDIS Halt command.
+ * @param pdev: USB Device Handle pointer
+ * @param Msg: Pointer to the message data extracted from SendEncapsulated command
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_ProcessHaltMsg(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_HaltMsgTypeDef *Msg)
+{
+ /* Get the CDC_RNDIS handle pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ /* Set CDC_RNDIS state to INITIALIZED */
+ hcdc->State = CDC_RNDIS_STATE_UNINITIALIZED;
+
+ /* No response required for this message, so no notification (RESPNSE_AVAILABLE) is sent */
+
+ UNUSED(Msg);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_ProcessKeepAliveMsg
+ * Parse, extract data and check correctness of CDC_RNDIS KeepAlive command.
+ * @param pdev: USB Device Handle pointer
+ * @param Msg: Pointer to the message data extracted from SendEncapsulated command
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_ProcessKeepAliveMsg(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_KpAliveMsgTypeDef *Msg)
+{
+ /* Get the CDC_RNDIS handle pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ /* Use same Msg input buffer as response buffer */
+ USBD_CDC_RNDIS_KpAliveCpltMsgTypeDef *InitResponse = (USBD_CDC_RNDIS_KpAliveCpltMsgTypeDef *)Msg;
+
+ /* Store the Message Request ID */
+ uint32_t ReqId = Msg->ReqId;
+
+ /* Check correctness of the message (MsgType already checked by entry to this function) */
+ if (Msg->MsgLength != sizeof(USBD_CDC_RNDIS_KpAliveMsgTypeDef))
+ {
+ InitResponse->Status = CDC_RNDIS_STATUS_FAILURE;
+ }
+ else
+ {
+ InitResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ }
+
+ /* Setup the response buffer content */
+ InitResponse->MsgType = CDC_RNDIS_KEEPALIVE_CMPLT_ID;
+ InitResponse->MsgLength = sizeof(USBD_CDC_RNDIS_KpAliveCpltMsgTypeDef);
+ InitResponse->ReqId = ReqId;
+ InitResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+
+ /* Set Response Ready field in order to send response during next control request */
+ hcdc->ResponseRdy = 1U;
+
+ /* Send Notification on Interrupt EP to inform Host that response is ready */
+ (void)USBD_CDC_RNDIS_SendNotification(pdev, RESPONSE_AVAILABLE, 0U, NULL);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_ProcessQueryMsg
+ * Parse, extract data and check correctness of CDC_RNDIS Query command.
+ * @param pdev: USB Device Handle pointer
+ * @param Msg: Pointer to the message data extracted from SendEncapsulated command
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_ProcessQueryMsg(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_QueryMsgTypeDef *Msg)
+{
+ /* Get the CDC_RNDIS handle pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ /* Use same Msg input buffer as response buffer */
+ USBD_CDC_RNDIS_QueryCpltMsgTypeDef *QueryResponse = (USBD_CDC_RNDIS_QueryCpltMsgTypeDef *)Msg;
+
+ /* Store the Message Request ID */
+ uint32_t ReqId = Msg->RequestId;
+
+ /* Process the OID depending on its code */
+ switch (Msg->Oid)
+ {
+ case OID_GEN_SUPPORTED_LIST:
+ QueryResponse->InfoBufLength = sizeof(CDC_RNDIS_SupportedOIDs);
+ (void)USBD_memcpy(QueryResponse->InfoBuf, CDC_RNDIS_SupportedOIDs,
+ sizeof(CDC_RNDIS_SupportedOIDs));
+
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_HARDWARE_STATUS:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = CDC_RNDIS_HW_STS_READY;
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_MEDIA_SUPPORTED:
+ case OID_GEN_MEDIA_IN_USE:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = CDC_RNDIS_MEDIUM_802_3;
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_VENDOR_ID:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = USBD_CDC_RNDIS_VID;
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_MAXIMUM_FRAME_SIZE:
+ case OID_GEN_TRANSMIT_BLOCK_SIZE:
+ case OID_GEN_RECEIVE_BLOCK_SIZE:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = CDC_RNDIS_ETH_FRAME_SIZE_MAX;
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_VENDOR_DESCRIPTION:
+ QueryResponse->InfoBufLength = (strlen(USBD_CDC_RNDIS_VENDOR_DESC) + 1U);
+ (void)USBD_memcpy(QueryResponse->InfoBuf, USBD_CDC_RNDIS_VENDOR_DESC,
+ strlen(USBD_CDC_RNDIS_VENDOR_DESC));
+
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_MEDIA_CONNECT_STATUS:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = CDC_RNDIS_MEDIA_STATE_CONNECTED;
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_MAXIMUM_SEND_PACKETS:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = 1U;
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_LINK_SPEED:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = USBD_CDC_RNDIS_LINK_SPEED;
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_802_3_PERMANENT_ADDRESS:
+ case OID_802_3_CURRENT_ADDRESS:
+ QueryResponse->InfoBufLength = 6U;
+ (void)USBD_memcpy(QueryResponse->InfoBuf, MAC_StrDesc, 6);
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_802_3_MAXIMUM_LIST_SIZE:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = 1U; /* Only one multicast address supported */
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_CURRENT_PACKET_FILTER:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = 0xFFFFFFU; /* USBD_CDC_RNDIS_DEVICE.packetFilter; */
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_802_3_RCV_ERROR_ALIGNMENT:
+ case OID_802_3_XMIT_ONE_COLLISION:
+ case OID_802_3_XMIT_MORE_COLLISIONS:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ QueryResponse->InfoBuf[0] = 0U; /* Unused OIDs, return zero */
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_GEN_MAXIMUM_TOTAL_SIZE:
+ QueryResponse->InfoBufLength = sizeof(uint32_t);
+ /* Indicate maximum overall buffer (Ethernet frame and CDC_RNDIS header) the adapter can handle */
+ QueryResponse->InfoBuf[0] = (CDC_RNDIS_MESSAGE_BUFFER_SIZE + CDC_RNDIS_ETH_FRAME_SIZE_MAX);
+ QueryResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ default:
+ /* Unknown or unsupported OID */
+ QueryResponse->InfoBufLength = 0U;
+ QueryResponse->Status = CDC_RNDIS_STATUS_FAILURE;
+ break;
+ }
+
+ /* Setup the response buffer content */
+ QueryResponse->MsgType = CDC_RNDIS_QUERY_CMPLT_ID;
+ QueryResponse->MsgLength = QueryResponse->InfoBufLength + 24U;
+ QueryResponse->ReqId = ReqId;
+ QueryResponse->InfoBufOffset = 16U;
+
+ /* Set Response Ready field in order to send response during next control request */
+ hcdc->ResponseRdy = 1U;
+
+ /* Send Notification on Interrupt EP to inform Host that response is ready */
+ (void)USBD_CDC_RNDIS_SendNotification(pdev, RESPONSE_AVAILABLE, 0U, NULL);
+
+ return(uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_ProcessSetMsg
+ * Parse, extract data and check correctness of CDC_RNDIS Set Message command.
+ * @param pdev: USB Device Handle pointer
+ * @param Msg: Pointer to the message data extracted from SendEncapsulated command
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_ProcessSetMsg(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_SetMsgTypeDef *Msg)
+{
+ /* Get the CDC_RNDIS handle pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ /* Get and format the Msg input */
+ USBD_CDC_RNDIS_SetMsgTypeDef *SetMessage = (USBD_CDC_RNDIS_SetMsgTypeDef *)Msg;
+
+ /* Use same Msg input buffer as response buffer */
+ USBD_CDC_RNDIS_SetCpltMsgTypeDef *SetResponse = (USBD_CDC_RNDIS_SetCpltMsgTypeDef *)Msg;
+
+ /* Store the Message Request ID */
+ uint32_t ReqId = SetMessage->ReqId;
+
+ switch (SetMessage->Oid)
+ {
+ case OID_GEN_CURRENT_PACKET_FILTER:
+ /* Setup the packet filter value */
+ hcdc->PacketFilter = SetMessage->InfoBuf[0];
+ SetResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ case OID_802_3_MULTICAST_LIST:
+ /* List of multicast addresses on a miniport adapter */
+ SetResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ break;
+
+ default:
+ /* Report an error */
+ SetResponse->Status = CDC_RNDIS_STATUS_FAILURE;
+ break;
+ }
+
+ /* Prepare response buffer */
+ SetResponse->MsgType = CDC_RNDIS_SET_CMPLT_ID;
+ SetResponse->MsgLength = sizeof(USBD_CDC_RNDIS_SetCpltMsgTypeDef);
+ SetResponse->ReqId = ReqId;
+
+ /* Set Response Ready field in order to send response during next control request */
+ hcdc->ResponseRdy = 1U;
+
+ /* Send Notification on Interrupt EP to inform Host that response is ready */
+ (void)USBD_CDC_RNDIS_SendNotification(pdev, RESPONSE_AVAILABLE, 0U, NULL);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_ProcessResetMsg
+ * Parse, extract data and check correctness of CDC_RNDIS Set Message command.
+ * @param pdev: USB Device Handle pointer
+ * @param Msg: Pointer to the message data extracted from SendEncapsulated command
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_ProcessResetMsg(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_ResetMsgTypeDef *Msg)
+{
+ /* Get and format the Msg input */
+ USBD_CDC_RNDIS_ResetMsgTypeDef *ResetMessage = (USBD_CDC_RNDIS_ResetMsgTypeDef *)Msg;
+ /* Get the CDC_RNDIS handle pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+ /* Use same Msg input buffer as response buffer */
+ USBD_CDC_RNDIS_ResetCpltMsgTypeDef *ResetResponse = (USBD_CDC_RNDIS_ResetCpltMsgTypeDef *)Msg;
+
+ if ((ResetMessage->MsgLength != sizeof(USBD_CDC_RNDIS_ResetMsgTypeDef)) || \
+ (ResetMessage->Reserved != 0U))
+ {
+ ResetResponse->Status = CDC_RNDIS_STATUS_FAILURE;
+ }
+ else
+ {
+ ResetResponse->Status = CDC_RNDIS_STATUS_SUCCESS;
+ }
+
+ /* Prepare response buffer */
+ ResetResponse->MsgType = CDC_RNDIS_RESET_CMPLT_ID;
+ ResetResponse->MsgLength = sizeof(USBD_CDC_RNDIS_ResetCpltMsgTypeDef);
+ ResetResponse->AddrReset = 0U;
+
+ /* Set CDC_RNDIS state to INITIALIZED */
+ hcdc->State = CDC_RNDIS_STATE_BUS_INITIALIZED;
+ hcdc->LinkStatus = 0U;
+
+ /* Set Response Ready field in order to send response during next control request */
+ hcdc->ResponseRdy = 1U;
+
+ /* Send Notification on Interrupt EP to inform Host that response is ready */
+ (void)USBD_CDC_RNDIS_SendNotification(pdev, RESPONSE_AVAILABLE, 0U, NULL);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CDC_RNDIS_ProcessPacketMsg
+ * Parse, extract data and check correctness of CDC_RNDIS Data Packet.
+ * @param pdev: USB Device Handle pointer
+ * @param Msg: Pointer to the message data extracted from Packet
+ * @retval status
+ */
+static uint8_t USBD_CDC_RNDIS_ProcessPacketMsg(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_PacketMsgTypeDef *Msg)
+{
+ uint32_t tmp1, tmp2;
+
+ /* Get the CDC_RNDIS handle pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ /* Get and format the Msg input */
+ USBD_CDC_RNDIS_PacketMsgTypeDef *PacketMsg = (USBD_CDC_RNDIS_PacketMsgTypeDef *)Msg;
+
+ /* Check correctness of the message */
+ if ((PacketMsg->MsgType != CDC_RNDIS_PACKET_MSG_ID))
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ /* Point to the payload and udpate the message length */
+
+ /* Use temporary storage variables to comply with MISRA-C 2012 rule of (+) operand allowed types */
+ tmp1 = (uint32_t)PacketMsg;
+ tmp2 = (uint32_t)(PacketMsg->DataOffset);
+ hcdc->RxBuffer = (uint8_t *)(tmp1 + tmp2 + CDC_RNDIS_PCKTMSG_DATAOFFSET_OFFSET);
+ hcdc->RxLength = PacketMsg->DataLength;
+
+ /* Process data by application */
+ ((USBD_CDC_RNDIS_ItfTypeDef *)pdev->pUserData)->Receive(hcdc->RxBuffer, &hcdc->RxLength);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+* @brief USBD_CDC_RNDIS_ProcessUnsupportedMsg
+* Parse, extract data and check correctness of CDC_RNDIS KeepAlive command.
+* @param pdev: USB Device Handle pointer
+* @param Msg: Pointer to the message data extracted from SendEncapsulated command
+* @retval status
+*/
+static uint8_t USBD_CDC_RNDIS_ProcessUnsupportedMsg(USBD_HandleTypeDef *pdev,
+ USBD_CDC_RNDIS_CtrlMsgTypeDef *Msg)
+{
+ /* Get the CDC_RNDIS handle pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc = (USBD_CDC_RNDIS_HandleTypeDef *)pdev->pClassData;
+
+ /* Use same Msg input buffer as response buffer */
+ USBD_CDC_RNDIS_StsChangeMsgTypeDef *Response = (USBD_CDC_RNDIS_StsChangeMsgTypeDef *)Msg;
+
+ /* Setup the response buffer content */
+ Response->MsgType = CDC_RNDIS_INDICATE_STATUS_MSG_ID;
+ Response->MsgLength = sizeof(USBD_CDC_RNDIS_StsChangeMsgTypeDef);
+ Response->Status = CDC_RNDIS_STATUS_NOT_SUPPORTED;
+ Response->StsBufLength = 0U;
+ Response->StsBufOffset = 20U;
+
+ /* Set Response Ready field in order to send response during next control request */
+ hcdc->ResponseRdy = 1U;
+
+ /* Send Notification on Interrupt EP to inform Host that response is ready */
+ (void)USBD_CDC_RNDIS_SendNotification(pdev, RESPONSE_AVAILABLE, 0U, NULL);
+
+ UNUSED(Msg);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Src/usbd_cdc_rndis_if_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Src/usbd_cdc_rndis_if_template.c
new file mode 100644
index 0000000000..9408d43bb4
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_RNDIS/Src/usbd_cdc_rndis_if_template.c
@@ -0,0 +1,233 @@
+/**
+ ******************************************************************************
+ * @file usbd_cdc_rndis_if_template.c
+ * @author MCD Application Team
+ * @brief Source file for USBD CDC_RNDIS interface template
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2019 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+
+/* Include TCP/IP stack header files */
+/*
+#include "lwip/opt.h"
+#include "lwip/init.h"
+#include "lwip/dhcp.h"
+#include "lwip/netif.h"
+#include "lwip/timeouts.h"
+#include "netif/etharp.h"
+#include "http_cgi_ssi.h"
+#include "ethernetif.h"
+*/
+
+#include "main.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #pragma data_alignment=4
+#endif
+__ALIGN_BEGIN uint8_t UserRxBuffer[CDC_RNDIS_ETH_MAX_SEGSZE + 100] __ALIGN_END; /* Received Data over USB are stored in this buffer */
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+ #pragma data_alignment=4
+#endif
+__ALIGN_BEGIN static uint8_t UserTxBuffer[CDC_RNDIS_ETH_MAX_SEGSZE + 100] __ALIGN_END; /* Received Data over CDC_RNDIS (CDC_RNDIS interface) are stored in this buffer */
+
+static uint8_t CDC_RNDISInitialized = 0U;
+
+/* USB handler declaration */
+extern USBD_HandleTypeDef USBD_Device;
+
+
+/* Private function prototypes -----------------------------------------------*/
+static int8_t CDC_RNDIS_Itf_Init(void);
+static int8_t CDC_RNDIS_Itf_DeInit(void);
+static int8_t CDC_RNDIS_Itf_Control(uint8_t cmd, uint8_t *pbuf, uint16_t length);
+static int8_t CDC_RNDIS_Itf_Receive(uint8_t *pbuf, uint32_t *Len);
+static int8_t CDC_RNDIS_Itf_TransmitCplt(uint8_t *pbuf, uint32_t *Len, uint8_t epnum);
+static int8_t CDC_RNDIS_Itf_Process(USBD_HandleTypeDef *pdev);
+
+USBD_CDC_RNDIS_ItfTypeDef USBD_CDC_RNDIS_fops =
+{
+ CDC_RNDIS_Itf_Init,
+ CDC_RNDIS_Itf_DeInit,
+ CDC_RNDIS_Itf_Control,
+ CDC_RNDIS_Itf_Receive,
+ CDC_RNDIS_Itf_TransmitCplt,
+ CDC_RNDIS_Itf_Process,
+ (uint8_t *)CDC_RNDIS_MAC_STR_DESC,
+};
+
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief CDC_RNDIS_Itf_Init
+ * Initializes the CDC_RNDIS media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_RNDIS_Itf_Init(void)
+{
+ if (CDC_RNDISInitialized == 0U)
+ {
+ /*
+ Initialize the LwIP stack
+ Add your code here
+
+ */
+
+ CDC_RNDISInitialized = 1U;
+ }
+
+ /* Set Application Buffers */
+ (void)USBD_CDC_RNDIS_SetTxBuffer(&USBD_Device, UserTxBuffer, 0U);
+ (void)USBD_CDC_RNDIS_SetRxBuffer(&USBD_Device, UserRxBuffer);
+
+ return (0);
+}
+
+/**
+ * @brief CDC_RNDIS_Itf_DeInit
+ * DeInitializes the CDC_RNDIS media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_RNDIS_Itf_DeInit(void)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc_cdc_rndis = (USBD_CDC_RNDIS_HandleTypeDef *)(USBD_Device.pClassData);
+
+ /*
+ Add your code here
+ */
+
+ /* Notify application layer that link is down */
+ hcdc_cdc_rndis->LinkStatus = 0U;
+
+ return (0);
+}
+
+/**
+ * @brief CDC_RNDIS_Itf_Control
+ * Manage the CDC_RNDIS class requests
+ * @param Cmd: Command code
+ * @param Buf: Buffer containing command data (request parameters)
+ * @param Len: Number of data to be sent (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_RNDIS_Itf_Control(uint8_t cmd, uint8_t *pbuf, uint16_t length)
+{
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc_cdc_rndis = (USBD_CDC_RNDIS_HandleTypeDef *)(USBD_Device.pClassData);
+
+ switch (cmd)
+ {
+ case CDC_RNDIS_SEND_ENCAPSULATED_COMMAND:
+ /* Add your code here */
+ break;
+
+ case CDC_RNDIS_GET_ENCAPSULATED_RESPONSE:
+ /* Check if this is the first time we enter */
+ if (hcdc_cdc_rndis->LinkStatus == 0U)
+ {
+ /* Setup the Link up at TCP/IP stack level */
+ hcdc_cdc_rndis->LinkStatus = 1U;
+ /*
+ Add your code here
+ */
+ }
+ /* Add your code here */
+ break;
+
+ default:
+ /* Add your code here */
+ break;
+ }
+
+ UNUSED(length);
+ UNUSED(pbuf);
+
+ return (0);
+}
+
+/**
+ * @brief CDC_RNDIS_Itf_Receive
+ * Data received over USB OUT endpoint are sent over CDC_RNDIS interface
+ * through this function.
+ * @param Buf: Buffer of data to be transmitted
+ * @param Len: Number of data received (in bytes)
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_RNDIS_Itf_Receive(uint8_t *Buf, uint32_t *Len)
+{
+ /* Get the CDC_RNDIS handler pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc_cdc_rndis = (USBD_CDC_RNDIS_HandleTypeDef *)(USBD_Device.pClassData);
+
+ /* Call Eth buffer processing */
+ hcdc_cdc_rndis->RxState = 1U;
+
+ UNUSED(Buf);
+ UNUSED(Len);
+
+ return (0);
+}
+
+/**
+ * @brief CDC_RNDIS_Itf_TransmitCplt
+ * Data transmited callback
+ *
+ * @note
+ * This function is IN transfer complete callback used to inform user that
+ * the submitted Data is successfully sent over USB.
+ *
+ * @param Buf: Buffer of data to be received
+ * @param Len: Number of data received (in bytes)
+ * @param epnum: EP number
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_RNDIS_Itf_TransmitCplt(uint8_t *Buf, uint32_t *Len, uint8_t epnum)
+{
+ UNUSED(Buf);
+ UNUSED(Len);
+ UNUSED(epnum);
+
+ return (0);
+}
+
+/**
+ * @brief CDC_RNDIS_Itf_Process
+ * Data received over USB OUT endpoint are sent over CDC_RNDIS interface
+ * through this function.
+ * @param pdef: pointer to the USB Device Handle
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t CDC_RNDIS_Itf_Process(USBD_HandleTypeDef *pdev)
+{
+ /* Get the CDC_RNDIS handler pointer */
+ USBD_CDC_RNDIS_HandleTypeDef *hcdc_cdc_rndis = (USBD_CDC_RNDIS_HandleTypeDef *)(pdev->pClassData);
+
+ if ((hcdc_cdc_rndis != NULL) && (hcdc_cdc_rndis->LinkStatus != 0U))
+ {
+ /*
+ Add your code here
+ Read a received packet from the Ethernet buffers and send it
+ to the lwIP for handling
+ */
+ }
+
+ return (0);
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Inc/usbd_customhid.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Inc/usbd_customhid.h
new file mode 100644
index 0000000000..a1dcd7ca7b
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Inc/usbd_customhid.h
@@ -0,0 +1,164 @@
+/**
+ ******************************************************************************
+ * @file usbd_customhid.h
+ * @author MCD Application Team
+ * @brief header file for the usbd_customhid.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_CUSTOMHID_H
+#define __USB_CUSTOMHID_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_CUSTOM_HID
+ * @brief This file is the Header file for USBD_customhid.c
+ * @{
+ */
+
+
+/** @defgroup USBD_CUSTOM_HID_Exported_Defines
+ * @{
+ */
+#define CUSTOM_HID_EPIN_ADDR 0x81U
+#define CUSTOM_HID_EPIN_SIZE 0x02U
+
+#define CUSTOM_HID_EPOUT_ADDR 0x01U
+#define CUSTOM_HID_EPOUT_SIZE 0x02U
+
+#define USB_CUSTOM_HID_CONFIG_DESC_SIZ 41U
+#define USB_CUSTOM_HID_DESC_SIZ 9U
+
+#ifndef CUSTOM_HID_HS_BINTERVAL
+#define CUSTOM_HID_HS_BINTERVAL 0x05U
+#endif /* CUSTOM_HID_HS_BINTERVAL */
+
+#ifndef CUSTOM_HID_FS_BINTERVAL
+#define CUSTOM_HID_FS_BINTERVAL 0x05U
+#endif /* CUSTOM_HID_FS_BINTERVAL */
+
+#ifndef USBD_CUSTOMHID_OUTREPORT_BUF_SIZE
+#define USBD_CUSTOMHID_OUTREPORT_BUF_SIZE 0x02U
+#endif /* USBD_CUSTOMHID_OUTREPORT_BUF_SIZE */
+
+#ifndef USBD_CUSTOM_HID_REPORT_DESC_SIZE
+#define USBD_CUSTOM_HID_REPORT_DESC_SIZE 163U
+#endif /* USBD_CUSTOM_HID_REPORT_DESC_SIZE */
+
+#define CUSTOM_HID_DESCRIPTOR_TYPE 0x21U
+#define CUSTOM_HID_REPORT_DESC 0x22U
+
+#define CUSTOM_HID_REQ_SET_PROTOCOL 0x0BU
+#define CUSTOM_HID_REQ_GET_PROTOCOL 0x03U
+
+#define CUSTOM_HID_REQ_SET_IDLE 0x0AU
+#define CUSTOM_HID_REQ_GET_IDLE 0x02U
+
+#define CUSTOM_HID_REQ_SET_REPORT 0x09U
+#define CUSTOM_HID_REQ_GET_REPORT 0x01U
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+typedef enum
+{
+ CUSTOM_HID_IDLE = 0U,
+ CUSTOM_HID_BUSY,
+} CUSTOM_HID_StateTypeDef;
+
+typedef struct _USBD_CUSTOM_HID_Itf
+{
+ uint8_t *pReport;
+ int8_t (* Init)(void);
+ int8_t (* DeInit)(void);
+ int8_t (* OutEvent)(uint8_t event_idx, uint8_t state);
+
+} USBD_CUSTOM_HID_ItfTypeDef;
+
+typedef struct
+{
+ uint8_t Report_buf[USBD_CUSTOMHID_OUTREPORT_BUF_SIZE];
+ uint32_t Protocol;
+ uint32_t IdleState;
+ uint32_t AltSetting;
+ uint32_t IsReportAvailable;
+ CUSTOM_HID_StateTypeDef state;
+} USBD_CUSTOM_HID_HandleTypeDef;
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_CUSTOM_HID;
+#define USBD_CUSTOM_HID_CLASS &USBD_CUSTOM_HID
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+uint8_t USBD_CUSTOM_HID_SendReport(USBD_HandleTypeDef *pdev,
+ uint8_t *report, uint16_t len);
+
+uint8_t USBD_CUSTOM_HID_ReceivePacket(USBD_HandleTypeDef *pdev);
+
+uint8_t USBD_CUSTOM_HID_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_CUSTOM_HID_ItfTypeDef *fops);
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_CUSTOMHID_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Inc/usbd_customhid_if_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Inc/usbd_customhid_if_template.h
new file mode 100644
index 0000000000..e39069383a
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Inc/usbd_customhid_if_template.h
@@ -0,0 +1,43 @@
+/**
+ ******************************************************************************
+ * @file usbd_customhid_if_template.h
+ * @author MCD Application Team
+ * @brief Header for usbd_customhid_if_template.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CUSTOMHID_IF_TEMPLATE_H
+#define __USBD_CUSTOMHID_IF_TEMPLATE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_customhid.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+extern USBD_CUSTOM_HID_ItfTypeDef USBD_CustomHID_template_fops;
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_CUSTOMHID_IF_TEMPLATE_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Src/usbd_customhid.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Src/usbd_customhid.c
new file mode 100644
index 0000000000..268027407f
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Src/usbd_customhid.c
@@ -0,0 +1,762 @@
+/**
+ ******************************************************************************
+ * @file usbd_customhid.c
+ * @author MCD Application Team
+ * @brief This file provides the CUSTOM_HID core functions.
+ *
+ * @verbatim
+ *
+ * ===================================================================
+ * CUSTOM_HID Class Description
+ * ===================================================================
+ * This module manages the CUSTOM_HID class V1.11 following the "Device Class Definition
+ * for Human Interface Devices (CUSTOM_HID) Version 1.11 Jun 27, 2001".
+ * This driver implements the following aspects of the specification:
+ * - The Boot Interface Subclass
+ * - Usage Page : Generic Desktop
+ * - Usage : Vendor
+ * - Collection : Application
+ *
+ * @note In HS mode and when the DMA is used, all variables and data structures
+ * dealing with the DMA during the transaction process should be 32-bit aligned.
+ *
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_customhid.h"
+#include "usbd_ctlreq.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_CUSTOM_HID
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_CUSTOM_HID_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CUSTOM_HID_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CUSTOM_HID_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+/** @defgroup USBD_CUSTOM_HID_Private_FunctionPrototypes
+ * @{
+ */
+
+static uint8_t USBD_CUSTOM_HID_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_CUSTOM_HID_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_CUSTOM_HID_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+
+static uint8_t USBD_CUSTOM_HID_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_CUSTOM_HID_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_CUSTOM_HID_EP0_RxReady(USBD_HandleTypeDef *pdev);
+
+static uint8_t *USBD_CUSTOM_HID_GetFSCfgDesc(uint16_t *length);
+static uint8_t *USBD_CUSTOM_HID_GetHSCfgDesc(uint16_t *length);
+static uint8_t *USBD_CUSTOM_HID_GetOtherSpeedCfgDesc(uint16_t *length);
+static uint8_t *USBD_CUSTOM_HID_GetDeviceQualifierDesc(uint16_t *length);
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CUSTOM_HID_Private_Variables
+ * @{
+ */
+
+USBD_ClassTypeDef USBD_CUSTOM_HID =
+{
+ USBD_CUSTOM_HID_Init,
+ USBD_CUSTOM_HID_DeInit,
+ USBD_CUSTOM_HID_Setup,
+ NULL, /*EP0_TxSent*/
+ USBD_CUSTOM_HID_EP0_RxReady, /*EP0_RxReady*/ /* STATUS STAGE IN */
+ USBD_CUSTOM_HID_DataIn, /*DataIn*/
+ USBD_CUSTOM_HID_DataOut,
+ NULL, /*SOF */
+ NULL,
+ NULL,
+ USBD_CUSTOM_HID_GetHSCfgDesc,
+ USBD_CUSTOM_HID_GetFSCfgDesc,
+ USBD_CUSTOM_HID_GetOtherSpeedCfgDesc,
+ USBD_CUSTOM_HID_GetDeviceQualifierDesc,
+};
+
+/* USB CUSTOM_HID device FS Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CUSTOM_HID_CfgFSDesc[USB_CUSTOM_HID_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_CUSTOM_HID_CONFIG_DESC_SIZ,
+ /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: bus powered */
+ 0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */
+
+ /************** Descriptor of CUSTOM HID interface ****************/
+ /* 09 */
+ 0x09, /* bLength: Interface Descriptor size*/
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints*/
+ 0x03, /* bInterfaceClass: CUSTOM_HID */
+ 0x00, /* bInterfaceSubClass : 1=BOOT, 0=no boot */
+ 0x00, /* nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse */
+ 0x00, /* iInterface: Index of string descriptor */
+ /******************** Descriptor of CUSTOM_HID *************************/
+ /* 18 */
+ 0x09, /* bLength: CUSTOM_HID Descriptor size */
+ CUSTOM_HID_DESCRIPTOR_TYPE, /* bDescriptorType: CUSTOM_HID */
+ 0x11, /* bCUSTOM_HIDUSTOM_HID: CUSTOM_HID Class Spec release number */
+ 0x01,
+ 0x00, /* bCountryCode: Hardware target country */
+ 0x01, /* bNumDescriptors: Number of CUSTOM_HID class descriptors to follow */
+ 0x22, /* bDescriptorType */
+ USBD_CUSTOM_HID_REPORT_DESC_SIZE, /* wItemLength: Total length of Report descriptor */
+ 0x00,
+ /******************** Descriptor of Custom HID endpoints ********************/
+ /* 27 */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: */
+
+ CUSTOM_HID_EPIN_ADDR, /* bEndpointAddress: Endpoint Address (IN) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ CUSTOM_HID_EPIN_SIZE, /* wMaxPacketSize: 2 Byte max */
+ 0x00,
+ CUSTOM_HID_FS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 34 */
+
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: */
+ CUSTOM_HID_EPOUT_ADDR, /* bEndpointAddress: Endpoint Address (OUT) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ CUSTOM_HID_EPOUT_SIZE, /* wMaxPacketSize: 2 Bytes max */
+ 0x00,
+ CUSTOM_HID_FS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 41 */
+};
+
+/* USB CUSTOM_HID device HS Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CUSTOM_HID_CfgHSDesc[USB_CUSTOM_HID_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_CUSTOM_HID_CONFIG_DESC_SIZ,
+ /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: bus powered */
+ 0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */
+
+ /************** Descriptor of CUSTOM HID interface ****************/
+ /* 09 */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints */
+ 0x03, /* bInterfaceClass: CUSTOM_HID */
+ 0x00, /* bInterfaceSubClass : 1=BOOT, 0=no boot */
+ 0x00, /* nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse */
+ 0, /* iInterface: Index of string descriptor */
+ /******************** Descriptor of CUSTOM_HID *************************/
+ /* 18 */
+ 0x09, /* bLength: CUSTOM_HID Descriptor size */
+ CUSTOM_HID_DESCRIPTOR_TYPE, /* bDescriptorType: CUSTOM_HID */
+ 0x11, /* bCUSTOM_HIDUSTOM_HID: CUSTOM_HID Class Spec release number */
+ 0x01,
+ 0x00, /* bCountryCode: Hardware target country */
+ 0x01, /* bNumDescriptors: Number of CUSTOM_HID class descriptors to follow */
+ 0x22, /* bDescriptorType */
+ USBD_CUSTOM_HID_REPORT_DESC_SIZE, /* wItemLength: Total length of Report descriptor */
+ 0x00,
+ /******************** Descriptor of Custom HID endpoints ********************/
+ /* 27 */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: */
+
+ CUSTOM_HID_EPIN_ADDR, /* bEndpointAddress: Endpoint Address (IN) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ CUSTOM_HID_EPIN_SIZE, /* wMaxPacketSize: 2 Byte max */
+ 0x00,
+ CUSTOM_HID_HS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 34 */
+
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: */
+ CUSTOM_HID_EPOUT_ADDR, /* bEndpointAddress: Endpoint Address (OUT) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ CUSTOM_HID_EPOUT_SIZE, /* wMaxPacketSize: 2 Bytes max */
+ 0x00,
+ CUSTOM_HID_HS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 41 */
+};
+
+/* USB CUSTOM_HID device Other Speed Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CUSTOM_HID_OtherSpeedCfgDesc[USB_CUSTOM_HID_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_CUSTOM_HID_CONFIG_DESC_SIZ,
+ /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: bus powered */
+ 0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */
+
+ /************** Descriptor of CUSTOM HID interface ****************/
+ /* 09 */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints */
+ 0x03, /* bInterfaceClass: CUSTOM_HID */
+ 0x00, /* bInterfaceSubClass : 1=BOOT, 0=no boot */
+ 0x00, /* nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse */
+ 0, /* iInterface: Index of string descriptor */
+ /******************** Descriptor of CUSTOM_HID *************************/
+ /* 18 */
+ 0x09, /* bLength: CUSTOM_HID Descriptor size */
+ CUSTOM_HID_DESCRIPTOR_TYPE, /* bDescriptorType: CUSTOM_HID */
+ 0x11, /* bCUSTOM_HIDUSTOM_HID: CUSTOM_HID Class Spec release number */
+ 0x01,
+ 0x00, /* bCountryCode: Hardware target country */
+ 0x01, /* bNumDescriptors: Number of CUSTOM_HID class descriptors to follow */
+ 0x22, /* bDescriptorType */
+ USBD_CUSTOM_HID_REPORT_DESC_SIZE, /* wItemLength: Total length of Report descriptor */
+ 0x00,
+ /******************** Descriptor of Custom HID endpoints ********************/
+ /* 27 */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: */
+
+ CUSTOM_HID_EPIN_ADDR, /* bEndpointAddress: Endpoint Address (IN) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ CUSTOM_HID_EPIN_SIZE, /* wMaxPacketSize: 2 Byte max */
+ 0x00,
+ CUSTOM_HID_FS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 34 */
+
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: */
+ CUSTOM_HID_EPOUT_ADDR, /* bEndpointAddress: Endpoint Address (OUT) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ CUSTOM_HID_EPOUT_SIZE, /* wMaxPacketSize: 2 Bytes max */
+ 0x00,
+ CUSTOM_HID_FS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 41 */
+};
+
+/* USB CUSTOM_HID device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CUSTOM_HID_Desc[USB_CUSTOM_HID_DESC_SIZ] __ALIGN_END =
+{
+ /* 18 */
+ 0x09, /* bLength: CUSTOM_HID Descriptor size */
+ CUSTOM_HID_DESCRIPTOR_TYPE, /* bDescriptorType: CUSTOM_HID */
+ 0x11, /* bCUSTOM_HIDUSTOM_HID: CUSTOM_HID Class Spec release number */
+ 0x01,
+ 0x00, /* bCountryCode: Hardware target country */
+ 0x01, /* bNumDescriptors: Number of CUSTOM_HID class descriptors to follow */
+ 0x22, /* bDescriptorType */
+ USBD_CUSTOM_HID_REPORT_DESC_SIZE, /* wItemLength: Total length of Report descriptor */
+ 0x00,
+};
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_CUSTOM_HID_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x40,
+ 0x01,
+ 0x00,
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CUSTOM_HID_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_CUSTOM_HID_Init
+ * Initialize the CUSTOM_HID interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_CUSTOM_HID_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+ USBD_CUSTOM_HID_HandleTypeDef *hhid;
+
+ hhid = USBD_malloc(sizeof(USBD_CUSTOM_HID_HandleTypeDef));
+
+ if (hhid == NULL)
+ {
+ pdev->pClassData = NULL;
+ return (uint8_t)USBD_EMEM;
+ }
+
+ pdev->pClassData = (void *)hhid;
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ pdev->ep_in[CUSTOM_HID_EPIN_ADDR & 0xFU].bInterval = CUSTOM_HID_HS_BINTERVAL;
+ pdev->ep_out[CUSTOM_HID_EPOUT_ADDR & 0xFU].bInterval = CUSTOM_HID_HS_BINTERVAL;
+ }
+ else /* LOW and FULL-speed endpoints */
+ {
+ pdev->ep_in[CUSTOM_HID_EPIN_ADDR & 0xFU].bInterval = CUSTOM_HID_FS_BINTERVAL;
+ pdev->ep_out[CUSTOM_HID_EPOUT_ADDR & 0xFU].bInterval = CUSTOM_HID_FS_BINTERVAL;
+ }
+
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, CUSTOM_HID_EPIN_ADDR, USBD_EP_TYPE_INTR,
+ CUSTOM_HID_EPIN_SIZE);
+
+ pdev->ep_in[CUSTOM_HID_EPIN_ADDR & 0xFU].is_used = 1U;
+
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, CUSTOM_HID_EPOUT_ADDR, USBD_EP_TYPE_INTR,
+ CUSTOM_HID_EPOUT_SIZE);
+
+ pdev->ep_out[CUSTOM_HID_EPOUT_ADDR & 0xFU].is_used = 1U;
+
+ hhid->state = CUSTOM_HID_IDLE;
+
+ ((USBD_CUSTOM_HID_ItfTypeDef *)pdev->pUserData)->Init();
+
+ /* Prepare Out endpoint to receive 1st packet */
+ (void)USBD_LL_PrepareReceive(pdev, CUSTOM_HID_EPOUT_ADDR, hhid->Report_buf,
+ USBD_CUSTOMHID_OUTREPORT_BUF_SIZE);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CUSTOM_HID_Init
+ * DeInitialize the CUSTOM_HID layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_CUSTOM_HID_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ /* Close CUSTOM_HID EP IN */
+ (void)USBD_LL_CloseEP(pdev, CUSTOM_HID_EPIN_ADDR);
+ pdev->ep_in[CUSTOM_HID_EPIN_ADDR & 0xFU].is_used = 0U;
+ pdev->ep_in[CUSTOM_HID_EPIN_ADDR & 0xFU].bInterval = 0U;
+
+ /* Close CUSTOM_HID EP OUT */
+ (void)USBD_LL_CloseEP(pdev, CUSTOM_HID_EPOUT_ADDR);
+ pdev->ep_out[CUSTOM_HID_EPOUT_ADDR & 0xFU].is_used = 0U;
+ pdev->ep_out[CUSTOM_HID_EPOUT_ADDR & 0xFU].bInterval = 0U;
+
+ /* FRee allocated memory */
+ if (pdev->pClassData != NULL)
+ {
+ ((USBD_CUSTOM_HID_ItfTypeDef *)pdev->pUserData)->DeInit();
+ USBD_free(pdev->pClassData);
+ pdev->pClassData = NULL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CUSTOM_HID_Setup
+ * Handle the CUSTOM_HID specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_CUSTOM_HID_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req)
+{
+ USBD_CUSTOM_HID_HandleTypeDef *hhid = (USBD_CUSTOM_HID_HandleTypeDef *)pdev->pClassData;
+ uint16_t len = 0U;
+ uint8_t *pbuf = NULL;
+ uint16_t status_info = 0U;
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS:
+ switch (req->bRequest)
+ {
+ case CUSTOM_HID_REQ_SET_PROTOCOL:
+ hhid->Protocol = (uint8_t)(req->wValue);
+ break;
+
+ case CUSTOM_HID_REQ_GET_PROTOCOL:
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&hhid->Protocol, 1U);
+ break;
+
+ case CUSTOM_HID_REQ_SET_IDLE:
+ hhid->IdleState = (uint8_t)(req->wValue >> 8);
+ break;
+
+ case CUSTOM_HID_REQ_GET_IDLE:
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&hhid->IdleState, 1U);
+ break;
+
+ case CUSTOM_HID_REQ_SET_REPORT:
+ hhid->IsReportAvailable = 1U;
+ (void)USBD_CtlPrepareRx(pdev, hhid->Report_buf, req->wLength);
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_DESCRIPTOR:
+ if ((req->wValue >> 8) == CUSTOM_HID_REPORT_DESC)
+ {
+ len = MIN(USBD_CUSTOM_HID_REPORT_DESC_SIZE, req->wLength);
+ pbuf = ((USBD_CUSTOM_HID_ItfTypeDef *)pdev->pUserData)->pReport;
+ }
+ else
+ {
+ if ((req->wValue >> 8) == CUSTOM_HID_DESCRIPTOR_TYPE)
+ {
+ pbuf = USBD_CUSTOM_HID_Desc;
+ len = MIN(USB_CUSTOM_HID_DESC_SIZ, req->wLength);
+ }
+ }
+
+ (void)USBD_CtlSendData(pdev, pbuf, len);
+ break;
+
+ case USB_REQ_GET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&hhid->AltSetting, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ hhid->AltSetting = (uint8_t)(req->wValue);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ return (uint8_t)ret;
+}
+
+/**
+ * @brief USBD_CUSTOM_HID_SendReport
+ * Send CUSTOM_HID Report
+ * @param pdev: device instance
+ * @param buff: pointer to report
+ * @retval status
+ */
+uint8_t USBD_CUSTOM_HID_SendReport(USBD_HandleTypeDef *pdev,
+ uint8_t *report, uint16_t len)
+{
+ USBD_CUSTOM_HID_HandleTypeDef *hhid;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ hhid = (USBD_CUSTOM_HID_HandleTypeDef*)pdev->pClassData;
+
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ if (hhid->state == CUSTOM_HID_IDLE)
+ {
+ hhid->state = CUSTOM_HID_BUSY;
+ (void)USBD_LL_Transmit(pdev, CUSTOM_HID_EPIN_ADDR, report, len);
+ }
+ else
+ {
+ return (uint8_t)USBD_BUSY;
+ }
+ }
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CUSTOM_HID_GetFSCfgDesc
+ * return FS configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CUSTOM_HID_GetFSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CUSTOM_HID_CfgFSDesc);
+
+ return USBD_CUSTOM_HID_CfgFSDesc;
+}
+
+/**
+ * @brief USBD_CUSTOM_HID_GetHSCfgDesc
+ * return HS configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CUSTOM_HID_GetHSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CUSTOM_HID_CfgHSDesc);
+
+ return USBD_CUSTOM_HID_CfgHSDesc;
+}
+
+/**
+ * @brief USBD_CUSTOM_HID_GetOtherSpeedCfgDesc
+ * return other speed configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_CUSTOM_HID_GetOtherSpeedCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CUSTOM_HID_OtherSpeedCfgDesc);
+
+ return USBD_CUSTOM_HID_OtherSpeedCfgDesc;
+}
+
+/**
+ * @brief USBD_CUSTOM_HID_DataIn
+ * handle data IN Stage
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_CUSTOM_HID_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ UNUSED(epnum);
+
+ /* Ensure that the FIFO is empty before a new transfer, this condition could
+ be caused by a new transfer before the end of the previous transfer */
+ ((USBD_CUSTOM_HID_HandleTypeDef *)pdev->pClassData)->state = CUSTOM_HID_IDLE;
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_CUSTOM_HID_DataOut
+ * handle data OUT Stage
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_CUSTOM_HID_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ UNUSED(epnum);
+ USBD_CUSTOM_HID_HandleTypeDef *hhid;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ hhid = (USBD_CUSTOM_HID_HandleTypeDef*)pdev->pClassData;
+
+ /* USB data will be immediately processed, this allow next USB traffic being
+ NAKed till the end of the application processing */
+ ((USBD_CUSTOM_HID_ItfTypeDef *)pdev->pUserData)->OutEvent(hhid->Report_buf[0],
+ hhid->Report_buf[1]);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CUSTOM_HID_ReceivePacket
+ * prepare OUT Endpoint for reception
+ * @param pdev: device instance
+ * @retval status
+ */
+uint8_t USBD_CUSTOM_HID_ReceivePacket(USBD_HandleTypeDef *pdev)
+{
+ USBD_CUSTOM_HID_HandleTypeDef *hhid;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ hhid = (USBD_CUSTOM_HID_HandleTypeDef*)pdev->pClassData;
+
+ /* Resume USB Out process */
+ (void)USBD_LL_PrepareReceive(pdev, CUSTOM_HID_EPOUT_ADDR, hhid->Report_buf,
+ USBD_CUSTOMHID_OUTREPORT_BUF_SIZE);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+ * @brief USBD_CUSTOM_HID_EP0_RxReady
+ * Handles control request data.
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_CUSTOM_HID_EP0_RxReady(USBD_HandleTypeDef *pdev)
+{
+ USBD_CUSTOM_HID_HandleTypeDef *hhid = (USBD_CUSTOM_HID_HandleTypeDef *)pdev->pClassData;
+
+ if (hhid->IsReportAvailable == 1U)
+ {
+ ((USBD_CUSTOM_HID_ItfTypeDef *)pdev->pUserData)->OutEvent(hhid->Report_buf[0],
+ hhid->Report_buf[1]);
+ hhid->IsReportAvailable = 0U;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+* @brief DeviceQualifierDescriptor
+* return Device Qualifier descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+static uint8_t *USBD_CUSTOM_HID_GetDeviceQualifierDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_CUSTOM_HID_DeviceQualifierDesc);
+
+ return USBD_CUSTOM_HID_DeviceQualifierDesc;
+}
+
+/**
+* @brief USBD_CUSTOM_HID_RegisterInterface
+ * @param pdev: device instance
+ * @param fops: CUSTOMHID Interface callback
+ * @retval status
+ */
+uint8_t USBD_CUSTOM_HID_RegisterInterface(USBD_HandleTypeDef *pdev,
+ USBD_CUSTOM_HID_ItfTypeDef *fops)
+{
+ if (fops == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ pdev->pUserData = fops;
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Src/usbd_customhid_if_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Src/usbd_customhid_if_template.c
new file mode 100644
index 0000000000..1fb6edd16d
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CustomHID/Src/usbd_customhid_if_template.c
@@ -0,0 +1,91 @@
+/**
+ ******************************************************************************
+ * @file usbd_customhid_if_template.c
+ * @author MCD Application Team
+ * @brief USB Device Custom HID interface file.
+ * This template should be copied to the user folder, renamed and customized
+ * following user needs.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_customhid_if_template.h"
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+
+static int8_t TEMPLATE_CUSTOM_HID_Init(void);
+static int8_t TEMPLATE_CUSTOM_HID_DeInit(void);
+static int8_t TEMPLATE_CUSTOM_HID_OutEvent(uint8_t event_idx, uint8_t state);
+/* Private variables ---------------------------------------------------------*/
+USBD_CUSTOM_HID_ItfTypeDef USBD_CustomHID_template_fops =
+{
+ TEMPLATE_CUSTOM_HID_ReportDesc,
+ TEMPLATE_CUSTOM_HID_Init,
+ TEMPLATE_CUSTOM_HID_DeInit,
+ TEMPLATE_CUSTOM_HID_OutEvent,
+};
+
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief TEMPLATE_CUSTOM_HID_Init
+ * Initializes the CUSTOM HID media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_CUSTOM_HID_Init(void)
+{
+ return (0);
+}
+
+/**
+ * @brief TEMPLATE_CUSTOM_HID_DeInit
+ * DeInitializes the CUSTOM HID media low layer
+ * @param None
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_CUSTOM_HID_DeInit(void)
+{
+ /*
+ Add your deinitialization code here
+ */
+ return (0);
+}
+
+
+/**
+ * @brief TEMPLATE_CUSTOM_HID_Control
+ * Manage the CUSTOM HID class events
+ * @param event_idx: event index
+ * @param state: event state
+ * @retval Result of the operation: USBD_OK if all operations are OK else USBD_FAIL
+ */
+static int8_t TEMPLATE_CUSTOM_HID_OutEvent(uint8_t event_idx, uint8_t state)
+{
+ UNUSED(event_idx);
+ UNUSED(state);
+
+ /* Start next USB packet transfer once data processing is completed */
+ USBD_CUSTOM_HID_ReceivePacket(&USBD_Device);
+
+ return (0);
+}
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Inc/usbd_dfu.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Inc/usbd_dfu.h
new file mode 100644
index 0000000000..307c96d931
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Inc/usbd_dfu.h
@@ -0,0 +1,235 @@
+/**
+ ******************************************************************************
+ * @file usbd_dfu.h
+ * @author MCD Application Team
+ * @brief Header file for the usbd_dfu.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_DFU_H
+#define __USB_DFU_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_DFU
+ * @brief This file is the Header file for usbd_dfu.c
+ * @{
+ */
+
+
+/** @defgroup USBD_DFU_Exported_Defines
+ * @{
+ */
+#ifndef USBD_DFU_MAX_ITF_NUM
+#define USBD_DFU_MAX_ITF_NUM 1U
+#endif /* USBD_DFU_MAX_ITF_NUM */
+
+#ifndef USBD_DFU_XFER_SIZE
+#define USBD_DFU_XFER_SIZE 1024U
+#endif /* USBD_DFU_XFER_SIZE */
+
+#ifndef USBD_DFU_APP_DEFAULT_ADD
+#define USBD_DFU_APP_DEFAULT_ADD 0x08008000U /* The first sector (32 KB) is reserved for DFU code */
+#endif /* USBD_DFU_APP_DEFAULT_ADD */
+
+#define USB_DFU_CONFIG_DESC_SIZ (18U + (9U * USBD_DFU_MAX_ITF_NUM))
+#define USB_DFU_DESC_SIZ 9U
+
+#define DFU_DESCRIPTOR_TYPE 0x21U
+
+
+/**************************************************/
+/* DFU Requests DFU states */
+/**************************************************/
+#define APP_STATE_IDLE 0U
+#define APP_STATE_DETACH 1U
+#define DFU_STATE_IDLE 2U
+#define DFU_STATE_DNLOAD_SYNC 3U
+#define DFU_STATE_DNLOAD_BUSY 4U
+#define DFU_STATE_DNLOAD_IDLE 5U
+#define DFU_STATE_MANIFEST_SYNC 6U
+#define DFU_STATE_MANIFEST 7U
+#define DFU_STATE_MANIFEST_WAIT_RESET 8U
+#define DFU_STATE_UPLOAD_IDLE 9U
+#define DFU_STATE_ERROR 10U
+
+/**************************************************/
+/* DFU errors */
+/**************************************************/
+#define DFU_ERROR_NONE 0x00U
+#define DFU_ERROR_TARGET 0x01U
+#define DFU_ERROR_FILE 0x02U
+#define DFU_ERROR_WRITE 0x03U
+#define DFU_ERROR_ERASE 0x04U
+#define DFU_ERROR_CHECK_ERASED 0x05U
+#define DFU_ERROR_PROG 0x06U
+#define DFU_ERROR_VERIFY 0x07U
+#define DFU_ERROR_ADDRESS 0x08U
+#define DFU_ERROR_NOTDONE 0x09U
+#define DFU_ERROR_FIRMWARE 0x0AU
+#define DFU_ERROR_VENDOR 0x0BU
+#define DFU_ERROR_USB 0x0CU
+#define DFU_ERROR_POR 0x0DU
+#define DFU_ERROR_UNKNOWN 0x0EU
+#define DFU_ERROR_STALLEDPKT 0x0FU
+
+/**************************************************/
+/* DFU Manifestation State */
+/**************************************************/
+#define DFU_MANIFEST_COMPLETE 0x00U
+#define DFU_MANIFEST_IN_PROGRESS 0x01U
+
+
+/**************************************************/
+/* Special Commands with Download Request */
+/**************************************************/
+#define DFU_CMD_GETCOMMANDS 0x00U
+#define DFU_CMD_SETADDRESSPOINTER 0x21U
+#define DFU_CMD_ERASE 0x41U
+
+#define DFU_MEDIA_ERASE 0x00U
+#define DFU_MEDIA_PROGRAM 0x01U
+
+/**************************************************/
+/* Other defines */
+/**************************************************/
+/* Bit Detach capable = bit 3 in bmAttributes field */
+#define DFU_DETACH_MASK (1U << 4)
+#define DFU_STATUS_DEPTH 6U
+
+typedef enum
+{
+ DFU_DETACH = 0U,
+ DFU_DNLOAD,
+ DFU_UPLOAD,
+ DFU_GETSTATUS,
+ DFU_CLRSTATUS,
+ DFU_GETSTATE,
+ DFU_ABORT
+} DFU_RequestTypeDef;
+
+typedef void (*pFunction)(void);
+
+
+/********** Descriptor of DFU interface 0 Alternate setting n ****************/
+#define USBD_DFU_IF_DESC(n) 0x09, /* bLength: Interface Descriptor size */ \
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType */ \
+ 0x00, /* bInterfaceNumber: Number of Interface */ \
+ (n), /* bAlternateSetting: Alternate setting */ \
+ 0x00, /* bNumEndpoints*/ \
+ 0xFE, /* bInterfaceClass: Application Specific Class Code */ \
+ 0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */ \
+ 0x02, /* nInterfaceProtocol: DFU mode protocol */ \
+ USBD_IDX_INTERFACE_STR + (n) + 1U /* iInterface: Index of string descriptor */ \
+
+#define TRANSFER_SIZE_BYTES(size) ((uint8_t)(size)), /* XFERSIZEB0 */\
+ ((uint8_t)((size) >> 8)) /* XFERSIZEB1 */
+
+#define IS_PROTECTED_AREA(add) (uint8_t)((((add) >= 0x08000000) && ((add) < (APP_DEFAULT_ADD)))? 1:0)
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+
+typedef struct
+{
+ union
+ {
+ uint32_t d32[USBD_DFU_XFER_SIZE / 4U];
+ uint8_t d8[USBD_DFU_XFER_SIZE];
+ } buffer;
+
+ uint32_t wblock_num;
+ uint32_t wlength;
+ uint32_t data_ptr;
+ uint32_t alt_setting;
+
+ uint8_t dev_status[DFU_STATUS_DEPTH];
+ uint8_t ReservedForAlign[2];
+ uint8_t dev_state;
+ uint8_t manif_state;
+} USBD_DFU_HandleTypeDef;
+
+typedef struct
+{
+ const uint8_t *pStrDesc;
+ uint16_t (* Init)(void);
+ uint16_t (* DeInit)(void);
+ uint16_t (* Erase)(uint32_t Add);
+ uint16_t (* Write)(uint8_t *src, uint8_t *dest, uint32_t Len);
+ uint8_t *(* Read)(uint8_t *src, uint8_t *dest, uint32_t Len);
+ uint16_t (* GetStatus)(uint32_t Add, uint8_t cmd, uint8_t *buff);
+} USBD_DFU_MediaTypeDef;
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_DFU;
+#define USBD_DFU_CLASS &USBD_DFU
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+uint8_t USBD_DFU_RegisterMedia(USBD_HandleTypeDef *pdev,
+ USBD_DFU_MediaTypeDef *fops);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_DFU_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Inc/usbd_dfu_media_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Inc/usbd_dfu_media_template.h
new file mode 100644
index 0000000000..1ba14227c9
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Inc/usbd_dfu_media_template.h
@@ -0,0 +1,97 @@
+/**
+ ******************************************************************************
+ * @file usbd_dfu_media_template.h
+ * @author MCD Application Team
+ * @brief header file for the usbd_dfu_media_template.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_DFU_MEDIA_TEMPLATE_H
+#define __USBD_DFU_MEDIA_TEMPLATE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_dfu.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_MEDIA
+ * @brief header file for the usbd_dfu_media_template.c file
+ * @{
+ */
+
+/** @defgroup USBD_MEDIA_Exported_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_MEDIA_Exported_Types
+ * @{
+ */
+
+
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_MEDIA_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_MEDIA_Exported_Variables
+ * @{
+ */
+extern USBD_DFU_MediaTypeDef USBD_DFU_MEDIA_Template_fops;
+/**
+ * @}
+ */
+
+/** @defgroup USBD_MEDIA_Exported_FunctionsPrototype
+ * @{
+ */
+
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_DFU_MEDIA_TEMPLATE_H */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Src/usbd_dfu.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Src/usbd_dfu.c
new file mode 100644
index 0000000000..d179650b1a
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Src/usbd_dfu.c
@@ -0,0 +1,1063 @@
+/**
+ ******************************************************************************
+ * @file usbd_dfu.c
+ * @author MCD Application Team
+ * @brief This file provides the DFU core functions.
+ *
+ * @verbatim
+ *
+ * ===================================================================
+ * DFU Class Driver Description
+ * ===================================================================
+ * This driver manages the DFU class V1.1 following the "Device Class Specification for
+ * Device Firmware Upgrade Version 1.1 Aug 5, 2004".
+ * This driver implements the following aspects of the specification:
+ * - Device descriptor management
+ * - Configuration descriptor management
+ * - Enumeration as DFU device (in DFU mode only)
+ * - Requests management (supporting ST DFU sub-protocol)
+ * - Memory operations management (Download/Upload/Erase/Detach/GetState/GetStatus)
+ * - DFU state machine implementation.
+ *
+ * @note
+ * ST DFU sub-protocol is compliant with DFU protocol and use sub-requests to manage
+ * memory addressing, commands processing, specific memories operations (ie. Erase) ...
+ * As required by the DFU specification, only endpoint 0 is used in this application.
+ * Other endpoints and functions may be added to the application (ie. DFU ...)
+ *
+ * These aspects may be enriched or modified for a specific user application.
+ *
+ * This driver doesn't implement the following aspects of the specification
+ * (but it is possible to manage these features with some modifications on this driver):
+ * - Manifestation Tolerant mode
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_dfu.h"
+#include "usbd_ctlreq.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_DFU
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_DFU_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_DFU_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_DFU_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_DFU_Private_FunctionPrototypes
+ * @{
+ */
+
+static uint8_t USBD_DFU_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_DFU_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_DFU_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static uint8_t USBD_DFU_EP0_RxReady(USBD_HandleTypeDef *pdev);
+static uint8_t USBD_DFU_EP0_TxReady(USBD_HandleTypeDef *pdev);
+static uint8_t USBD_DFU_SOF(USBD_HandleTypeDef *pdev);
+
+static uint8_t *USBD_DFU_GetCfgDesc(uint16_t *length);
+static uint8_t *USBD_DFU_GetDeviceQualifierDesc(uint16_t *length);
+
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+static uint8_t *USBD_DFU_GetUsrStringDesc(USBD_HandleTypeDef *pdev,
+ uint8_t index, uint16_t *length);
+#endif
+
+static void DFU_Detach(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void DFU_Download(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void DFU_Upload(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void DFU_GetStatus(USBD_HandleTypeDef *pdev);
+static void DFU_ClearStatus(USBD_HandleTypeDef *pdev);
+static void DFU_GetState(USBD_HandleTypeDef *pdev);
+static void DFU_Abort(USBD_HandleTypeDef *pdev);
+static void DFU_Leave(USBD_HandleTypeDef *pdev);
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DFU_Private_Variables
+ * @{
+ */
+
+USBD_ClassTypeDef USBD_DFU =
+{
+ USBD_DFU_Init,
+ USBD_DFU_DeInit,
+ USBD_DFU_Setup,
+ USBD_DFU_EP0_TxReady,
+ USBD_DFU_EP0_RxReady,
+ NULL,
+ NULL,
+ USBD_DFU_SOF,
+ NULL,
+ NULL,
+ USBD_DFU_GetCfgDesc,
+ USBD_DFU_GetCfgDesc,
+ USBD_DFU_GetCfgDesc,
+ USBD_DFU_GetDeviceQualifierDesc,
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+ USBD_DFU_GetUsrStringDesc
+#endif
+};
+
+/* USB DFU device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_DFU_CfgDesc[USB_DFU_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuation Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_DFU_CONFIG_DESC_SIZ,
+ /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x02, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xC0, /* bmAttributes: bus powered and Supprts Remote Wakeup */
+ 0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */
+ /* 09 */
+
+ /********** Descriptor of DFU interface 0 Alternate setting 0 **************/
+ USBD_DFU_IF_DESC(0U), /* This interface is mandatory for all devices */
+
+#if (USBD_DFU_MAX_ITF_NUM > 1U)
+ /********** Descriptor of DFU interface 0 Alternate setting 1 **************/
+ USBD_DFU_IF_DESC(1),
+#endif /* (USBD_DFU_MAX_ITF_NUM > 1) */
+
+#if (USBD_DFU_MAX_ITF_NUM > 2U)
+ /********** Descriptor of DFU interface 0 Alternate setting 2 **************/
+ USBD_DFU_IF_DESC(2),
+#endif /* (USBD_DFU_MAX_ITF_NUM > 2) */
+
+#if (USBD_DFU_MAX_ITF_NUM > 3U)
+ /********** Descriptor of DFU interface 0 Alternate setting 3 **************/
+ USBD_DFU_IF_DESC(3),
+#endif /* (USBD_DFU_MAX_ITF_NUM > 3) */
+
+#if (USBD_DFU_MAX_ITF_NUM > 4U)
+ /********** Descriptor of DFU interface 0 Alternate setting 4 **************/
+ USBD_DFU_IF_DESC(4),
+#endif /* (USBD_DFU_MAX_ITF_NUM > 4) */
+
+#if (USBD_DFU_MAX_ITF_NUM > 5U)
+ /********** Descriptor of DFU interface 0 Alternate setting 5 **************/
+ USBD_DFU_IF_DESC(5),
+#endif /* (USBD_DFU_MAX_ITF_NUM > 5) */
+
+#if (USBD_DFU_MAX_ITF_NUM > 6U)
+#error "ERROR: usbd_dfu_core.c: Modify the file to support more descriptors!"
+#endif /* (USBD_DFU_MAX_ITF_NUM > 6) */
+
+ /******************** DFU Functional Descriptor********************/
+ 0x09, /* blength = 9 Bytes */
+ DFU_DESCRIPTOR_TYPE, /* DFU Functional Descriptor */
+ 0x0B, /* bmAttribute:
+ bitCanDnload = 1 (bit 0)
+ bitCanUpload = 1 (bit 1)
+ bitManifestationTolerant = 0 (bit 2)
+ bitWillDetach = 1 (bit 3)
+ Reserved (bit4-6)
+ bitAcceleratedST = 0 (bit 7) */
+ 0xFF, /* DetachTimeOut= 255 ms*/
+ 0x00,
+ /* WARNING: In DMA mode the multiple MPS packets feature is still not supported
+ ==> In this case, when using DMA USBD_DFU_XFER_SIZE should be set to 64 in usbd_conf.h */
+ TRANSFER_SIZE_BYTES(USBD_DFU_XFER_SIZE), /* TransferSize = 1024 Byte */
+ 0x1A, /* bcdDFUVersion */
+ 0x01
+ /***********************************************************/
+ /* 9*/
+};
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_DFU_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x40,
+ 0x01,
+ 0x00,
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DFU_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_DFU_Init
+ * Initialize the DFU interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_DFU_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ USBD_DFU_HandleTypeDef *hdfu;
+
+ /* Allocate Audio structure */
+ hdfu = USBD_malloc(sizeof(USBD_DFU_HandleTypeDef));
+
+ if (hdfu == NULL)
+ {
+ pdev->pClassData = NULL;
+ return (uint8_t)USBD_EMEM;
+ }
+
+ pdev->pClassData = (void *)hdfu;
+
+ hdfu->alt_setting = 0U;
+ hdfu->data_ptr = USBD_DFU_APP_DEFAULT_ADD;
+ hdfu->wblock_num = 0U;
+ hdfu->wlength = 0U;
+
+ hdfu->manif_state = DFU_MANIFEST_COMPLETE;
+ hdfu->dev_state = DFU_STATE_IDLE;
+
+ hdfu->dev_status[0] = DFU_ERROR_NONE;
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = DFU_STATE_IDLE;
+ hdfu->dev_status[5] = 0U;
+
+ /* Initialize Hardware layer */
+ if (((USBD_DFU_MediaTypeDef *)pdev->pUserData)->Init() != USBD_OK)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_DFU_Init
+ * De-Initialize the DFU layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_DFU_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+ USBD_DFU_HandleTypeDef *hdfu;
+
+ if (pdev->pClassData == NULL)
+ {
+ return (uint8_t)USBD_EMEM;
+ }
+
+ hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+ hdfu->wblock_num = 0U;
+ hdfu->wlength = 0U;
+
+ hdfu->dev_state = DFU_STATE_IDLE;
+ hdfu->dev_status[0] = DFU_ERROR_NONE;
+ hdfu->dev_status[4] = DFU_STATE_IDLE;
+
+ /* DeInit physical Interface components and Hardware Layer */
+ ((USBD_DFU_MediaTypeDef *)pdev->pUserData)->DeInit();
+ USBD_free(pdev->pClassData);
+ pdev->pClassData = NULL;
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_DFU_Setup
+ * Handle the DFU specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_DFU_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+ USBD_StatusTypeDef ret = USBD_OK;
+ uint8_t *pbuf = NULL;
+ uint16_t len = 0U;
+ uint16_t status_info = 0U;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS:
+ switch (req->bRequest)
+ {
+ case DFU_DNLOAD:
+ DFU_Download(pdev, req);
+ break;
+
+ case DFU_UPLOAD:
+ DFU_Upload(pdev, req);
+ break;
+
+ case DFU_GETSTATUS:
+ DFU_GetStatus(pdev);
+ break;
+
+ case DFU_CLRSTATUS:
+ DFU_ClearStatus(pdev);
+ break;
+
+ case DFU_GETSTATE:
+ DFU_GetState(pdev);
+ break;
+
+ case DFU_ABORT:
+ DFU_Abort(pdev);
+ break;
+
+ case DFU_DETACH:
+ DFU_Detach(pdev, req);
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_DESCRIPTOR:
+ if ((req->wValue >> 8) == DFU_DESCRIPTOR_TYPE)
+ {
+ pbuf = USBD_DFU_CfgDesc + (9U * (USBD_DFU_MAX_ITF_NUM + 1U));
+ len = MIN(USB_DFU_DESC_SIZ, req->wLength);
+ }
+
+ (void)USBD_CtlSendData(pdev, pbuf, len);
+ break;
+
+ case USB_REQ_GET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)hdfu->alt_setting, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ if ((uint8_t)(req->wValue) < USBD_DFU_MAX_ITF_NUM)
+ {
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ hdfu->alt_setting = (uint8_t)(req->wValue);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ }
+ else
+ {
+ /* Call the error management function (command will be nacked */
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+
+/**
+ * @brief USBD_DFU_GetCfgDesc
+ * return configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_DFU_GetCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_DFU_CfgDesc);
+
+ return USBD_DFU_CfgDesc;
+}
+
+
+/**
+ * @brief USBD_DFU_EP0_RxReady
+ * handle EP0 Rx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_DFU_EP0_RxReady(USBD_HandleTypeDef *pdev)
+{
+ UNUSED(pdev);
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_DFU_EP0_TxReady
+ * handle EP0 TRx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_DFU_EP0_TxReady(USBD_HandleTypeDef *pdev)
+{
+ USBD_SetupReqTypedef req;
+ uint32_t addr;
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+ USBD_DFU_MediaTypeDef *DfuInterface = (USBD_DFU_MediaTypeDef *)pdev->pUserData;
+
+ if (hdfu->dev_state == DFU_STATE_DNLOAD_BUSY)
+ {
+ /* Decode the Special Command*/
+ if (hdfu->wblock_num == 0U)
+ {
+ if(hdfu->wlength == 1U)
+ {
+ if (hdfu->buffer.d8[0] == DFU_CMD_GETCOMMANDS)
+ {
+ /* nothink to do */
+ }
+ }
+ else if (hdfu->wlength == 5U)
+ {
+ if (hdfu->buffer.d8[0] == DFU_CMD_SETADDRESSPOINTER)
+ {
+ hdfu->data_ptr = hdfu->buffer.d8[1];
+ hdfu->data_ptr += (uint32_t)hdfu->buffer.d8[2] << 8;
+ hdfu->data_ptr += (uint32_t)hdfu->buffer.d8[3] << 16;
+ hdfu->data_ptr += (uint32_t)hdfu->buffer.d8[4] << 24;
+ }
+ else if (hdfu->buffer.d8[0] == DFU_CMD_ERASE)
+ {
+ hdfu->data_ptr = hdfu->buffer.d8[1];
+ hdfu->data_ptr += (uint32_t)hdfu->buffer.d8[2] << 8;
+ hdfu->data_ptr += (uint32_t)hdfu->buffer.d8[3] << 16;
+ hdfu->data_ptr += (uint32_t)hdfu->buffer.d8[4] << 24;
+
+ if (DfuInterface->Erase(hdfu->data_ptr) != USBD_OK)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+ }
+ else
+ {
+ /* .. */
+ }
+ }
+ else
+ {
+ /* Reset the global length and block number */
+ hdfu->wlength = 0U;
+ hdfu->wblock_num = 0U;
+ /* Call the error management function (command will be nacked) */
+ req.bmRequest = 0U;
+ req.wLength = 1U;
+ USBD_CtlError(pdev, &req);
+ }
+ }
+ /* Regular Download Command */
+ else
+ {
+ if (hdfu->wblock_num > 1U)
+ {
+ /* Decode the required address */
+ addr = ((hdfu->wblock_num - 2U) * USBD_DFU_XFER_SIZE) + hdfu->data_ptr;
+
+ /* Preform the write operation */
+ if (DfuInterface->Write(hdfu->buffer.d8, (uint8_t *)addr, hdfu->wlength) != USBD_OK)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+ }
+ }
+
+ /* Reset the global length and block number */
+ hdfu->wlength = 0U;
+ hdfu->wblock_num = 0U;
+
+ /* Update the state machine */
+ hdfu->dev_state = DFU_STATE_DNLOAD_SYNC;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+ }
+ else if (hdfu->dev_state == DFU_STATE_MANIFEST)/* Manifestation in progress */
+ {
+ /* Start leaving DFU mode */
+ DFU_Leave(pdev);
+ }
+ else
+ {
+ /* .. */
+ }
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_DFU_SOF
+ * handle SOF event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_DFU_SOF(USBD_HandleTypeDef *pdev)
+{
+ UNUSED(pdev);
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+* @brief DeviceQualifierDescriptor
+* return Device Qualifier descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+static uint8_t *USBD_DFU_GetDeviceQualifierDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_DFU_DeviceQualifierDesc);
+
+ return USBD_DFU_DeviceQualifierDesc;
+}
+
+/**
+ * @brief USBD_DFU_GetUsrStringDesc
+ * Manages the transfer of memory interfaces string descriptors.
+ * @param speed : current device speed
+ * @param index: desciptor index
+ * @param length : pointer data length
+ * @retval pointer to the descriptor table or NULL if the descriptor is not supported.
+ */
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+static uint8_t *USBD_DFU_GetUsrStringDesc(USBD_HandleTypeDef *pdev, uint8_t index, uint16_t *length)
+{
+ static uint8_t USBD_StrDesc[255];
+ USBD_DFU_MediaTypeDef *DfuInterface = (USBD_DFU_MediaTypeDef *)pdev->pUserData;
+
+ /* Check if the requested string interface is supported */
+ if (index <= (USBD_IDX_INTERFACE_STR + USBD_DFU_MAX_ITF_NUM))
+ {
+ USBD_GetString((uint8_t *)DfuInterface->pStrDesc, USBD_StrDesc, length);
+ return USBD_StrDesc;
+ }
+ else
+ {
+ /* Not supported Interface Descriptor index */
+ return NULL;
+ }
+}
+#endif
+
+/**
+* @brief USBD_MSC_RegisterStorage
+* @param fops: storage callback
+* @retval status
+*/
+uint8_t USBD_DFU_RegisterMedia(USBD_HandleTypeDef *pdev,
+ USBD_DFU_MediaTypeDef *fops)
+{
+ if (fops == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ pdev->pUserData = fops;
+
+ return (uint8_t)USBD_OK;
+}
+
+/******************************************************************************
+ DFU Class requests management
+******************************************************************************/
+/**
+ * @brief DFU_Detach
+ * Handles the DFU DETACH request.
+ * @param pdev: device instance
+ * @param req: pointer to the request structure.
+ * @retval None.
+ */
+static void DFU_Detach(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+
+ if ((hdfu->dev_state == DFU_STATE_IDLE) ||
+ (hdfu->dev_state == DFU_STATE_DNLOAD_SYNC) ||
+ (hdfu->dev_state == DFU_STATE_DNLOAD_IDLE) ||
+ (hdfu->dev_state == DFU_STATE_MANIFEST_SYNC) ||
+ (hdfu->dev_state == DFU_STATE_UPLOAD_IDLE))
+ {
+ /* Update the state machine */
+ hdfu->dev_state = DFU_STATE_IDLE;
+ hdfu->dev_status[0] = DFU_ERROR_NONE;
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U; /*bwPollTimeout=0ms*/
+ hdfu->dev_status[4] = hdfu->dev_state;
+ hdfu->dev_status[5] = 0U; /*iString*/
+ hdfu->wblock_num = 0U;
+ hdfu->wlength = 0U;
+ }
+
+ /* Check the detach capability in the DFU functional descriptor */
+ if (((USBD_DFU_CfgDesc[12U + (9U * USBD_DFU_MAX_ITF_NUM)]) & DFU_DETACH_MASK) != 0U)
+ {
+ /* Perform an Attach-Detach operation on USB bus */
+ (void)USBD_Stop(pdev);
+ (void)USBD_Start(pdev);
+ }
+ else
+ {
+ /* Wait for the period of time specified in Detach request */
+ USBD_Delay((uint32_t)req->wValue);
+ }
+}
+
+/**
+ * @brief DFU_Download
+ * Handles the DFU DNLOAD request.
+ * @param pdev: device instance
+ * @param req: pointer to the request structure
+ * @retval None
+ */
+static void DFU_Download(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+
+ /* Data setup request */
+ if (req->wLength > 0U)
+ {
+ if ((hdfu->dev_state == DFU_STATE_IDLE) || (hdfu->dev_state == DFU_STATE_DNLOAD_IDLE))
+ {
+ /* Update the global length and block number */
+ hdfu->wblock_num = req->wValue;
+ hdfu->wlength = req->wLength;
+
+ /* Update the state machine */
+ hdfu->dev_state = DFU_STATE_DNLOAD_SYNC;
+ hdfu->dev_status[4] = hdfu->dev_state;
+
+ /* Prepare the reception of the buffer over EP0 */
+ (void)USBD_CtlPrepareRx(pdev, (uint8_t *)hdfu->buffer.d8, hdfu->wlength);
+ }
+ /* Unsupported state */
+ else
+ {
+ /* Call the error management function (command will be nacked */
+ USBD_CtlError(pdev, req);
+ }
+ }
+ /* 0 Data DNLOAD request */
+ else
+ {
+ /* End of DNLOAD operation*/
+ if ((hdfu->dev_state == DFU_STATE_DNLOAD_IDLE) || (hdfu->dev_state == DFU_STATE_IDLE))
+ {
+ hdfu->manif_state = DFU_MANIFEST_IN_PROGRESS;
+ hdfu->dev_state = DFU_STATE_MANIFEST_SYNC;
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+ }
+ else
+ {
+ /* Call the error management function (command will be nacked */
+ USBD_CtlError(pdev, req);
+ }
+ }
+}
+
+/**
+ * @brief DFU_Upload
+ * Handles the DFU UPLOAD request.
+ * @param pdev: instance
+ * @param req: pointer to the request structure
+ * @retval status
+ */
+static void DFU_Upload(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+ USBD_DFU_MediaTypeDef *DfuInterface = (USBD_DFU_MediaTypeDef *)pdev->pUserData;
+ uint8_t *phaddr;
+ uint32_t addr;
+
+ /* Data setup request */
+ if (req->wLength > 0U)
+ {
+ if ((hdfu->dev_state == DFU_STATE_IDLE) || (hdfu->dev_state == DFU_STATE_UPLOAD_IDLE))
+ {
+ /* Update the global length and block number */
+ hdfu->wblock_num = req->wValue;
+ hdfu->wlength = req->wLength;
+
+ /* DFU Get Command */
+ if (hdfu->wblock_num == 0U)
+ {
+ /* Update the state machine */
+ hdfu->dev_state = (hdfu->wlength > 3U) ? DFU_STATE_IDLE : DFU_STATE_UPLOAD_IDLE;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+
+ /* Store the values of all supported commands */
+ hdfu->buffer.d8[0] = DFU_CMD_GETCOMMANDS;
+ hdfu->buffer.d8[1] = DFU_CMD_SETADDRESSPOINTER;
+ hdfu->buffer.d8[2] = DFU_CMD_ERASE;
+
+ /* Send the status data over EP0 */
+ (void)USBD_CtlSendData(pdev, (uint8_t *)(&(hdfu->buffer.d8[0])), 3U);
+ }
+ else if (hdfu->wblock_num > 1U)
+ {
+ hdfu->dev_state = DFU_STATE_UPLOAD_IDLE;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+
+ addr = ((hdfu->wblock_num - 2U) * USBD_DFU_XFER_SIZE) + hdfu->data_ptr;
+
+ /* Return the physical address where data are stored */
+ phaddr = DfuInterface->Read((uint8_t *)addr, hdfu->buffer.d8, hdfu->wlength);
+
+ /* Send the status data over EP0 */
+ (void)USBD_CtlSendData(pdev, phaddr, hdfu->wlength);
+ }
+ else /* unsupported hdfu->wblock_num */
+ {
+ hdfu->dev_state = DFU_ERROR_STALLEDPKT;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+
+ /* Call the error management function (command will be nacked */
+ USBD_CtlError(pdev, req);
+ }
+ }
+ /* Unsupported state */
+ else
+ {
+ hdfu->wlength = 0U;
+ hdfu->wblock_num = 0U;
+
+ /* Call the error management function (command will be nacked */
+ USBD_CtlError(pdev, req);
+ }
+ }
+ /* No Data setup request */
+ else
+ {
+ hdfu->dev_state = DFU_STATE_IDLE;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+ }
+}
+
+/**
+ * @brief DFU_GetStatus
+ * Handles the DFU GETSTATUS request.
+ * @param pdev: instance
+ * @retval status
+ */
+static void DFU_GetStatus(USBD_HandleTypeDef *pdev)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+ USBD_DFU_MediaTypeDef *DfuInterface = (USBD_DFU_MediaTypeDef *)pdev->pUserData;
+
+ switch (hdfu->dev_state)
+ {
+ case DFU_STATE_DNLOAD_SYNC:
+ if (hdfu->wlength != 0U)
+ {
+ hdfu->dev_state = DFU_STATE_DNLOAD_BUSY;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+
+ if ((hdfu->wblock_num == 0U) && (hdfu->buffer.d8[0] == DFU_CMD_ERASE))
+ {
+ DfuInterface->GetStatus(hdfu->data_ptr, DFU_MEDIA_ERASE, hdfu->dev_status);
+ }
+ else
+ {
+ DfuInterface->GetStatus(hdfu->data_ptr, DFU_MEDIA_PROGRAM, hdfu->dev_status);
+ }
+ }
+ else /* (hdfu->wlength==0)*/
+ {
+ hdfu->dev_state = DFU_STATE_DNLOAD_IDLE;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+ }
+ break;
+
+ case DFU_STATE_MANIFEST_SYNC:
+ if (hdfu->manif_state == DFU_MANIFEST_IN_PROGRESS)
+ {
+ hdfu->dev_state = DFU_STATE_MANIFEST;
+
+ hdfu->dev_status[1] = 1U; /*bwPollTimeout = 1ms*/
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+ }
+ else
+ {
+ if ((hdfu->manif_state == DFU_MANIFEST_COMPLETE) &&
+ (((USBD_DFU_CfgDesc[(11U + (9U * USBD_DFU_MAX_ITF_NUM))]) & 0x04U) != 0U))
+ {
+ hdfu->dev_state = DFU_STATE_IDLE;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+ }
+ }
+ break;
+
+ default:
+ break;
+ }
+
+ /* Send the status data over EP0 */
+ (void)USBD_CtlSendData(pdev, (uint8_t *)(&(hdfu->dev_status[0])), 6U);
+}
+
+/**
+ * @brief DFU_ClearStatus
+ * Handles the DFU CLRSTATUS request.
+ * @param pdev: device instance
+ * @retval status
+ */
+static void DFU_ClearStatus(USBD_HandleTypeDef *pdev)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+
+ if (hdfu->dev_state == DFU_STATE_ERROR)
+ {
+ hdfu->dev_state = DFU_STATE_IDLE;
+ hdfu->dev_status[0] = DFU_ERROR_NONE; /*bStatus*/
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U; /*bwPollTimeout=0ms*/
+ hdfu->dev_status[4] = hdfu->dev_state; /*bState*/
+ hdfu->dev_status[5] = 0U; /*iString*/
+ }
+ else
+ {
+ /*State Error*/
+ hdfu->dev_state = DFU_STATE_ERROR;
+ hdfu->dev_status[0] = DFU_ERROR_UNKNOWN; /*bStatus*/
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U; /*bwPollTimeout=0ms*/
+ hdfu->dev_status[4] = hdfu->dev_state; /*bState*/
+ hdfu->dev_status[5] = 0U; /*iString*/
+ }
+}
+
+/**
+ * @brief DFU_GetState
+ * Handles the DFU GETSTATE request.
+ * @param pdev: device instance
+ * @retval None
+ */
+static void DFU_GetState(USBD_HandleTypeDef *pdev)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+
+ /* Return the current state of the DFU interface */
+ (void)USBD_CtlSendData(pdev, &hdfu->dev_state, 1U);
+}
+
+/**
+ * @brief DFU_Abort
+ * Handles the DFU ABORT request.
+ * @param pdev: device instance
+ * @retval None
+ */
+static void DFU_Abort(USBD_HandleTypeDef *pdev)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+
+
+ if ((hdfu->dev_state == DFU_STATE_IDLE) ||
+ (hdfu->dev_state == DFU_STATE_DNLOAD_SYNC) ||
+ (hdfu->dev_state == DFU_STATE_DNLOAD_IDLE) ||
+ (hdfu->dev_state == DFU_STATE_MANIFEST_SYNC) ||
+ (hdfu->dev_state == DFU_STATE_UPLOAD_IDLE))
+ {
+ hdfu->dev_state = DFU_STATE_IDLE;
+ hdfu->dev_status[0] = DFU_ERROR_NONE;
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U; /*bwPollTimeout=0ms*/
+ hdfu->dev_status[4] = hdfu->dev_state;
+ hdfu->dev_status[5] = 0U; /*iString*/
+ hdfu->wblock_num = 0U;
+ hdfu->wlength = 0U;
+ }
+}
+
+/**
+ * @brief DFU_Leave
+ * Handles the sub-protocol DFU leave DFU mode request (leaves DFU mode
+ * and resets device to jump to user loaded code).
+ * @param pdev: device instance
+ * @retval None
+ */
+static void DFU_Leave(USBD_HandleTypeDef *pdev)
+{
+ USBD_DFU_HandleTypeDef *hdfu = (USBD_DFU_HandleTypeDef *)pdev->pClassData;
+
+ hdfu->manif_state = DFU_MANIFEST_COMPLETE;
+
+ if (((USBD_DFU_CfgDesc[(11U + (9U * USBD_DFU_MAX_ITF_NUM))]) & 0x04U) != 0U)
+ {
+ hdfu->dev_state = DFU_STATE_MANIFEST_SYNC;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+ return;
+ }
+ else
+ {
+ hdfu->dev_state = DFU_STATE_MANIFEST_WAIT_RESET;
+
+ hdfu->dev_status[1] = 0U;
+ hdfu->dev_status[2] = 0U;
+ hdfu->dev_status[3] = 0U;
+ hdfu->dev_status[4] = hdfu->dev_state;
+
+ /* Disconnect the USB device */
+ (void)USBD_Stop(pdev);
+
+ /* Generate system reset to allow jumping to the user code */
+ NVIC_SystemReset();
+
+ /* The next instructions will not be reached (system reset) */
+ }
+}
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Src/usbd_dfu_media_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Src/usbd_dfu_media_template.c
new file mode 100644
index 0000000000..b40a10cb8a
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/DFU/Src/usbd_dfu_media_template.c
@@ -0,0 +1,135 @@
+/**
+ ******************************************************************************
+ * @file usbd_dfu_media_template.c
+ * @author MCD Application Team
+ * @brief Memory management layer
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_dfu_media_template.h"
+
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Extern function prototypes ------------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+uint16_t MEM_If_Init(void);
+uint16_t MEM_If_Erase(uint32_t Add);
+uint16_t MEM_If_Write(uint8_t *src, uint8_t *dest, uint32_t Len);
+uint8_t *MEM_If_Read(uint8_t *src, uint8_t *dest, uint32_t Len);
+uint16_t MEM_If_DeInit(void);
+uint16_t MEM_If_GetStatus(uint32_t Add, uint8_t Cmd, uint8_t *buffer);
+
+USBD_DFU_MediaTypeDef USBD_DFU_MEDIA_Template_fops =
+{
+ (uint8_t *)"DFU MEDIA",
+ MEM_If_Init,
+ MEM_If_DeInit,
+ MEM_If_Erase,
+ MEM_If_Write,
+ MEM_If_Read,
+ MEM_If_GetStatus,
+
+};
+/**
+ * @brief MEM_If_Init
+ * Memory initialization routine.
+ * @param None
+ * @retval 0 if operation is successful, MAL_FAIL else.
+ */
+uint16_t MEM_If_Init(void)
+{
+ return 0;
+}
+
+/**
+ * @brief MEM_If_DeInit
+ * Memory deinitialization routine.
+ * @param None
+ * @retval 0 if operation is successful, MAL_FAIL else.
+ */
+uint16_t MEM_If_DeInit(void)
+{
+ return 0;
+}
+
+/**
+ * @brief MEM_If_Erase
+ * Erase sector.
+ * @param Add: Address of sector to be erased.
+ * @retval 0 if operation is successful, MAL_FAIL else.
+ */
+uint16_t MEM_If_Erase(uint32_t Add)
+{
+ return 0;
+}
+
+/**
+ * @brief MEM_If_Write
+ * Memory write routine.
+ * @param Add: Address to be written to.
+ * @param Len: Number of data to be written (in bytes).
+ * @retval 0 if operation is successful, MAL_FAIL else.
+ */
+uint16_t MEM_If_Write(uint8_t *src, uint8_t *dest, uint32_t Len)
+{
+ return 0;
+}
+
+/**
+ * @brief MEM_If_Read
+ * Memory read routine.
+ * @param Add: Address to be read from.
+ * @param Len: Number of data to be read (in bytes).
+ * @retval Pointer to the physical address where data should be read.
+ */
+uint8_t *MEM_If_Read(uint8_t *src, uint8_t *dest, uint32_t Len)
+{
+ /* Return a valid address to avoid HardFault */
+ return (uint8_t *)(0);
+}
+
+/**
+ * @brief Flash_If_GetStatus
+ * Memory read routine.
+ * @param Add: Address to be read from.
+ * @param cmd: Number of data to be read (in bytes).
+ * @retval Pointer to the physical address where data should be read.
+ */
+uint16_t MEM_If_GetStatus(uint32_t Add, uint8_t Cmd, uint8_t *buffer)
+{
+ switch (Cmd)
+ {
+ case DFU_MEDIA_PROGRAM:
+
+ break;
+
+ case DFU_MEDIA_ERASE:
+ default:
+
+ break;
+ }
+ return (0);
+}
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID/Inc/usbd_hid.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID/Inc/usbd_hid.h
new file mode 100644
index 0000000000..40ed7291af
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID/Inc/usbd_hid.h
@@ -0,0 +1,139 @@
+/**
+ ******************************************************************************
+ * @file usbd_hid.h
+ * @author MCD Application Team
+ * @brief Header file for the usbd_hid_core.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_HID_H
+#define __USB_HID_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_HID
+ * @brief This file is the Header file for usbd_hid.c
+ * @{
+ */
+
+
+/** @defgroup USBD_HID_Exported_Defines
+ * @{
+ */
+#define HID_EPIN_ADDR 0x81U
+#define HID_EPIN_SIZE 0x04U
+
+#define USB_HID_CONFIG_DESC_SIZ 34U
+#define USB_HID_DESC_SIZ 9U
+#define HID_MOUSE_REPORT_DESC_SIZE 74U
+
+#define HID_DESCRIPTOR_TYPE 0x21U
+#define HID_REPORT_DESC 0x22U
+
+#ifndef HID_HS_BINTERVAL
+#define HID_HS_BINTERVAL 0x07U
+#endif /* HID_HS_BINTERVAL */
+
+#ifndef HID_FS_BINTERVAL
+#define HID_FS_BINTERVAL 0x0AU
+#endif /* HID_FS_BINTERVAL */
+
+#define HID_REQ_SET_PROTOCOL 0x0BU
+#define HID_REQ_GET_PROTOCOL 0x03U
+
+#define HID_REQ_SET_IDLE 0x0AU
+#define HID_REQ_GET_IDLE 0x02U
+
+#define HID_REQ_SET_REPORT 0x09U
+#define HID_REQ_GET_REPORT 0x01U
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+typedef enum
+{
+ HID_IDLE = 0,
+ HID_BUSY,
+} HID_StateTypeDef;
+
+
+typedef struct
+{
+ uint32_t Protocol;
+ uint32_t IdleState;
+ uint32_t AltSetting;
+ HID_StateTypeDef state;
+} USBD_HID_HandleTypeDef;
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_HID;
+#define USBD_HID_CLASS &USBD_HID
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+uint8_t USBD_HID_SendReport(USBD_HandleTypeDef *pdev, uint8_t *report,uint16_t len);
+uint32_t USBD_HID_GetPollingInterval(USBD_HandleTypeDef *pdev);
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_HID_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID/Src/usbd_hid.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID/Src/usbd_hid.c
new file mode 100644
index 0000000000..c73dacebe9
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID/Src/usbd_hid.c
@@ -0,0 +1,680 @@
+/**
+ ******************************************************************************
+ * @file usbd_hid.c
+ * @author MCD Application Team
+ * @brief This file provides the HID core functions.
+ *
+ * @verbatim
+ *
+ * ===================================================================
+ * HID Class Description
+ * ===================================================================
+ * This module manages the HID class V1.11 following the "Device Class Definition
+ * for Human Interface Devices (HID) Version 1.11 Jun 27, 2001".
+ * This driver implements the following aspects of the specification:
+ * - The Boot Interface Subclass
+ * - The Mouse protocol
+ * - Usage Page : Generic Desktop
+ * - Usage : Joystick
+ * - Collection : Application
+ *
+ * @note In HS mode and when the DMA is used, all variables and data structures
+ * dealing with the DMA during the transaction process should be 32-bit aligned.
+ *
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_hid.h"
+#include "usbd_ctlreq.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_HID
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_HID_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_HID_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_HID_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_HID_Private_FunctionPrototypes
+ * @{
+ */
+
+static uint8_t USBD_HID_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_HID_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_HID_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static uint8_t USBD_HID_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+
+static uint8_t *USBD_HID_GetFSCfgDesc(uint16_t *length);
+static uint8_t *USBD_HID_GetHSCfgDesc(uint16_t *length);
+static uint8_t *USBD_HID_GetOtherSpeedCfgDesc(uint16_t *length);
+static uint8_t *USBD_HID_GetDeviceQualifierDesc(uint16_t *length);
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_HID_Private_Variables
+ * @{
+ */
+
+USBD_ClassTypeDef USBD_HID = {
+ USBD_HID_Init,
+ USBD_HID_DeInit,
+ USBD_HID_Setup,
+ NULL, /* EP0_TxSent */
+ NULL, /* EP0_RxReady */
+ USBD_HID_DataIn, /* DataIn */
+ NULL, /* DataOut */
+ NULL, /* SOF */
+ NULL,
+ NULL,
+ USBD_HID_GetHSCfgDesc,
+ USBD_HID_GetFSCfgDesc,
+ USBD_HID_GetOtherSpeedCfgDesc,
+ USBD_HID_GetDeviceQualifierDesc,
+};
+
+/* USB HID device FS Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_HID_CfgFSDesc[USB_HID_CONFIG_DESC_SIZ] __ALIGN_END = {
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_HID_CONFIG_DESC_SIZ,
+ /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xE0, /* bmAttributes: bus powered and Support Remote Wake-up */
+ 0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */
+
+ /************** Descriptor of Joystick Mouse interface ****************/
+ /* 09 */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints */
+ 0x03, /* bInterfaceClass: HID */
+ 0x01, /* bInterfaceSubClass : 1=BOOT, 0=no boot */
+ 0x02, /* nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse */
+ 0, /* iInterface: Index of string descriptor */
+ /******************** Descriptor of Joystick Mouse HID ********************/
+ /* 18 */
+ 0x09, /* bLength: HID Descriptor size */
+ HID_DESCRIPTOR_TYPE, /* bDescriptorType: HID */
+ 0x11, /* bcdHID: HID Class Spec release number */
+ 0x01,
+ 0x00, /* bCountryCode: Hardware target country */
+ 0x01, /* bNumDescriptors: Number of HID class descriptors to follow */
+ 0x22, /* bDescriptorType */
+ HID_MOUSE_REPORT_DESC_SIZE, /* wItemLength: Total length of Report descriptor */
+ 0x00,
+ /******************** Descriptor of Mouse endpoint ********************/
+ /* 27 */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType:*/
+
+ HID_EPIN_ADDR, /* bEndpointAddress: Endpoint Address (IN) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ HID_EPIN_SIZE, /* wMaxPacketSize: 4 Byte max */
+ 0x00,
+ HID_FS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 34 */
+};
+
+/* USB HID device HS Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_HID_CfgHSDesc[USB_HID_CONFIG_DESC_SIZ] __ALIGN_END = {
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_HID_CONFIG_DESC_SIZ,
+ /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xE0, /* bmAttributes: bus powered and Support Remote Wake-up */
+ 0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */
+
+ /************** Descriptor of Joystick Mouse interface ****************/
+ /* 09 */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints */
+ 0x03, /* bInterfaceClass: HID */
+ 0x01, /* bInterfaceSubClass : 1=BOOT, 0=no boot */
+ 0x02, /* nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse */
+ 0, /* iInterface: Index of string descriptor */
+ /******************** Descriptor of Joystick Mouse HID ********************/
+ /* 18 */
+ 0x09, /* bLength: HID Descriptor size */
+ HID_DESCRIPTOR_TYPE, /* bDescriptorType: HID */
+ 0x11, /* bcdHID: HID Class Spec release number */
+ 0x01,
+ 0x00, /* bCountryCode: Hardware target country */
+ 0x01, /* bNumDescriptors: Number of HID class descriptors to follow */
+ 0x22, /* bDescriptorType */
+ HID_MOUSE_REPORT_DESC_SIZE, /* wItemLength: Total length of Report descriptor */
+ 0x00,
+ /******************** Descriptor of Mouse endpoint ********************/
+ /* 27 */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: */
+
+ HID_EPIN_ADDR, /* bEndpointAddress: Endpoint Address (IN) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ HID_EPIN_SIZE, /* wMaxPacketSize: 4 Byte max */
+ 0x00,
+ HID_HS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 34 */
+};
+
+/* USB HID device Other Speed Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_HID_OtherSpeedCfgDesc[USB_HID_CONFIG_DESC_SIZ] __ALIGN_END = {
+ 0x09, /* bLength: Configuration Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_HID_CONFIG_DESC_SIZ,
+ /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: Configuration value */
+ 0x00, /* iConfiguration: Index of string descriptor describing the configuration */
+ 0xE0, /* bmAttributes: bus powered and Support Remote Wake-up */
+ 0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */
+
+ /************** Descriptor of Joystick Mouse interface ****************/
+ /* 09 */
+ 0x09, /* bLength: Interface Descriptor size */
+ USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface descriptor type */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x01, /* bNumEndpoints */
+ 0x03, /* bInterfaceClass: HID */
+ 0x01, /* bInterfaceSubClass : 1=BOOT, 0=no boot */
+ 0x02, /* nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse */
+ 0, /* iInterface: Index of string descriptor */
+ /******************** Descriptor of Joystick Mouse HID ********************/
+ /* 18 */
+ 0x09, /* bLength: HID Descriptor size */
+ HID_DESCRIPTOR_TYPE, /* bDescriptorType: HID */
+ 0x11, /* bcdHID: HID Class Spec release number */
+ 0x01,
+ 0x00, /* bCountryCode: Hardware target country */
+ 0x01, /* bNumDescriptors: Number of HID class descriptors to follow */
+ 0x22, /* bDescriptorType */
+ HID_MOUSE_REPORT_DESC_SIZE, /* wItemLength: Total length of Report descriptor */
+ 0x00,
+ /******************** Descriptor of Mouse endpoint ********************/
+ /* 27 */
+ 0x07, /* bLength: Endpoint Descriptor size */
+ USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: */
+
+ HID_EPIN_ADDR, /* bEndpointAddress: Endpoint Address (IN) */
+ 0x03, /* bmAttributes: Interrupt endpoint */
+ HID_EPIN_SIZE, /* wMaxPacketSize: 4 Byte max */
+ 0x00,
+ HID_FS_BINTERVAL, /* bInterval: Polling Interval */
+ /* 34 */
+};
+
+
+/* USB HID device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_HID_Desc[USB_HID_DESC_SIZ] __ALIGN_END = {
+ /* 18 */
+ 0x09, /* bLength: HID Descriptor size */
+ HID_DESCRIPTOR_TYPE, /* bDescriptorType: HID */
+ 0x11, /* bcdHID: HID Class Spec release number */
+ 0x01,
+ 0x00, /* bCountryCode: Hardware target country */
+ 0x01, /* bNumDescriptors: Number of HID class descriptors to follow */
+ 0x22, /* bDescriptorType */
+ HID_MOUSE_REPORT_DESC_SIZE, /* wItemLength: Total length of Report descriptor */
+ 0x00,
+};
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_HID_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END = {
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x40,
+ 0x01,
+ 0x00,
+};
+
+__ALIGN_BEGIN static uint8_t HID_MOUSE_ReportDesc[HID_MOUSE_REPORT_DESC_SIZE] __ALIGN_END = {
+ 0x05, 0x01,
+ 0x09, 0x02,
+ 0xA1, 0x01,
+ 0x09, 0x01,
+
+ 0xA1, 0x00,
+ 0x05, 0x09,
+ 0x19, 0x01,
+ 0x29, 0x03,
+
+ 0x15, 0x00,
+ 0x25, 0x01,
+ 0x95, 0x03,
+ 0x75, 0x01,
+
+ 0x81, 0x02,
+ 0x95, 0x01,
+ 0x75, 0x05,
+ 0x81, 0x01,
+
+ 0x05, 0x01,
+ 0x09, 0x30,
+ 0x09, 0x31,
+ 0x09, 0x38,
+
+ 0x15, 0x81,
+ 0x25, 0x7F,
+ 0x75, 0x08,
+ 0x95, 0x03,
+
+ 0x81, 0x06,
+ 0xC0, 0x09,
+ 0x3c, 0x05,
+ 0xff, 0x09,
+
+ 0x01, 0x15,
+ 0x00, 0x25,
+ 0x01, 0x75,
+ 0x01, 0x95,
+
+ 0x02, 0xb1,
+ 0x22, 0x75,
+ 0x06, 0x95,
+ 0x01, 0xb1,
+
+ 0x01, 0xc0
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_HID_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_HID_Init
+ * Initialize the HID interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_HID_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ USBD_HID_HandleTypeDef *hhid;
+
+ hhid = USBD_malloc(sizeof(USBD_HID_HandleTypeDef));
+
+ if (hhid == NULL)
+ {
+ pdev->pClassData = NULL;
+ return (uint8_t)USBD_EMEM;
+ }
+
+ pdev->pClassData = (void *)hhid;
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ pdev->ep_in[HID_EPIN_ADDR & 0xFU].bInterval = HID_HS_BINTERVAL;
+ }
+ else /* LOW and FULL-speed endpoints */
+ {
+ pdev->ep_in[HID_EPIN_ADDR & 0xFU].bInterval = HID_FS_BINTERVAL;
+ }
+
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, HID_EPIN_ADDR, USBD_EP_TYPE_INTR, HID_EPIN_SIZE);
+ pdev->ep_in[HID_EPIN_ADDR & 0xFU].is_used = 1U;
+
+ hhid->state = HID_IDLE;
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_HID_DeInit
+ * DeInitialize the HID layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_HID_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ /* Close HID EPs */
+ (void)USBD_LL_CloseEP(pdev, HID_EPIN_ADDR);
+ pdev->ep_in[HID_EPIN_ADDR & 0xFU].is_used = 0U;
+ pdev->ep_in[HID_EPIN_ADDR & 0xFU].bInterval = 0U;
+
+ /* FRee allocated memory */
+ if (pdev->pClassData != NULL)
+ {
+ (void)USBD_free(pdev->pClassData);
+ pdev->pClassData = NULL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_HID_Setup
+ * Handle the HID specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_HID_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef *)pdev->pClassData;
+ USBD_StatusTypeDef ret = USBD_OK;
+ uint16_t len;
+ uint8_t *pbuf;
+ uint16_t status_info = 0U;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS :
+ switch (req->bRequest)
+ {
+ case HID_REQ_SET_PROTOCOL:
+ hhid->Protocol = (uint8_t)(req->wValue);
+ break;
+
+ case HID_REQ_GET_PROTOCOL:
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&hhid->Protocol, 1U);
+ break;
+
+ case HID_REQ_SET_IDLE:
+ hhid->IdleState = (uint8_t)(req->wValue >> 8);
+ break;
+
+ case HID_REQ_GET_IDLE:
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&hhid->IdleState, 1U);
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_DESCRIPTOR:
+ if ((req->wValue >> 8) == HID_REPORT_DESC)
+ {
+ len = MIN(HID_MOUSE_REPORT_DESC_SIZE, req->wLength);
+ pbuf = HID_MOUSE_ReportDesc;
+ }
+ else if ((req->wValue >> 8) == HID_DESCRIPTOR_TYPE)
+ {
+ pbuf = USBD_HID_Desc;
+ len = MIN(USB_HID_DESC_SIZ, req->wLength);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ (void)USBD_CtlSendData(pdev, pbuf, len);
+ break;
+
+ case USB_REQ_GET_INTERFACE :
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&hhid->AltSetting, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ hhid->AltSetting = (uint8_t)(req->wValue);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+/**
+ * @brief USBD_HID_SendReport
+ * Send HID Report
+ * @param pdev: device instance
+ * @param buff: pointer to report
+ * @retval status
+ */
+uint8_t USBD_HID_SendReport(USBD_HandleTypeDef *pdev, uint8_t *report, uint16_t len)
+{
+ USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef *)pdev->pClassData;
+
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ if (hhid->state == HID_IDLE)
+ {
+ hhid->state = HID_BUSY;
+ (void)USBD_LL_Transmit(pdev, HID_EPIN_ADDR, report, len);
+ }
+ }
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_HID_GetPollingInterval
+ * return polling interval from endpoint descriptor
+ * @param pdev: device instance
+ * @retval polling interval
+ */
+uint32_t USBD_HID_GetPollingInterval(USBD_HandleTypeDef *pdev)
+{
+ uint32_t polling_interval;
+
+ /* HIGH-speed endpoints */
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ /* Sets the data transfer polling interval for high speed transfers.
+ Values between 1..16 are allowed. Values correspond to interval
+ of 2 ^ (bInterval-1). This option (8 ms, corresponds to HID_HS_BINTERVAL */
+ polling_interval = (((1U << (HID_HS_BINTERVAL - 1U))) / 8U);
+ }
+ else /* LOW and FULL-speed endpoints */
+ {
+ /* Sets the data transfer polling interval for low and full
+ speed transfers */
+ polling_interval = HID_FS_BINTERVAL;
+ }
+
+ return ((uint32_t)(polling_interval));
+}
+
+/**
+ * @brief USBD_HID_GetCfgFSDesc
+ * return FS configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_HID_GetFSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_HID_CfgFSDesc);
+
+ return USBD_HID_CfgFSDesc;
+}
+
+/**
+ * @brief USBD_HID_GetCfgHSDesc
+ * return HS configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_HID_GetHSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_HID_CfgHSDesc);
+
+ return USBD_HID_CfgHSDesc;
+}
+
+/**
+ * @brief USBD_HID_GetOtherSpeedCfgDesc
+ * return other speed configuration descriptor
+ * @param speed : current device speed
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_HID_GetOtherSpeedCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_HID_OtherSpeedCfgDesc);
+
+ return USBD_HID_OtherSpeedCfgDesc;
+}
+
+/**
+ * @brief USBD_HID_DataIn
+ * handle data IN Stage
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_HID_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ UNUSED(epnum);
+ /* Ensure that the FIFO is empty before a new transfer, this condition could
+ be caused by a new transfer before the end of the previous transfer */
+ ((USBD_HID_HandleTypeDef *)pdev->pClassData)->state = HID_IDLE;
+
+ return (uint8_t)USBD_OK;
+}
+
+
+/**
+* @brief DeviceQualifierDescriptor
+* return Device Qualifier descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+static uint8_t *USBD_HID_GetDeviceQualifierDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_HID_DeviceQualifierDesc);
+
+ return USBD_HID_DeviceQualifierDesc;
+}
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc.h
new file mode 100644
index 0000000000..a0bbab9065
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc.h
@@ -0,0 +1,130 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc.h
+ * @author MCD Application Team
+ * @brief Header for the usbd_msc.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_MSC_H
+#define __USBD_MSC_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_msc_bot.h"
+#include "usbd_msc_scsi.h"
+#include "usbd_ioreq.h"
+
+/** @addtogroup USBD_MSC_BOT
+ * @{
+ */
+
+/** @defgroup USBD_MSC
+ * @brief This file is the Header file for usbd_msc.c
+ * @{
+ */
+
+
+/** @defgroup USBD_BOT_Exported_Defines
+ * @{
+ */
+/* MSC Class Config */
+#ifndef MSC_MEDIA_PACKET
+#define MSC_MEDIA_PACKET 512U
+#endif /* MSC_MEDIA_PACKET */
+
+#define MSC_MAX_FS_PACKET 0x40U
+#define MSC_MAX_HS_PACKET 0x200U
+
+#define BOT_GET_MAX_LUN 0xFE
+#define BOT_RESET 0xFF
+#define USB_MSC_CONFIG_DESC_SIZ 32
+
+
+#define MSC_EPIN_ADDR 0x81U
+#define MSC_EPOUT_ADDR 0x01U
+
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Types
+ * @{
+ */
+typedef struct _USBD_STORAGE
+{
+ int8_t (* Init)(uint8_t lun);
+ int8_t (* GetCapacity)(uint8_t lun, uint32_t *block_num, uint16_t *block_size);
+ int8_t (* IsReady)(uint8_t lun);
+ int8_t (* IsWriteProtected)(uint8_t lun);
+ int8_t (* Read)(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
+ int8_t (* Write)(uint8_t lun, uint8_t *buf, uint32_t blk_addr, uint16_t blk_len);
+ int8_t (* GetMaxLun)(void);
+ int8_t *pInquiry;
+
+} USBD_StorageTypeDef;
+
+
+typedef struct
+{
+ uint32_t max_lun;
+ uint32_t interface;
+ uint8_t bot_state;
+ uint8_t bot_status;
+ uint32_t bot_data_length;
+ uint8_t bot_data[MSC_MEDIA_PACKET];
+ USBD_MSC_BOT_CBWTypeDef cbw;
+ USBD_MSC_BOT_CSWTypeDef csw;
+
+ USBD_SCSI_SenseTypeDef scsi_sense [SENSE_LIST_DEEPTH];
+ uint8_t scsi_sense_head;
+ uint8_t scsi_sense_tail;
+ uint8_t scsi_medium_state;
+
+ uint16_t scsi_blk_size;
+ uint32_t scsi_blk_nbr;
+
+ uint32_t scsi_blk_addr;
+ uint32_t scsi_blk_len;
+}
+USBD_MSC_BOT_HandleTypeDef;
+
+/* Structure for MSC process */
+extern USBD_ClassTypeDef USBD_MSC;
+#define USBD_MSC_CLASS &USBD_MSC
+
+uint8_t USBD_MSC_RegisterStorage(USBD_HandleTypeDef *pdev,
+ USBD_StorageTypeDef *fops);
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_MSC_H */
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_bot.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_bot.h
new file mode 100644
index 0000000000..f5b1b6d42e
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_bot.h
@@ -0,0 +1,150 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc_bot.h
+ * @author MCD Application Team
+ * @brief Header for the usbd_msc_bot.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_MSC_BOT_H
+#define __USBD_MSC_BOT_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_core.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup MSC_BOT
+ * @brief This file is the Header file for usbd_msc_bot.c
+ * @{
+ */
+
+
+/** @defgroup USBD_CORE_Exported_Defines
+ * @{
+ */
+#define USBD_BOT_IDLE 0U /* Idle state */
+#define USBD_BOT_DATA_OUT 1U /* Data Out state */
+#define USBD_BOT_DATA_IN 2U /* Data In state */
+#define USBD_BOT_LAST_DATA_IN 3U /* Last Data In Last */
+#define USBD_BOT_SEND_DATA 4U /* Send Immediate data */
+#define USBD_BOT_NO_DATA 5U /* No data Stage */
+
+#define USBD_BOT_CBW_SIGNATURE 0x43425355U
+#define USBD_BOT_CSW_SIGNATURE 0x53425355U
+#define USBD_BOT_CBW_LENGTH 31U
+#define USBD_BOT_CSW_LENGTH 13U
+#define USBD_BOT_MAX_DATA 256U
+
+/* CSW Status Definitions */
+#define USBD_CSW_CMD_PASSED 0x00U
+#define USBD_CSW_CMD_FAILED 0x01U
+#define USBD_CSW_PHASE_ERROR 0x02U
+
+/* BOT Status */
+#define USBD_BOT_STATUS_NORMAL 0U
+#define USBD_BOT_STATUS_RECOVERY 1U
+#define USBD_BOT_STATUS_ERROR 2U
+
+
+#define USBD_DIR_IN 0U
+#define USBD_DIR_OUT 1U
+#define USBD_BOTH_DIR 2U
+
+/**
+ * @}
+ */
+
+/** @defgroup MSC_CORE_Private_TypesDefinitions
+ * @{
+ */
+
+typedef struct
+{
+ uint32_t dSignature;
+ uint32_t dTag;
+ uint32_t dDataLength;
+ uint8_t bmFlags;
+ uint8_t bLUN;
+ uint8_t bCBLength;
+ uint8_t CB[16];
+ uint8_t ReservedForAlign;
+}
+USBD_MSC_BOT_CBWTypeDef;
+
+
+typedef struct
+{
+ uint32_t dSignature;
+ uint32_t dTag;
+ uint32_t dDataResidue;
+ uint8_t bStatus;
+ uint8_t ReservedForAlign[3];
+}
+USBD_MSC_BOT_CSWTypeDef;
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_Types
+ * @{
+ */
+
+/**
+ * @}
+ */
+/** @defgroup USBD_CORE_Exported_FunctionsPrototypes
+ * @{
+ */
+void MSC_BOT_Init(USBD_HandleTypeDef *pdev);
+void MSC_BOT_Reset(USBD_HandleTypeDef *pdev);
+void MSC_BOT_DeInit(USBD_HandleTypeDef *pdev);
+void MSC_BOT_DataIn(USBD_HandleTypeDef *pdev,
+ uint8_t epnum);
+
+void MSC_BOT_DataOut(USBD_HandleTypeDef *pdev,
+ uint8_t epnum);
+
+void MSC_BOT_SendCSW(USBD_HandleTypeDef *pdev,
+ uint8_t CSW_Status);
+
+void MSC_BOT_CplClrFeature(USBD_HandleTypeDef *pdev,
+ uint8_t epnum);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_MSC_BOT_H */
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_data.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_data.h
new file mode 100644
index 0000000000..26838de02e
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_data.h
@@ -0,0 +1,105 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc_data.h
+ * @author MCD Application Team
+ * @brief Header for the usbd_msc_data.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_MSC_DATA_H
+#define __USBD_MSC_DATA_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_conf.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USB_INFO
+ * @brief general defines for the usb device library file
+ * @{
+ */
+
+/** @defgroup USB_INFO_Exported_Defines
+ * @{
+ */
+#define MODE_SENSE6_LEN 0x17U
+#define MODE_SENSE10_LEN 0x1BU
+#define LENGTH_INQUIRY_PAGE00 0x06U
+#define LENGTH_INQUIRY_PAGE80 0x08U
+#define LENGTH_FORMAT_CAPACITIES 0x14U
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_INFO_Exported_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_INFO_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_INFO_Exported_Variables
+ * @{
+ */
+extern uint8_t MSC_Page00_Inquiry_Data[LENGTH_INQUIRY_PAGE00];
+extern uint8_t MSC_Page80_Inquiry_Data[LENGTH_INQUIRY_PAGE80];
+extern uint8_t MSC_Mode_Sense6_data[MODE_SENSE6_LEN];
+extern uint8_t MSC_Mode_Sense10_data[MODE_SENSE10_LEN];
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_INFO_Exported_FunctionsPrototype
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_MSC_DATA_H */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_scsi.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_scsi.h
new file mode 100644
index 0000000000..b32ded0f6c
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_scsi.h
@@ -0,0 +1,185 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc_scsi.h
+ * @author MCD Application Team
+ * @brief Header for the usbd_msc_scsi.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_MSC_SCSI_H
+#define __USBD_MSC_SCSI_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_def.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_SCSI
+ * @brief header file for the storage disk file
+ * @{
+ */
+
+/** @defgroup USBD_SCSI_Exported_Defines
+ * @{
+ */
+
+#define SENSE_LIST_DEEPTH 4U
+
+/* SCSI Commands */
+#define SCSI_FORMAT_UNIT 0x04U
+#define SCSI_INQUIRY 0x12U
+#define SCSI_MODE_SELECT6 0x15U
+#define SCSI_MODE_SELECT10 0x55U
+#define SCSI_MODE_SENSE6 0x1AU
+#define SCSI_MODE_SENSE10 0x5AU
+#define SCSI_ALLOW_MEDIUM_REMOVAL 0x1EU
+#define SCSI_READ6 0x08U
+#define SCSI_READ10 0x28U
+#define SCSI_READ12 0xA8U
+#define SCSI_READ16 0x88U
+
+#define SCSI_READ_CAPACITY10 0x25U
+#define SCSI_READ_CAPACITY16 0x9EU
+
+#define SCSI_REQUEST_SENSE 0x03U
+#define SCSI_START_STOP_UNIT 0x1BU
+#define SCSI_TEST_UNIT_READY 0x00U
+#define SCSI_WRITE6 0x0AU
+#define SCSI_WRITE10 0x2AU
+#define SCSI_WRITE12 0xAAU
+#define SCSI_WRITE16 0x8AU
+
+#define SCSI_VERIFY10 0x2FU
+#define SCSI_VERIFY12 0xAFU
+#define SCSI_VERIFY16 0x8FU
+
+#define SCSI_SEND_DIAGNOSTIC 0x1DU
+#define SCSI_READ_FORMAT_CAPACITIES 0x23U
+
+#define NO_SENSE 0U
+#define RECOVERED_ERROR 1U
+#define NOT_READY 2U
+#define MEDIUM_ERROR 3U
+#define HARDWARE_ERROR 4U
+#define ILLEGAL_REQUEST 5U
+#define UNIT_ATTENTION 6U
+#define DATA_PROTECT 7U
+#define BLANK_CHECK 8U
+#define VENDOR_SPECIFIC 9U
+#define COPY_ABORTED 10U
+#define ABORTED_COMMAND 11U
+#define VOLUME_OVERFLOW 13U
+#define MISCOMPARE 14U
+
+
+#define INVALID_CDB 0x20U
+#define INVALID_FIELED_IN_COMMAND 0x24U
+#define PARAMETER_LIST_LENGTH_ERROR 0x1AU
+#define INVALID_FIELD_IN_PARAMETER_LIST 0x26U
+#define ADDRESS_OUT_OF_RANGE 0x21U
+#define MEDIUM_NOT_PRESENT 0x3AU
+#define MEDIUM_HAVE_CHANGED 0x28U
+#define WRITE_PROTECTED 0x27U
+#define UNRECOVERED_READ_ERROR 0x11U
+#define WRITE_FAULT 0x03U
+
+#define READ_FORMAT_CAPACITY_DATA_LEN 0x0CU
+#define READ_CAPACITY10_DATA_LEN 0x08U
+#define REQUEST_SENSE_DATA_LEN 0x12U
+#define STANDARD_INQUIRY_DATA_LEN 0x24U
+#define BLKVFY 0x04U
+
+#define SCSI_MEDIUM_UNLOCKED 0x00U
+#define SCSI_MEDIUM_LOCKED 0x01U
+#define SCSI_MEDIUM_EJECTED 0x02U
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_SCSI_Exported_TypesDefinitions
+ * @{
+ */
+
+typedef struct _SENSE_ITEM
+{
+ uint8_t Skey;
+ union
+ {
+ struct _ASCs
+ {
+ uint8_t ASC;
+ uint8_t ASCQ;
+ } b;
+ uint8_t ASC;
+ uint8_t *pData;
+ } w;
+} USBD_SCSI_SenseTypeDef;
+/**
+ * @}
+ */
+
+/** @defgroup USBD_SCSI_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_SCSI_Exported_Variables
+ * @{
+ */
+
+/**
+ * @}
+ */
+/** @defgroup USBD_SCSI_Exported_FunctionsPrototype
+ * @{
+ */
+int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *cmd);
+
+void SCSI_SenseCode(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t sKey,
+ uint8_t ASC);
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_MSC_SCSI_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_storage_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_storage_template.h
new file mode 100644
index 0000000000..0288c308fc
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Inc/usbd_msc_storage_template.h
@@ -0,0 +1,97 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc_storage.h
+ * @author MCD Application Team
+ * @brief Header file for the usbd_msc_storage.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_MSC_STORAGE_H
+#define __USBD_MSC_STORAGE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_msc.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_STORAGE
+ * @brief header file for the usbd_msc_storage.c file
+ * @{
+ */
+
+/** @defgroup USBD_STORAGE_Exported_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_STORAGE_Exported_Types
+ * @{
+ */
+
+
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_STORAGE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_STORAGE_Exported_Variables
+ * @{
+ */
+extern USBD_StorageTypeDef USBD_MSC_Template_fops;
+/**
+ * @}
+ */
+
+/** @defgroup USBD_STORAGE_Exported_FunctionsPrototype
+ * @{
+ */
+
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_MSC_STORAGE_H */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc.c
new file mode 100644
index 0000000000..fe6e1c6a24
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc.c
@@ -0,0 +1,584 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc.c
+ * @author MCD Application Team
+ * @brief This file provides all the MSC core functions.
+ *
+ * @verbatim
+ *
+ * ===================================================================
+ * MSC Class Description
+ * ===================================================================
+ * This module manages the MSC class V1.0 following the "Universal
+ * Serial Bus Mass Storage Class (MSC) Bulk-Only Transport (BOT) Version 1.0
+ * Sep. 31, 1999".
+ * This driver implements the following aspects of the specification:
+ * - Bulk-Only Transport protocol
+ * - Subclass : SCSI transparent command set (ref. SCSI Primary Commands - 3 (SPC-3))
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+- "stm32xxxxx_{eval}{discovery}{adafruit}_sd.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_msc.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup MSC_CORE
+ * @brief Mass storage core module
+ * @{
+ */
+
+/** @defgroup MSC_CORE_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_CORE_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_CORE_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_CORE_Private_FunctionPrototypes
+ * @{
+ */
+uint8_t USBD_MSC_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+uint8_t USBD_MSC_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+uint8_t USBD_MSC_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+uint8_t USBD_MSC_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+uint8_t USBD_MSC_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum);
+
+uint8_t *USBD_MSC_GetHSCfgDesc(uint16_t *length);
+uint8_t *USBD_MSC_GetFSCfgDesc(uint16_t *length);
+uint8_t *USBD_MSC_GetOtherSpeedCfgDesc(uint16_t *length);
+uint8_t *USBD_MSC_GetDeviceQualifierDescriptor(uint16_t *length);
+
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_CORE_Private_Variables
+ * @{
+ */
+
+
+USBD_ClassTypeDef USBD_MSC =
+{
+ USBD_MSC_Init,
+ USBD_MSC_DeInit,
+ USBD_MSC_Setup,
+ NULL, /*EP0_TxSent*/
+ NULL, /*EP0_RxReady*/
+ USBD_MSC_DataIn,
+ USBD_MSC_DataOut,
+ NULL, /*SOF */
+ NULL,
+ NULL,
+ USBD_MSC_GetHSCfgDesc,
+ USBD_MSC_GetFSCfgDesc,
+ USBD_MSC_GetOtherSpeedCfgDesc,
+ USBD_MSC_GetDeviceQualifierDescriptor,
+};
+
+/* USB Mass storage device Configuration Descriptor */
+/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
+__ALIGN_BEGIN static uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuation Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_MSC_CONFIG_DESC_SIZ,
+
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: */
+ 0x04, /* iConfiguration: */
+ 0xC0, /* bmAttributes: */
+ 0x32, /* MaxPower 100 mA */
+
+ /******************** Mass Storage interface ********************/
+ 0x09, /* bLength: Interface Descriptor size */
+ 0x04, /* bDescriptorType: */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints */
+ 0x08, /* bInterfaceClass: MSC Class */
+ 0x06, /* bInterfaceSubClass : SCSI transparent */
+ 0x50, /* nInterfaceProtocol */
+ 0x05, /* iInterface: */
+ /******************** Mass Storage Endpoints ********************/
+ 0x07, /* Endpoint descriptor length = 7 */
+ 0x05, /* Endpoint descriptor type */
+ MSC_EPIN_ADDR, /* Endpoint address (IN, address 1) */
+ 0x02, /* Bulk endpoint type */
+ LOBYTE(MSC_MAX_HS_PACKET),
+ HIBYTE(MSC_MAX_HS_PACKET),
+ 0x00, /* Polling interval in milliseconds */
+
+ 0x07, /* Endpoint descriptor length = 7 */
+ 0x05, /* Endpoint descriptor type */
+ MSC_EPOUT_ADDR, /* Endpoint address (OUT, address 1) */
+ 0x02, /* Bulk endpoint type */
+ LOBYTE(MSC_MAX_HS_PACKET),
+ HIBYTE(MSC_MAX_HS_PACKET),
+ 0x00 /* Polling interval in milliseconds */
+};
+
+/* USB Mass storage device Configuration Descriptor */
+/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
+__ALIGN_BEGIN static uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuation Descriptor size */
+ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_MSC_CONFIG_DESC_SIZ,
+
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: */
+ 0x04, /* iConfiguration: */
+ 0xC0, /* bmAttributes: */
+ 0x32, /* MaxPower 100 mA */
+
+ /******************** Mass Storage interface ********************/
+ 0x09, /* bLength: Interface Descriptor size */
+ 0x04, /* bDescriptorType: */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints*/
+ 0x08, /* bInterfaceClass: MSC Class */
+ 0x06, /* bInterfaceSubClass : SCSI transparent*/
+ 0x50, /* nInterfaceProtocol */
+ 0x05, /* iInterface: */
+ /******************** Mass Storage Endpoints ********************/
+ 0x07, /* Endpoint descriptor length = 7 */
+ 0x05, /* Endpoint descriptor type */
+ MSC_EPIN_ADDR, /* Endpoint address (IN, address 1) */
+ 0x02, /* Bulk endpoint type */
+ LOBYTE(MSC_MAX_FS_PACKET),
+ HIBYTE(MSC_MAX_FS_PACKET),
+ 0x00, /* Polling interval in milliseconds */
+
+ 0x07, /* Endpoint descriptor length = 7 */
+ 0x05, /* Endpoint descriptor type */
+ MSC_EPOUT_ADDR, /* Endpoint address (OUT, address 1) */
+ 0x02, /* Bulk endpoint type */
+ LOBYTE(MSC_MAX_FS_PACKET),
+ HIBYTE(MSC_MAX_FS_PACKET),
+ 0x00 /* Polling interval in milliseconds */
+};
+
+__ALIGN_BEGIN static uint8_t USBD_MSC_OtherSpeedCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuation Descriptor size */
+ USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION,
+ USB_MSC_CONFIG_DESC_SIZ,
+
+ 0x00,
+ 0x01, /* bNumInterfaces: 1 interface */
+ 0x01, /* bConfigurationValue: */
+ 0x04, /* iConfiguration: */
+ 0xC0, /* bmAttributes: */
+ 0x32, /* MaxPower 100 mA */
+
+ /******************** Mass Storage interface ********************/
+ 0x09, /* bLength: Interface Descriptor size */
+ 0x04, /* bDescriptorType: */
+ 0x00, /* bInterfaceNumber: Number of Interface */
+ 0x00, /* bAlternateSetting: Alternate setting */
+ 0x02, /* bNumEndpoints */
+ 0x08, /* bInterfaceClass: MSC Class */
+ 0x06, /* bInterfaceSubClass : SCSI transparent command set */
+ 0x50, /* nInterfaceProtocol */
+ 0x05, /* iInterface: */
+ /******************** Mass Storage Endpoints ********************/
+ 0x07, /* Endpoint descriptor length = 7 */
+ 0x05, /* Endpoint descriptor type */
+ MSC_EPIN_ADDR, /* Endpoint address (IN, address 1) */
+ 0x02, /* Bulk endpoint type */
+ 0x40,
+ 0x00,
+ 0x00, /* Polling interval in milliseconds */
+
+ 0x07, /* Endpoint descriptor length = 7 */
+ 0x05, /* Endpoint descriptor type */
+ MSC_EPOUT_ADDR, /* Endpoint address (OUT, address 1) */
+ 0x02, /* Bulk endpoint type */
+ 0x40,
+ 0x00,
+ 0x00 /* Polling interval in milliseconds */
+};
+
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_MSC_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ MSC_MAX_FS_PACKET,
+ 0x01,
+ 0x00,
+};
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_CORE_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_MSC_Init
+ * Initialize the mass storage configuration
+ * @param pdev: device instance
+ * @param cfgidx: configuration index
+ * @retval status
+ */
+uint8_t USBD_MSC_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+ USBD_MSC_BOT_HandleTypeDef *hmsc;
+
+ hmsc = USBD_malloc(sizeof(USBD_MSC_BOT_HandleTypeDef));
+
+ if (hmsc == NULL)
+ {
+ pdev->pClassData = NULL;
+ return (uint8_t)USBD_EMEM;
+ }
+
+ pdev->pClassData = (void *)hmsc;
+
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, MSC_EPOUT_ADDR, USBD_EP_TYPE_BULK, MSC_MAX_HS_PACKET);
+ pdev->ep_out[MSC_EPOUT_ADDR & 0xFU].is_used = 1U;
+
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, MSC_EPIN_ADDR, USBD_EP_TYPE_BULK, MSC_MAX_HS_PACKET);
+ pdev->ep_in[MSC_EPIN_ADDR & 0xFU].is_used = 1U;
+ }
+ else
+ {
+ /* Open EP OUT */
+ (void)USBD_LL_OpenEP(pdev, MSC_EPOUT_ADDR, USBD_EP_TYPE_BULK, MSC_MAX_FS_PACKET);
+ pdev->ep_out[MSC_EPOUT_ADDR & 0xFU].is_used = 1U;
+
+ /* Open EP IN */
+ (void)USBD_LL_OpenEP(pdev, MSC_EPIN_ADDR, USBD_EP_TYPE_BULK, MSC_MAX_FS_PACKET);
+ pdev->ep_in[MSC_EPIN_ADDR & 0xFU].is_used = 1U;
+ }
+
+ /* Init the BOT layer */
+ MSC_BOT_Init(pdev);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_MSC_DeInit
+ * DeInitilaize the mass storage configuration
+ * @param pdev: device instance
+ * @param cfgidx: configuration index
+ * @retval status
+ */
+uint8_t USBD_MSC_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ UNUSED(cfgidx);
+
+ /* Close MSC EPs */
+ (void)USBD_LL_CloseEP(pdev, MSC_EPOUT_ADDR);
+ pdev->ep_out[MSC_EPOUT_ADDR & 0xFU].is_used = 0U;
+
+ /* Close EP IN */
+ (void)USBD_LL_CloseEP(pdev, MSC_EPIN_ADDR);
+ pdev->ep_in[MSC_EPIN_ADDR & 0xFU].is_used = 0U;
+
+ /* De-Init the BOT layer */
+ MSC_BOT_DeInit(pdev);
+
+ /* Free MSC Class Resources */
+ if (pdev->pClassData != NULL)
+ {
+ (void)USBD_free(pdev->pClassData);
+ pdev->pClassData = NULL;
+ }
+
+ return (uint8_t)USBD_OK;
+}
+/**
+* @brief USBD_MSC_Setup
+* Handle the MSC specific requests
+* @param pdev: device instance
+* @param req: USB request
+* @retval status
+*/
+uint8_t USBD_MSC_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+ USBD_StatusTypeDef ret = USBD_OK;
+ uint16_t status_info = 0U;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ /* Class request */
+ case USB_REQ_TYPE_CLASS:
+ switch (req->bRequest)
+ {
+ case BOT_GET_MAX_LUN:
+ if ((req->wValue == 0U) && (req->wLength == 1U) &&
+ ((req->bmRequest & 0x80U) == 0x80U))
+ {
+ hmsc->max_lun = (uint32_t)((USBD_StorageTypeDef *)pdev->pUserData)->GetMaxLun();
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&hmsc->max_lun, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case BOT_RESET :
+ if ((req->wValue == 0U) && (req->wLength == 0U) &&
+ ((req->bmRequest & 0x80U) != 0x80U))
+ {
+ MSC_BOT_Reset(pdev);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+ /* Interface & Endpoint request */
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_STATUS:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&status_info, 2U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_GET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&hmsc->interface, 1U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_SET_INTERFACE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ hmsc->interface = (uint8_t)(req->wValue);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ if (req->wValue == USB_FEATURE_EP_HALT)
+ {
+ /* Flush the FIFO */
+ (void)USBD_LL_FlushEP(pdev, (uint8_t)req->wIndex);
+
+ /* Handle BOT error */
+ MSC_BOT_CplClrFeature(pdev, (uint8_t)req->wIndex);
+ }
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+/**
+* @brief USBD_MSC_DataIn
+* handle data IN Stage
+* @param pdev: device instance
+* @param epnum: endpoint index
+* @retval status
+*/
+uint8_t USBD_MSC_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ MSC_BOT_DataIn(pdev, epnum);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+* @brief USBD_MSC_DataOut
+* handle data OUT Stage
+* @param pdev: device instance
+* @param epnum: endpoint index
+* @retval status
+*/
+uint8_t USBD_MSC_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ MSC_BOT_DataOut(pdev, epnum);
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+* @brief USBD_MSC_GetHSCfgDesc
+* return configuration descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+uint8_t *USBD_MSC_GetHSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_MSC_CfgHSDesc);
+
+ return USBD_MSC_CfgHSDesc;
+}
+
+/**
+* @brief USBD_MSC_GetFSCfgDesc
+* return configuration descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+uint8_t *USBD_MSC_GetFSCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_MSC_CfgFSDesc);
+
+ return USBD_MSC_CfgFSDesc;
+}
+
+/**
+* @brief USBD_MSC_GetOtherSpeedCfgDesc
+* return other speed configuration descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+uint8_t *USBD_MSC_GetOtherSpeedCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_MSC_OtherSpeedCfgDesc);
+
+ return USBD_MSC_OtherSpeedCfgDesc;
+}
+/**
+* @brief DeviceQualifierDescriptor
+* return Device Qualifier descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+uint8_t *USBD_MSC_GetDeviceQualifierDescriptor(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_MSC_DeviceQualifierDesc);
+
+ return USBD_MSC_DeviceQualifierDesc;
+}
+
+/**
+* @brief USBD_MSC_RegisterStorage
+* @param fops: storage callback
+* @retval status
+*/
+uint8_t USBD_MSC_RegisterStorage(USBD_HandleTypeDef *pdev, USBD_StorageTypeDef *fops)
+{
+ if (fops == NULL)
+ {
+ return (uint8_t)USBD_FAIL;
+ }
+
+ pdev->pUserData = fops;
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_bot.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_bot.c
new file mode 100644
index 0000000000..ae68ac055c
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_bot.c
@@ -0,0 +1,386 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc_bot.c
+ * @author MCD Application Team
+ * @brief This file provides all the BOT protocol core functions.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+- "stm32xxxxx_{eval}{discovery}{adafruit}_sd.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_msc_bot.h"
+#include "usbd_msc.h"
+#include "usbd_msc_scsi.h"
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup MSC_BOT
+ * @brief BOT protocol module
+ * @{
+ */
+
+/** @defgroup MSC_BOT_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_BOT_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_BOT_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_BOT_Private_Variables
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_BOT_Private_FunctionPrototypes
+ * @{
+ */
+static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev, uint8_t *pbuf, uint32_t len);
+static void MSC_BOT_CBW_Decode(USBD_HandleTypeDef *pdev);
+static void MSC_BOT_Abort(USBD_HandleTypeDef *pdev);
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_BOT_Private_Functions
+ * @{
+ */
+
+
+/**
+* @brief MSC_BOT_Init
+* Initialize the BOT Process
+* @param pdev: device instance
+* @retval None
+*/
+void MSC_BOT_Init(USBD_HandleTypeDef *pdev)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ hmsc->bot_state = USBD_BOT_IDLE;
+ hmsc->bot_status = USBD_BOT_STATUS_NORMAL;
+
+ hmsc->scsi_sense_tail = 0U;
+ hmsc->scsi_sense_head = 0U;
+ hmsc->scsi_medium_state = SCSI_MEDIUM_UNLOCKED;
+
+ ((USBD_StorageTypeDef *)pdev->pUserData)->Init(0U);
+
+ (void)USBD_LL_FlushEP(pdev, MSC_EPOUT_ADDR);
+ (void)USBD_LL_FlushEP(pdev, MSC_EPIN_ADDR);
+
+ /* Prapare EP to Receive First BOT Cmd */
+ (void)USBD_LL_PrepareReceive(pdev, MSC_EPOUT_ADDR, (uint8_t *)&hmsc->cbw,
+ USBD_BOT_CBW_LENGTH);
+}
+
+/**
+* @brief MSC_BOT_Reset
+* Reset the BOT Machine
+* @param pdev: device instance
+* @retval None
+*/
+void MSC_BOT_Reset(USBD_HandleTypeDef *pdev)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ hmsc->bot_state = USBD_BOT_IDLE;
+ hmsc->bot_status = USBD_BOT_STATUS_RECOVERY;
+
+ (void)USBD_LL_ClearStallEP(pdev, MSC_EPIN_ADDR);
+ (void)USBD_LL_ClearStallEP(pdev, MSC_EPOUT_ADDR);
+
+ /* Prapare EP to Receive First BOT Cmd */
+ (void)USBD_LL_PrepareReceive(pdev, MSC_EPOUT_ADDR, (uint8_t *)&hmsc->cbw,
+ USBD_BOT_CBW_LENGTH);
+}
+
+/**
+* @brief MSC_BOT_DeInit
+* Deinitialize the BOT Machine
+* @param pdev: device instance
+* @retval None
+*/
+void MSC_BOT_DeInit(USBD_HandleTypeDef *pdev)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+ hmsc->bot_state = USBD_BOT_IDLE;
+}
+
+/**
+* @brief MSC_BOT_DataIn
+* Handle BOT IN data stage
+* @param pdev: device instance
+* @param epnum: endpoint index
+* @retval None
+*/
+void MSC_BOT_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ UNUSED(epnum);
+
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ switch (hmsc->bot_state)
+ {
+ case USBD_BOT_DATA_IN:
+ if (SCSI_ProcessCmd(pdev, hmsc->cbw.bLUN, &hmsc->cbw.CB[0]) < 0)
+ {
+ MSC_BOT_SendCSW(pdev, USBD_CSW_CMD_FAILED);
+ }
+ break;
+
+ case USBD_BOT_SEND_DATA:
+ case USBD_BOT_LAST_DATA_IN:
+ MSC_BOT_SendCSW(pdev, USBD_CSW_CMD_PASSED);
+ break;
+
+ default:
+ break;
+ }
+}
+/**
+* @brief MSC_BOT_DataOut
+* Process MSC OUT data
+* @param pdev: device instance
+* @param epnum: endpoint index
+* @retval None
+*/
+void MSC_BOT_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ UNUSED(epnum);
+
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ switch (hmsc->bot_state)
+ {
+ case USBD_BOT_IDLE:
+ MSC_BOT_CBW_Decode(pdev);
+ break;
+
+ case USBD_BOT_DATA_OUT:
+ if (SCSI_ProcessCmd(pdev, hmsc->cbw.bLUN, &hmsc->cbw.CB[0]) < 0)
+ {
+ MSC_BOT_SendCSW(pdev, USBD_CSW_CMD_FAILED);
+ }
+ break;
+
+ default:
+ break;
+ }
+}
+
+/**
+* @brief MSC_BOT_CBW_Decode
+* Decode the CBW command and set the BOT state machine accordingly
+* @param pdev: device instance
+* @retval None
+*/
+static void MSC_BOT_CBW_Decode(USBD_HandleTypeDef *pdev)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ hmsc->csw.dTag = hmsc->cbw.dTag;
+ hmsc->csw.dDataResidue = hmsc->cbw.dDataLength;
+
+ if ((USBD_LL_GetRxDataSize(pdev, MSC_EPOUT_ADDR) != USBD_BOT_CBW_LENGTH) ||
+ (hmsc->cbw.dSignature != USBD_BOT_CBW_SIGNATURE) ||
+ (hmsc->cbw.bLUN > 1U) || (hmsc->cbw.bCBLength < 1U) ||
+ (hmsc->cbw.bCBLength > 16U))
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+ hmsc->bot_status = USBD_BOT_STATUS_ERROR;
+ MSC_BOT_Abort(pdev);
+ }
+ else
+ {
+ if (SCSI_ProcessCmd(pdev, hmsc->cbw.bLUN, &hmsc->cbw.CB[0]) < 0)
+ {
+ if (hmsc->bot_state == USBD_BOT_NO_DATA)
+ {
+ MSC_BOT_SendCSW(pdev, USBD_CSW_CMD_FAILED);
+ }
+ else
+ {
+ MSC_BOT_Abort(pdev);
+ }
+ }
+ /* Burst xfer handled internally */
+ else if ((hmsc->bot_state != USBD_BOT_DATA_IN) &&
+ (hmsc->bot_state != USBD_BOT_DATA_OUT) &&
+ (hmsc->bot_state != USBD_BOT_LAST_DATA_IN))
+ {
+ if (hmsc->bot_data_length > 0U)
+ {
+ MSC_BOT_SendData(pdev, hmsc->bot_data, hmsc->bot_data_length);
+ }
+ else if (hmsc->bot_data_length == 0U)
+ {
+ MSC_BOT_SendCSW(pdev, USBD_CSW_CMD_PASSED);
+ }
+ else
+ {
+ MSC_BOT_Abort(pdev);
+ }
+ }
+ else
+ {
+ return;
+ }
+ }
+}
+
+/**
+* @brief MSC_BOT_SendData
+* Send the requested data
+* @param pdev: device instance
+* @param buf: pointer to data buffer
+* @param len: Data Length
+* @retval None
+*/
+static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev, uint8_t *pbuf, uint32_t len)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ uint32_t length = MIN(hmsc->cbw.dDataLength, len);
+
+ hmsc->csw.dDataResidue -= len;
+ hmsc->csw.bStatus = USBD_CSW_CMD_PASSED;
+ hmsc->bot_state = USBD_BOT_SEND_DATA;
+
+ (void)USBD_LL_Transmit(pdev, MSC_EPIN_ADDR, pbuf, length);
+}
+
+/**
+* @brief MSC_BOT_SendCSW
+* Send the Command Status Wrapper
+* @param pdev: device instance
+* @param status : CSW status
+* @retval None
+*/
+void MSC_BOT_SendCSW(USBD_HandleTypeDef *pdev, uint8_t CSW_Status)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ hmsc->csw.dSignature = USBD_BOT_CSW_SIGNATURE;
+ hmsc->csw.bStatus = CSW_Status;
+ hmsc->bot_state = USBD_BOT_IDLE;
+
+ (void)USBD_LL_Transmit(pdev, MSC_EPIN_ADDR, (uint8_t *)&hmsc->csw,
+ USBD_BOT_CSW_LENGTH);
+
+ /* Prepare EP to Receive next Cmd */
+ (void)USBD_LL_PrepareReceive(pdev, MSC_EPOUT_ADDR, (uint8_t *)&hmsc->cbw,
+ USBD_BOT_CBW_LENGTH);
+}
+
+/**
+* @brief MSC_BOT_Abort
+* Abort the current transfer
+* @param pdev: device instance
+* @retval status
+*/
+
+static void MSC_BOT_Abort(USBD_HandleTypeDef *pdev)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if ((hmsc->cbw.bmFlags == 0U) &&
+ (hmsc->cbw.dDataLength != 0U) &&
+ (hmsc->bot_status == USBD_BOT_STATUS_NORMAL))
+ {
+ (void)USBD_LL_StallEP(pdev, MSC_EPOUT_ADDR);
+ }
+
+ (void)USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
+
+ if (hmsc->bot_status == USBD_BOT_STATUS_ERROR)
+ {
+ (void)USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
+ (void)USBD_LL_StallEP(pdev, MSC_EPOUT_ADDR);
+ }
+}
+
+/**
+* @brief MSC_BOT_CplClrFeature
+* Complete the clear feature request
+* @param pdev: device instance
+* @param epnum: endpoint index
+* @retval None
+*/
+
+void MSC_BOT_CplClrFeature(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if (hmsc->bot_status == USBD_BOT_STATUS_ERROR) /* Bad CBW Signature */
+ {
+ (void)USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
+ (void)USBD_LL_StallEP(pdev, MSC_EPOUT_ADDR);
+ }
+ else if (((epnum & 0x80U) == 0x80U) && (hmsc->bot_status != USBD_BOT_STATUS_RECOVERY))
+ {
+ MSC_BOT_SendCSW(pdev, USBD_CSW_CMD_FAILED);
+ }
+ else
+ {
+ return;
+ }
+}
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_data.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_data.c
new file mode 100644
index 0000000000..d1c3a9772d
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_data.c
@@ -0,0 +1,183 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc_data.c
+ * @author MCD Application Team
+ * @brief This file provides all the vital inquiry pages and sense data.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+- "stm32xxxxx_{eval}{discovery}{adafruit}_sd.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_msc_data.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup MSC_DATA
+ * @brief Mass storage info/data module
+ * @{
+ */
+
+/** @defgroup MSC_DATA_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_DATA_Private_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_DATA_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_DATA_Private_Variables
+ * @{
+ */
+
+/* USB Mass storage Page 0 Inquiry Data */
+uint8_t MSC_Page00_Inquiry_Data[LENGTH_INQUIRY_PAGE00] =
+{
+ 0x00,
+ 0x00,
+ 0x00,
+ (LENGTH_INQUIRY_PAGE00 - 4U),
+ 0x00,
+ 0x80
+};
+
+/* USB Mass storage VPD Page 0x80 Inquiry Data for Unit Serial Number */
+uint8_t MSC_Page80_Inquiry_Data[LENGTH_INQUIRY_PAGE80] =
+{
+ 0x00,
+ 0x80,
+ 0x00,
+ LENGTH_INQUIRY_PAGE80,
+ 0x20, /* Put Product Serial number */
+ 0x20,
+ 0x20,
+ 0x20
+ };
+
+/* USB Mass storage sense 6 Data */
+uint8_t MSC_Mode_Sense6_data[MODE_SENSE6_LEN] =
+{
+ 0x22,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x08,
+ 0x12,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00
+};
+
+
+/* USB Mass storage sense 10 Data */
+uint8_t MSC_Mode_Sense10_data[MODE_SENSE10_LEN] =
+{
+ 0x00,
+ 0x26,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x08,
+ 0x12,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x00
+};
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_DATA_Private_FunctionPrototypes
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_DATA_Private_Functions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_scsi.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_scsi.c
new file mode 100644
index 0000000000..5c36a6e8c8
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_scsi.c
@@ -0,0 +1,1075 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc_scsi.c
+ * @author MCD Application Team
+ * @brief This file provides all the USBD SCSI layer functions.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+- "stm32xxxxx_{eval}{discovery}{adafruit}_sd.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_msc_bot.h"
+#include "usbd_msc_scsi.h"
+#include "usbd_msc.h"
+#include "usbd_msc_data.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup MSC_SCSI
+ * @brief Mass storage SCSI layer module
+ * @{
+ */
+
+/** @defgroup MSC_SCSI_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_SCSI_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_SCSI_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_SCSI_Private_Variables
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_SCSI_Private_FunctionPrototypes
+ * @{
+ */
+static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_ReadCapacity10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_ReadCapacity16(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_RequestSense(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_StartStopUnit(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_AllowPreventRemovable(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_ModeSense6(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_ModeSense10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_Write10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_Write12(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_Read12(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
+static int8_t SCSI_CheckAddressRange(USBD_HandleTypeDef *pdev, uint8_t lun,
+ uint32_t blk_offset, uint32_t blk_nbr);
+
+static int8_t SCSI_ProcessRead(USBD_HandleTypeDef *pdev, uint8_t lun);
+static int8_t SCSI_ProcessWrite(USBD_HandleTypeDef *pdev, uint8_t lun);
+
+static int8_t SCSI_UpdateBotData(USBD_MSC_BOT_HandleTypeDef *hmsc,
+ uint8_t *pBuff, uint16_t length);
+/**
+ * @}
+ */
+
+
+/** @defgroup MSC_SCSI_Private_Functions
+ * @{
+ */
+
+
+/**
+* @brief SCSI_ProcessCmd
+* Process SCSI commands
+* @param pdev: device instance
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *cmd)
+{
+ int8_t ret;
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ switch (cmd[0])
+ {
+ case SCSI_TEST_UNIT_READY:
+ ret = SCSI_TestUnitReady(pdev, lun, cmd);
+ break;
+
+ case SCSI_REQUEST_SENSE:
+ ret = SCSI_RequestSense(pdev, lun, cmd);
+ break;
+
+ case SCSI_INQUIRY:
+ ret = SCSI_Inquiry(pdev, lun, cmd);
+ break;
+
+ case SCSI_START_STOP_UNIT:
+ ret = SCSI_StartStopUnit(pdev, lun, cmd);
+ break;
+
+ case SCSI_ALLOW_MEDIUM_REMOVAL:
+ ret = SCSI_AllowPreventRemovable(pdev, lun, cmd);
+ break;
+
+ case SCSI_MODE_SENSE6:
+ ret = SCSI_ModeSense6(pdev, lun, cmd);
+ break;
+
+ case SCSI_MODE_SENSE10:
+ ret = SCSI_ModeSense10(pdev, lun, cmd);
+ break;
+
+ case SCSI_READ_FORMAT_CAPACITIES:
+ ret = SCSI_ReadFormatCapacity(pdev, lun, cmd);
+ break;
+
+ case SCSI_READ_CAPACITY10:
+ ret = SCSI_ReadCapacity10(pdev, lun, cmd);
+ break;
+
+ case SCSI_READ_CAPACITY16:
+ ret = SCSI_ReadCapacity16(pdev, lun, cmd);
+ break;
+
+ case SCSI_READ10:
+ ret = SCSI_Read10(pdev, lun, cmd);
+ break;
+
+ case SCSI_READ12:
+ ret = SCSI_Read12(pdev, lun, cmd);
+ break;
+
+ case SCSI_WRITE10:
+ ret = SCSI_Write10(pdev, lun, cmd);
+ break;
+
+ case SCSI_WRITE12:
+ ret = SCSI_Write12(pdev, lun, cmd);
+ break;
+
+ case SCSI_VERIFY10:
+ ret = SCSI_Verify10(pdev, lun, cmd);
+ break;
+
+ default:
+ SCSI_SenseCode(pdev, lun, ILLEGAL_REQUEST, INVALID_CDB);
+ hmsc->bot_status = USBD_BOT_STATUS_ERROR;
+ ret = -1;
+ break;
+ }
+
+ return ret;
+}
+
+
+/**
+* @brief SCSI_TestUnitReady
+* Process SCSI Test Unit Ready Command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(params);
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ /* case 9 : Hi > D0 */
+ if (hmsc->cbw.dDataLength != 0U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+
+ return -1;
+ }
+
+ if (hmsc->scsi_medium_state == SCSI_MEDIUM_EJECTED)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ hmsc->bot_state = USBD_BOT_NO_DATA;
+ return -1;
+ }
+
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) != 0)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ hmsc->bot_state = USBD_BOT_NO_DATA;
+
+ return -1;
+ }
+ hmsc->bot_data_length = 0U;
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_Inquiry
+* Process Inquiry command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ uint8_t *pPage;
+ uint16_t len;
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if (hmsc->cbw.dDataLength == 0U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ if ((params[1] & 0x01U) != 0U) /* Evpd is set */
+ {
+ if (params[2] == 0U) /* Request for Supported Vital Product Data Pages*/
+ {
+ (void)SCSI_UpdateBotData(hmsc, MSC_Page00_Inquiry_Data, LENGTH_INQUIRY_PAGE00);
+ }
+ else if (params[2] == 0x80U) /* Request for VPD page 0x80 Unit Serial Number */
+ {
+ (void)SCSI_UpdateBotData(hmsc, MSC_Page80_Inquiry_Data, LENGTH_INQUIRY_PAGE80);
+ }
+ else /* Request Not supported */
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST,
+ INVALID_FIELED_IN_COMMAND);
+
+ return -1;
+ }
+ }
+ else
+ {
+ pPage = (uint8_t *)&((USBD_StorageTypeDef *)pdev->pUserData)->pInquiry[lun * STANDARD_INQUIRY_DATA_LEN];
+ len = (uint16_t)pPage[4] + 5U;
+
+ if (params[4] <= len)
+ {
+ len = params[4];
+ }
+
+ (void)SCSI_UpdateBotData(hmsc, pPage, len);
+ }
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_ReadCapacity10
+* Process Read Capacity 10 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_ReadCapacity10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(params);
+ int8_t ret;
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ ret = ((USBD_StorageTypeDef *)pdev->pUserData)->GetCapacity(lun, &hmsc->scsi_blk_nbr, &hmsc->scsi_blk_size);
+
+ if ((ret != 0) || (hmsc->scsi_medium_state == SCSI_MEDIUM_EJECTED))
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ return -1;
+ }
+
+ hmsc->bot_data[0] = (uint8_t)((hmsc->scsi_blk_nbr - 1U) >> 24);
+ hmsc->bot_data[1] = (uint8_t)((hmsc->scsi_blk_nbr - 1U) >> 16);
+ hmsc->bot_data[2] = (uint8_t)((hmsc->scsi_blk_nbr - 1U) >> 8);
+ hmsc->bot_data[3] = (uint8_t)(hmsc->scsi_blk_nbr - 1U);
+
+ hmsc->bot_data[4] = (uint8_t)(hmsc->scsi_blk_size >> 24);
+ hmsc->bot_data[5] = (uint8_t)(hmsc->scsi_blk_size >> 16);
+ hmsc->bot_data[6] = (uint8_t)(hmsc->scsi_blk_size >> 8);
+ hmsc->bot_data[7] = (uint8_t)(hmsc->scsi_blk_size);
+
+ hmsc->bot_data_length = 8U;
+
+ return 0;
+
+}
+
+
+/**
+* @brief SCSI_ReadCapacity16
+* Process Read Capacity 16 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_ReadCapacity16(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(params);
+ uint8_t idx;
+ int8_t ret;
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ ret = ((USBD_StorageTypeDef *)pdev->pUserData)->GetCapacity(lun, &hmsc->scsi_blk_nbr, &hmsc->scsi_blk_size);
+
+ if ((ret != 0) || (hmsc->scsi_medium_state == SCSI_MEDIUM_EJECTED))
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ return -1;
+ }
+
+ hmsc->bot_data_length = ((uint32_t)params[10] << 24) |
+ ((uint32_t)params[11] << 16) |
+ ((uint32_t)params[12] << 8) |
+ (uint32_t)params[13];
+
+ for (idx = 0U; idx < hmsc->bot_data_length; idx++)
+ {
+ hmsc->bot_data[idx] = 0U;
+ }
+
+ hmsc->bot_data[4] = (uint8_t)((hmsc->scsi_blk_nbr - 1U) >> 24);
+ hmsc->bot_data[5] = (uint8_t)((hmsc->scsi_blk_nbr - 1U) >> 16);
+ hmsc->bot_data[6] = (uint8_t)((hmsc->scsi_blk_nbr - 1U) >> 8);
+ hmsc->bot_data[7] = (uint8_t)(hmsc->scsi_blk_nbr - 1U);
+
+ hmsc->bot_data[8] = (uint8_t)(hmsc->scsi_blk_size >> 24);
+ hmsc->bot_data[9] = (uint8_t)(hmsc->scsi_blk_size >> 16);
+ hmsc->bot_data[10] = (uint8_t)(hmsc->scsi_blk_size >> 8);
+ hmsc->bot_data[11] = (uint8_t)(hmsc->scsi_blk_size);
+
+ hmsc->bot_data_length = ((uint32_t)params[10] << 24) |
+ ((uint32_t)params[11] << 16) |
+ ((uint32_t)params[12] << 8) |
+ (uint32_t)params[13];
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_ReadFormatCapacity
+* Process Read Format Capacity command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(params);
+ uint16_t blk_size;
+ uint32_t blk_nbr;
+ uint16_t i;
+ int8_t ret;
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ ret = ((USBD_StorageTypeDef *)pdev->pUserData)->GetCapacity(lun, &blk_nbr, &blk_size);
+
+ if ((ret != 0) || (hmsc->scsi_medium_state == SCSI_MEDIUM_EJECTED))
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ return -1;
+ }
+
+ for (i = 0U; i < 12U ; i++)
+ {
+ hmsc->bot_data[i] = 0U;
+ }
+
+ hmsc->bot_data[3] = 0x08U;
+ hmsc->bot_data[4] = (uint8_t)((blk_nbr - 1U) >> 24);
+ hmsc->bot_data[5] = (uint8_t)((blk_nbr - 1U) >> 16);
+ hmsc->bot_data[6] = (uint8_t)((blk_nbr - 1U) >> 8);
+ hmsc->bot_data[7] = (uint8_t)(blk_nbr - 1U);
+
+ hmsc->bot_data[8] = 0x02U;
+ hmsc->bot_data[9] = (uint8_t)(blk_size >> 16);
+ hmsc->bot_data[10] = (uint8_t)(blk_size >> 8);
+ hmsc->bot_data[11] = (uint8_t)(blk_size);
+
+ hmsc->bot_data_length = 12U;
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_ModeSense6
+* Process Mode Sense6 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_ModeSense6(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(lun);
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+ uint16_t len = MODE_SENSE6_LEN;
+
+ if (params[4] <= len)
+ {
+ len = params[4];
+ }
+
+ (void)SCSI_UpdateBotData(hmsc, MSC_Mode_Sense6_data, len);
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_ModeSense10
+* Process Mode Sense10 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_ModeSense10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(lun);
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+ uint16_t len = MODE_SENSE10_LEN;
+
+ if (params[8] <= len)
+ {
+ len = params[8];
+ }
+
+ (void)SCSI_UpdateBotData(hmsc, MSC_Mode_Sense10_data, len);
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_RequestSense
+* Process Request Sense command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_RequestSense(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(lun);
+ uint8_t i;
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if (hmsc->cbw.dDataLength == 0U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ for (i = 0U; i < REQUEST_SENSE_DATA_LEN; i++)
+ {
+ hmsc->bot_data[i] = 0U;
+ }
+
+ hmsc->bot_data[0] = 0x70U;
+ hmsc->bot_data[7] = REQUEST_SENSE_DATA_LEN - 6U;
+
+ if ((hmsc->scsi_sense_head != hmsc->scsi_sense_tail))
+ {
+ hmsc->bot_data[2] = (uint8_t)hmsc->scsi_sense[hmsc->scsi_sense_head].Skey;
+ hmsc->bot_data[12] = (uint8_t)hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASC;
+ hmsc->bot_data[13] = (uint8_t)hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASCQ;
+ hmsc->scsi_sense_head++;
+
+ if (hmsc->scsi_sense_head == SENSE_LIST_DEEPTH)
+ {
+ hmsc->scsi_sense_head = 0U;
+ }
+ }
+
+ hmsc->bot_data_length = REQUEST_SENSE_DATA_LEN;
+
+ if (params[4] <= REQUEST_SENSE_DATA_LEN)
+ {
+ hmsc->bot_data_length = params[4];
+ }
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_SenseCode
+* Load the last error code in the error list
+* @param lun: Logical unit number
+* @param sKey: Sense Key
+* @param ASC: Additional Sense Code
+* @retval none
+
+*/
+void SCSI_SenseCode(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t sKey, uint8_t ASC)
+{
+ UNUSED(lun);
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ hmsc->scsi_sense[hmsc->scsi_sense_tail].Skey = sKey;
+ hmsc->scsi_sense[hmsc->scsi_sense_tail].w.b.ASC = ASC;
+ hmsc->scsi_sense[hmsc->scsi_sense_tail].w.b.ASCQ = 0U;
+ hmsc->scsi_sense_tail++;
+
+ if (hmsc->scsi_sense_tail == SENSE_LIST_DEEPTH)
+ {
+ hmsc->scsi_sense_tail = 0U;
+ }
+}
+
+
+/**
+* @brief SCSI_StartStopUnit
+* Process Start Stop Unit command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_StartStopUnit(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(lun);
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if ((hmsc->scsi_medium_state == SCSI_MEDIUM_LOCKED) && ((params[4] & 0x3U) == 2U))
+ {
+ SCSI_SenseCode(pdev, lun, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND);
+
+ return -1;
+ }
+
+ if ((params[4] & 0x3U) == 0x1U) /* START=1 */
+ {
+ hmsc->scsi_medium_state = SCSI_MEDIUM_UNLOCKED;
+ }
+ else if ((params[4] & 0x3U) == 0x2U) /* START=0 and LOEJ Load Eject=1 */
+ {
+ hmsc->scsi_medium_state = SCSI_MEDIUM_EJECTED;
+ }
+ else if ((params[4] & 0x3U) == 0x3U) /* START=1 and LOEJ Load Eject=1 */
+ {
+ hmsc->scsi_medium_state = SCSI_MEDIUM_UNLOCKED;
+ }
+ else
+ {
+ /* .. */
+ }
+ hmsc->bot_data_length = 0U;
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_AllowPreventRemovable
+* Process Allow Prevent Removable medium command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_AllowPreventRemovable(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ UNUSED(lun);
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if (params[4] == 0U)
+ {
+ hmsc->scsi_medium_state = SCSI_MEDIUM_UNLOCKED;
+ }
+ else
+ {
+ hmsc->scsi_medium_state = SCSI_MEDIUM_LOCKED;
+ }
+
+ hmsc->bot_data_length = 0U;
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_Read10
+* Process Read10 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if (hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
+ {
+ /* case 10 : Ho <> Di */
+ if ((hmsc->cbw.bmFlags & 0x80U) != 0x80U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ if (hmsc->scsi_medium_state == SCSI_MEDIUM_EJECTED)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+
+ return -1;
+ }
+
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) != 0)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ return -1;
+ }
+
+ hmsc->scsi_blk_addr = ((uint32_t)params[2] << 24) |
+ ((uint32_t)params[3] << 16) |
+ ((uint32_t)params[4] << 8) |
+ (uint32_t)params[5];
+
+ hmsc->scsi_blk_len = ((uint32_t)params[7] << 8) | (uint32_t)params[8];
+
+ if (SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr,
+ hmsc->scsi_blk_len) < 0)
+ {
+ return -1; /* error */
+ }
+
+ /* cases 4,5 : Hi <> Dn */
+ if (hmsc->cbw.dDataLength != (hmsc->scsi_blk_len * hmsc->scsi_blk_size))
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ hmsc->bot_state = USBD_BOT_DATA_IN;
+ }
+ hmsc->bot_data_length = MSC_MEDIA_PACKET;
+
+ return SCSI_ProcessRead(pdev, lun);
+}
+
+
+/**
+* @brief SCSI_Read12
+* Process Read12 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_Read12(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if (hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
+ {
+ /* case 10 : Ho <> Di */
+ if ((hmsc->cbw.bmFlags & 0x80U) != 0x80U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ if (hmsc->scsi_medium_state == SCSI_MEDIUM_EJECTED)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ return -1;
+ }
+
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) != 0)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ return -1;
+ }
+
+ hmsc->scsi_blk_addr = ((uint32_t)params[2] << 24) |
+ ((uint32_t)params[3] << 16) |
+ ((uint32_t)params[4] << 8) |
+ (uint32_t)params[5];
+
+ hmsc->scsi_blk_len = ((uint32_t)params[6] << 24) |
+ ((uint32_t)params[7] << 16) |
+ ((uint32_t)params[8] << 8) |
+ (uint32_t)params[9];
+
+ if (SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr,
+ hmsc->scsi_blk_len) < 0)
+ {
+ return -1; /* error */
+ }
+
+ /* cases 4,5 : Hi <> Dn */
+ if (hmsc->cbw.dDataLength != (hmsc->scsi_blk_len * hmsc->scsi_blk_size))
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ hmsc->bot_state = USBD_BOT_DATA_IN;
+ }
+ hmsc->bot_data_length = MSC_MEDIA_PACKET;
+
+ return SCSI_ProcessRead(pdev, lun);
+}
+
+
+/**
+* @brief SCSI_Write10
+* Process Write10 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_Write10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+ uint32_t len;
+
+ if (hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
+ {
+ if (hmsc->cbw.dDataLength == 0U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ /* case 8 : Hi <> Do */
+ if ((hmsc->cbw.bmFlags & 0x80U) == 0x80U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ /* Check whether Media is ready */
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) != 0)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ return -1;
+ }
+
+ /* Check If media is write-protected */
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->IsWriteProtected(lun) != 0)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, WRITE_PROTECTED);
+ return -1;
+ }
+
+ hmsc->scsi_blk_addr = ((uint32_t)params[2] << 24) |
+ ((uint32_t)params[3] << 16) |
+ ((uint32_t)params[4] << 8) |
+ (uint32_t)params[5];
+
+ hmsc->scsi_blk_len = ((uint32_t)params[7] << 8) |
+ (uint32_t)params[8];
+
+ /* check if LBA address is in the right range */
+ if (SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr,
+ hmsc->scsi_blk_len) < 0)
+ {
+ return -1; /* error */
+ }
+
+ len = hmsc->scsi_blk_len * hmsc->scsi_blk_size;
+
+ /* cases 3,11,13 : Hn,Ho <> D0 */
+ if (hmsc->cbw.dDataLength != len)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ len = MIN(len, MSC_MEDIA_PACKET);
+
+ /* Prepare EP to receive first data packet */
+ hmsc->bot_state = USBD_BOT_DATA_OUT;
+ (void)USBD_LL_PrepareReceive(pdev, MSC_EPOUT_ADDR, hmsc->bot_data, len);
+ }
+ else /* Write Process ongoing */
+ {
+ return SCSI_ProcessWrite(pdev, lun);
+ }
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_Write12
+* Process Write12 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_Write12(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+ uint32_t len;
+
+ if (hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
+ {
+ if (hmsc->cbw.dDataLength == 0U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ /* case 8 : Hi <> Do */
+ if ((hmsc->cbw.bmFlags & 0x80U) == 0x80U)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ /* Check whether Media is ready */
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) != 0)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, MEDIUM_NOT_PRESENT);
+ hmsc->bot_state = USBD_BOT_NO_DATA;
+ return -1;
+ }
+
+ /* Check If media is write-protected */
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->IsWriteProtected(lun) != 0)
+ {
+ SCSI_SenseCode(pdev, lun, NOT_READY, WRITE_PROTECTED);
+ hmsc->bot_state = USBD_BOT_NO_DATA;
+ return -1;
+ }
+
+ hmsc->scsi_blk_addr = ((uint32_t)params[2] << 24) |
+ ((uint32_t)params[3] << 16) |
+ ((uint32_t)params[4] << 8) |
+ (uint32_t)params[5];
+
+ hmsc->scsi_blk_len = ((uint32_t)params[6] << 24) |
+ ((uint32_t)params[7] << 16) |
+ ((uint32_t)params[8] << 8) |
+ (uint32_t)params[9];
+
+ /* check if LBA address is in the right range */
+ if (SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr,
+ hmsc->scsi_blk_len) < 0)
+ {
+ return -1; /* error */
+ }
+
+ len = hmsc->scsi_blk_len * hmsc->scsi_blk_size;
+
+ /* cases 3,11,13 : Hn,Ho <> D0 */
+ if (hmsc->cbw.dDataLength != len)
+ {
+ SCSI_SenseCode(pdev, hmsc->cbw.bLUN, ILLEGAL_REQUEST, INVALID_CDB);
+ return -1;
+ }
+
+ len = MIN(len, MSC_MEDIA_PACKET);
+
+ /* Prepare EP to receive first data packet */
+ hmsc->bot_state = USBD_BOT_DATA_OUT;
+ (void)USBD_LL_PrepareReceive(pdev, MSC_EPOUT_ADDR, hmsc->bot_data, len);
+ }
+ else /* Write Process ongoing */
+ {
+ return SCSI_ProcessWrite(pdev, lun);
+ }
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_Verify10
+* Process Verify10 command
+* @param lun: Logical unit number
+* @param params: Command parameters
+* @retval status
+*/
+static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if ((params[1] & 0x02U) == 0x02U)
+ {
+ SCSI_SenseCode(pdev, lun, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND);
+ return -1; /* Error, Verify Mode Not supported*/
+ }
+
+ if (SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr, hmsc->scsi_blk_len) < 0)
+ {
+ return -1; /* error */
+ }
+
+ hmsc->bot_data_length = 0U;
+
+ return 0;
+}
+
+/**
+* @brief SCSI_CheckAddressRange
+* Check address range
+* @param lun: Logical unit number
+* @param blk_offset: first block address
+* @param blk_nbr: number of block to be processed
+* @retval status
+*/
+static int8_t SCSI_CheckAddressRange(USBD_HandleTypeDef *pdev, uint8_t lun,
+ uint32_t blk_offset, uint32_t blk_nbr)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+
+ if ((blk_offset + blk_nbr) > hmsc->scsi_blk_nbr)
+ {
+ SCSI_SenseCode(pdev, lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE);
+ return -1;
+ }
+
+ return 0;
+}
+
+/**
+* @brief SCSI_ProcessRead
+* Handle Read Process
+* @param lun: Logical unit number
+* @retval status
+*/
+static int8_t SCSI_ProcessRead(USBD_HandleTypeDef *pdev, uint8_t lun)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+ uint32_t len = hmsc->scsi_blk_len * hmsc->scsi_blk_size;
+
+ len = MIN(len, MSC_MEDIA_PACKET);
+
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->Read(lun, hmsc->bot_data,
+ hmsc->scsi_blk_addr,
+ (len / hmsc->scsi_blk_size)) < 0)
+ {
+ SCSI_SenseCode(pdev, lun, HARDWARE_ERROR, UNRECOVERED_READ_ERROR);
+ return -1;
+ }
+
+ (void)USBD_LL_Transmit(pdev, MSC_EPIN_ADDR, hmsc->bot_data, len);
+
+ hmsc->scsi_blk_addr += (len / hmsc->scsi_blk_size);
+ hmsc->scsi_blk_len -= (len / hmsc->scsi_blk_size);
+
+ /* case 6 : Hi = Di */
+ hmsc->csw.dDataResidue -= len;
+
+ if (hmsc->scsi_blk_len == 0U)
+ {
+ hmsc->bot_state = USBD_BOT_LAST_DATA_IN;
+ }
+
+ return 0;
+}
+
+/**
+* @brief SCSI_ProcessWrite
+* Handle Write Process
+* @param lun: Logical unit number
+* @retval status
+*/
+static int8_t SCSI_ProcessWrite(USBD_HandleTypeDef *pdev, uint8_t lun)
+{
+ USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef *)pdev->pClassData;
+ uint32_t len = hmsc->scsi_blk_len * hmsc->scsi_blk_size;
+
+ len = MIN(len, MSC_MEDIA_PACKET);
+
+ if (((USBD_StorageTypeDef *)pdev->pUserData)->Write(lun, hmsc->bot_data,
+ hmsc->scsi_blk_addr,
+ (len / hmsc->scsi_blk_size)) < 0)
+ {
+ SCSI_SenseCode(pdev, lun, HARDWARE_ERROR, WRITE_FAULT);
+ return -1;
+ }
+
+ hmsc->scsi_blk_addr += (len / hmsc->scsi_blk_size);
+ hmsc->scsi_blk_len -= (len / hmsc->scsi_blk_size);
+
+ /* case 12 : Ho = Do */
+ hmsc->csw.dDataResidue -= len;
+
+ if (hmsc->scsi_blk_len == 0U)
+ {
+ MSC_BOT_SendCSW(pdev, USBD_CSW_CMD_PASSED);
+ }
+ else
+ {
+ len = MIN((hmsc->scsi_blk_len * hmsc->scsi_blk_size), MSC_MEDIA_PACKET);
+
+ /* Prepare EP to Receive next packet */
+ (void)USBD_LL_PrepareReceive(pdev, MSC_EPOUT_ADDR, hmsc->bot_data, len);
+ }
+
+ return 0;
+}
+
+
+/**
+* @brief SCSI_UpdateBotData
+* fill the requested Data to transmit buffer
+* @param hmsc handler
+* @param params: Data buffer
+* @param length: Data length
+* @retval status
+*/
+static int8_t SCSI_UpdateBotData(USBD_MSC_BOT_HandleTypeDef *hmsc,
+ uint8_t *pBuff, uint16_t length)
+{
+ uint16_t len = length;
+
+ hmsc->bot_data_length = len;
+
+ while (len != 0U)
+ {
+ len--;
+ hmsc->bot_data[len] = pBuff[len];
+ }
+
+ return 0;
+}
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_storage_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_storage_template.c
new file mode 100644
index 0000000000..dc6cc3dead
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC/Src/usbd_msc_storage_template.c
@@ -0,0 +1,177 @@
+/**
+ ******************************************************************************
+ * @file usbd_msc_storage_template.c
+ * @author MCD Application Team
+ * @brief Memory management layer
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* BSPDependencies
+- "stm32xxxxx_{eval}{discovery}{nucleo_144}.c"
+- "stm32xxxxx_{eval}{discovery}_io.c"
+- "stm32xxxxx_{eval}{discovery}{adafruit}_sd.c"
+EndBSPDependencies */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_msc_storage_template.h"
+
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Extern function prototypes ------------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+#define STORAGE_LUN_NBR 1U
+#define STORAGE_BLK_NBR 0x10000U
+#define STORAGE_BLK_SIZ 0x200U
+
+int8_t STORAGE_Init(uint8_t lun);
+
+int8_t STORAGE_GetCapacity(uint8_t lun, uint32_t *block_num,
+ uint16_t *block_size);
+
+int8_t STORAGE_IsReady(uint8_t lun);
+
+int8_t STORAGE_IsWriteProtected(uint8_t lun);
+
+int8_t STORAGE_Read(uint8_t lun, uint8_t *buf, uint32_t blk_addr,
+ uint16_t blk_len);
+
+int8_t STORAGE_Write(uint8_t lun, uint8_t *buf, uint32_t blk_addr,
+ uint16_t blk_len);
+
+int8_t STORAGE_GetMaxLun(void);
+
+/* USB Mass storage Standard Inquiry Data */
+int8_t STORAGE_Inquirydata[] = /* 36 */
+{
+
+ /* LUN 0 */
+ 0x00,
+ 0x80,
+ 0x02,
+ 0x02,
+ (STANDARD_INQUIRY_DATA_LEN - 5),
+ 0x00,
+ 0x00,
+ 0x00,
+ 'S', 'T', 'M', ' ', ' ', ' ', ' ', ' ', /* Manufacturer : 8 bytes */
+ 'P', 'r', 'o', 'd', 'u', 'c', 't', ' ', /* Product : 16 Bytes */
+ ' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ',
+ '0', '.', '0', '1', /* Version : 4 Bytes */
+};
+
+USBD_StorageTypeDef USBD_MSC_Template_fops =
+{
+ STORAGE_Init,
+ STORAGE_GetCapacity,
+ STORAGE_IsReady,
+ STORAGE_IsWriteProtected,
+ STORAGE_Read,
+ STORAGE_Write,
+ STORAGE_GetMaxLun,
+ STORAGE_Inquirydata,
+
+};
+/*******************************************************************************
+* Function Name : Read_Memory
+* Description : Handle the Read operation from the microSD card.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int8_t STORAGE_Init(uint8_t lun)
+{
+ return (0);
+}
+
+/*******************************************************************************
+* Function Name : Read_Memory
+* Description : Handle the Read operation from the STORAGE card.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int8_t STORAGE_GetCapacity(uint8_t lun, uint32_t *block_num, uint16_t *block_size)
+{
+ *block_num = STORAGE_BLK_NBR;
+ *block_size = STORAGE_BLK_SIZ;
+ return (0);
+}
+
+/*******************************************************************************
+* Function Name : Read_Memory
+* Description : Handle the Read operation from the STORAGE card.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int8_t STORAGE_IsReady(uint8_t lun)
+{
+ return (0);
+}
+
+/*******************************************************************************
+* Function Name : Read_Memory
+* Description : Handle the Read operation from the STORAGE card.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int8_t STORAGE_IsWriteProtected(uint8_t lun)
+{
+ return 0;
+}
+
+/*******************************************************************************
+* Function Name : Read_Memory
+* Description : Handle the Read operation from the STORAGE card.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int8_t STORAGE_Read(uint8_t lun, uint8_t *buf,
+ uint32_t blk_addr, uint16_t blk_len)
+{
+ return 0;
+}
+/*******************************************************************************
+* Function Name : Write_Memory
+* Description : Handle the Write operation to the STORAGE card.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int8_t STORAGE_Write(uint8_t lun, uint8_t *buf,
+ uint32_t blk_addr, uint16_t blk_len)
+{
+ return (0);
+}
+/*******************************************************************************
+* Function Name : Write_Memory
+* Description : Handle the Write operation to the STORAGE card.
+* Input : None.
+* Output : None.
+* Return : None.
+*******************************************************************************/
+int8_t STORAGE_GetMaxLun(void)
+{
+ return (STORAGE_LUN_NBR - 1);
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/Template/Inc/usbd_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/Template/Inc/usbd_template.h
new file mode 100644
index 0000000000..8e9163bb21
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/Template/Inc/usbd_template.h
@@ -0,0 +1,101 @@
+/**
+ ******************************************************************************
+ * @file usbd_template_core.h
+ * @author MCD Application Team
+ * @brief Header file for the usbd_template_core.c file.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_TEMPLATE_CORE_H
+#define __USB_TEMPLATE_CORE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_TEMPLATE
+ * @brief This file is the header file for usbd_template_core.c
+ * @{
+ */
+
+
+/** @defgroup USBD_TEMPLATE_Exported_Defines
+ * @{
+ */
+#define TEMPLATE_EPIN_ADDR 0x81U
+#define TEMPLATE_EPIN_SIZE 0x10U
+
+#define USB_TEMPLATE_CONFIG_DESC_SIZ 64U
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+
+extern USBD_ClassTypeDef USBD_TEMPLATE_ClassDriver;
+/**
+ * @}
+ */
+
+/** @defgroup USB_CORE_Exported_Functions
+ * @{
+ */
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_TEMPLATE_CORE_H */
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/Template/Src/usbd_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/Template/Src/usbd_template.c
new file mode 100644
index 0000000000..1c8ea725e5
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/Template/Src/usbd_template.c
@@ -0,0 +1,378 @@
+/**
+ ******************************************************************************
+ * @file usbd_template.c
+ * @author MCD Application Team
+ * @brief This file provides the HID core functions.
+ *
+ * @verbatim
+ *
+ * ===================================================================
+ * TEMPLATE Class Description
+ * ===================================================================
+ *
+ *
+ *
+ *
+ *
+ *
+ * @note In HS mode and when the DMA is used, all variables and data structures
+ * dealing with the DMA during the transaction process should be 32-bit aligned.
+ *
+ *
+ * @endverbatim
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_template.h"
+#include "usbd_ctlreq.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_TEMPLATE
+ * @brief usbd core module
+ * @{
+ */
+
+/** @defgroup USBD_TEMPLATE_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_TEMPLATE_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_TEMPLATE_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+
+
+/** @defgroup USBD_TEMPLATE_Private_FunctionPrototypes
+ * @{
+ */
+
+
+static uint8_t USBD_TEMPLATE_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_TEMPLATE_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+static uint8_t USBD_TEMPLATE_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static uint8_t USBD_TEMPLATE_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_TEMPLATE_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_TEMPLATE_EP0_RxReady(USBD_HandleTypeDef *pdev);
+static uint8_t USBD_TEMPLATE_EP0_TxReady(USBD_HandleTypeDef *pdev);
+static uint8_t USBD_TEMPLATE_SOF(USBD_HandleTypeDef *pdev);
+static uint8_t USBD_TEMPLATE_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum);
+static uint8_t USBD_TEMPLATE_IsoOutIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum);
+
+static uint8_t *USBD_TEMPLATE_GetCfgDesc(uint16_t *length);
+static uint8_t *USBD_TEMPLATE_GetDeviceQualifierDesc(uint16_t *length);
+/**
+ * @}
+ */
+
+/** @defgroup USBD_TEMPLATE_Private_Variables
+ * @{
+ */
+
+USBD_ClassTypeDef USBD_TEMPLATE_ClassDriver =
+{
+ USBD_TEMPLATE_Init,
+ USBD_TEMPLATE_DeInit,
+ USBD_TEMPLATE_Setup,
+ USBD_TEMPLATE_EP0_TxReady,
+ USBD_TEMPLATE_EP0_RxReady,
+ USBD_TEMPLATE_DataIn,
+ USBD_TEMPLATE_DataOut,
+ USBD_TEMPLATE_SOF,
+ USBD_TEMPLATE_IsoINIncomplete,
+ USBD_TEMPLATE_IsoOutIncomplete,
+ USBD_TEMPLATE_GetCfgDesc,
+ USBD_TEMPLATE_GetCfgDesc,
+ USBD_TEMPLATE_GetCfgDesc,
+ USBD_TEMPLATE_GetDeviceQualifierDesc,
+};
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma data_alignment=4
+#endif
+/* USB TEMPLATE device Configuration Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_TEMPLATE_CfgDesc[USB_TEMPLATE_CONFIG_DESC_SIZ] __ALIGN_END =
+{
+ 0x09, /* bLength: Configuation Descriptor size */
+ USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION, /* bDescriptorType: Configuration */
+ USB_TEMPLATE_CONFIG_DESC_SIZ,
+ /* wTotalLength: Bytes returned */
+ 0x00,
+ 0x01, /*bNumInterfaces: 1 interface*/
+ 0x01, /*bConfigurationValue: Configuration value*/
+ 0x02, /*iConfiguration: Index of string descriptor describing the configuration*/
+ 0xC0, /*bmAttributes: bus powered and Supports Remote Wakeup */
+ 0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/
+ /* 09 */
+
+ /********** Descriptor of TEMPLATE interface 0 Alternate setting 0 **************/
+
+};
+
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma data_alignment=4
+#endif
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN static uint8_t USBD_TEMPLATE_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+ USB_LEN_DEV_QUALIFIER_DESC,
+ USB_DESC_TYPE_DEVICE_QUALIFIER,
+ 0x00,
+ 0x02,
+ 0x00,
+ 0x00,
+ 0x00,
+ 0x40,
+ 0x01,
+ 0x00,
+};
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_TEMPLATE_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief USBD_TEMPLATE_Init
+ * Initialize the TEMPLATE interface
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_TEMPLATE_Init
+ * DeInitialize the TEMPLATE layer
+ * @param pdev: device instance
+ * @param cfgidx: Configuration index
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_TEMPLATE_Setup
+ * Handle the TEMPLATE specific requests
+ * @param pdev: instance
+ * @param req: usb requests
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_Setup(USBD_HandleTypeDef *pdev,
+ USBD_SetupReqTypedef *req)
+{
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS :
+ switch (req->bRequest)
+ {
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return (uint8_t)ret;
+}
+
+
+/**
+ * @brief USBD_TEMPLATE_GetCfgDesc
+ * return configuration descriptor
+ * @param length : pointer data length
+ * @retval pointer to descriptor buffer
+ */
+static uint8_t *USBD_TEMPLATE_GetCfgDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_TEMPLATE_CfgDesc);
+ return USBD_TEMPLATE_CfgDesc;
+}
+
+/**
+* @brief DeviceQualifierDescriptor
+* return Device Qualifier descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+uint8_t *USBD_TEMPLATE_DeviceQualifierDescriptor(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_TEMPLATE_DeviceQualifierDesc);
+ return USBD_TEMPLATE_DeviceQualifierDesc;
+}
+
+
+/**
+ * @brief USBD_TEMPLATE_DataIn
+ * handle data IN Stage
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+ * @brief USBD_TEMPLATE_EP0_RxReady
+ * handle EP0 Rx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_EP0_RxReady(USBD_HandleTypeDef *pdev)
+{
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_TEMPLATE_EP0_TxReady
+ * handle EP0 TRx Ready event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_EP0_TxReady(USBD_HandleTypeDef *pdev)
+{
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_TEMPLATE_SOF
+ * handle SOF event
+ * @param pdev: device instance
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_SOF(USBD_HandleTypeDef *pdev)
+{
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_TEMPLATE_IsoINIncomplete
+ * handle data ISO IN Incomplete event
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_TEMPLATE_IsoOutIncomplete
+ * handle data ISO OUT Incomplete event
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_IsoOutIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+
+ return (uint8_t)USBD_OK;
+}
+/**
+ * @brief USBD_TEMPLATE_DataOut
+ * handle data OUT Stage
+ * @param pdev: device instance
+ * @param epnum: endpoint index
+ * @retval status
+ */
+static uint8_t USBD_TEMPLATE_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
+{
+
+ return (uint8_t)USBD_OK;
+}
+
+/**
+* @brief DeviceQualifierDescriptor
+* return Device Qualifier descriptor
+* @param length : pointer data length
+* @retval pointer to descriptor buffer
+*/
+uint8_t *USBD_TEMPLATE_GetDeviceQualifierDesc(uint16_t *length)
+{
+ *length = (uint16_t)sizeof(USBD_TEMPLATE_DeviceQualifierDesc);
+
+ return USBD_TEMPLATE_DeviceQualifierDesc;
+}
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_conf_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_conf_template.h
new file mode 100644
index 0000000000..85e18ab781
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_conf_template.h
@@ -0,0 +1,170 @@
+/**
+ ******************************************************************************
+ * @file usbd_conf_template.h
+ * @author MCD Application Team
+ * @brief Header file for the usbd_conf_template.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CONF_TEMPLATE_H
+#define __USBD_CONF_TEMPLATE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32fxxx.h" /* replace 'stm32xxx' with your HAL driver header filename, ex: stm32f4xx.h */
+#include
+#include
+#include
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_CONF
+ * @brief USB device low level driver configuration file
+ * @{
+ */
+
+/** @defgroup USBD_CONF_Exported_Defines
+ * @{
+ */
+
+#define USBD_MAX_NUM_INTERFACES 1U
+#define USBD_MAX_NUM_CONFIGURATION 1U
+#define USBD_MAX_STR_DESC_SIZ 0x100U
+#define USBD_SELF_POWERED 1U
+#define USBD_DEBUG_LEVEL 2U
+
+/* ECM, RNDIS, DFU Class Config */
+#define USBD_SUPPORT_USER_STRING_DESC 1U
+
+/* BillBoard Class Config */
+#define USBD_CLASS_USER_STRING_DESC 1U
+#define USBD_CLASS_BOS_ENABLED 1U
+#define USB_BB_MAX_NUM_ALT_MODE 0x2U
+
+/* MSC Class Config */
+#define MSC_MEDIA_PACKET 8192U
+
+/* CDC Class Config */
+#define USBD_CDC_INTERVAL 2000U
+
+/* DFU Class Config */
+#define USBD_DFU_MAX_ITF_NUM 1U
+#define USBD_DFU_XFERS_IZE 1024U
+
+/* AUDIO Class Config */
+#define USBD_AUDIO_FREQ 22100U
+
+/** @defgroup USBD_Exported_Macros
+ * @{
+ */
+
+/* Memory management macros */
+#define USBD_malloc malloc
+#define USBD_free free
+#define USBD_memset memset
+#define USBD_memcpy memcpy
+#define USBD_Delay HAL_Delay
+
+/* DEBUG macros */
+#if (USBD_DEBUG_LEVEL > 0U)
+#define USBD_UsrLog(...) do { \
+ printf(__VA_ARGS__); \
+ printf("\n"); \
+} while (0)
+#else
+#define USBD_UsrLog(...) do {} while (0)
+#endif
+
+#if (USBD_DEBUG_LEVEL > 1U)
+
+#define USBD_ErrLog(...) do { \
+ printf("ERROR: ") ; \
+ printf(__VA_ARGS__); \
+ printf("\n"); \
+} while (0)
+#else
+#define USBD_ErrLog(...) do {} while (0)
+#endif
+
+#if (USBD_DEBUG_LEVEL > 2U)
+#define USBD_DbgLog(...) do { \
+ printf("DEBUG : ") ; \
+ printf(__VA_ARGS__); \
+ printf("\n"); \
+} while (0)
+#else
+#define USBD_DbgLog(...) do {} while (0)
+#endif
+
+/**
+ * @}
+ */
+
+
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CONF_Exported_Types
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CONF_Exported_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_Variables
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CONF_Exported_FunctionsPrototype
+ * @{
+ */
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_CONF_TEMPLATE_H */
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_core.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_core.h
new file mode 100644
index 0000000000..c7d2ba39e5
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_core.h
@@ -0,0 +1,158 @@
+/**
+ ******************************************************************************
+ * @file usbd_core.h
+ * @author MCD Application Team
+ * @brief Header file for usbd_core.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CORE_H
+#define __USBD_CORE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_conf.h"
+#include "usbd_def.h"
+#include "usbd_ioreq.h"
+#include "usbd_ctlreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_CORE
+ * @brief This file is the Header file for usbd_core.c file
+ * @{
+ */
+
+
+/** @defgroup USBD_CORE_Exported_Defines
+ * @{
+ */
+#ifndef USBD_DEBUG_LEVEL
+#define USBD_DEBUG_LEVEL 0U
+#endif /* USBD_DEBUG_LEVEL */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+ * @{
+ */
+
+
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_Variables
+ * @{
+ */
+#define USBD_SOF USBD_LL_SOF
+/**
+ * @}
+ */
+
+/** @defgroup USBD_CORE_Exported_FunctionsPrototype
+ * @{
+ */
+USBD_StatusTypeDef USBD_Init(USBD_HandleTypeDef *pdev, USBD_DescriptorsTypeDef *pdesc, uint8_t id);
+USBD_StatusTypeDef USBD_DeInit(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_Start(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_Stop(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_RegisterClass(USBD_HandleTypeDef *pdev, USBD_ClassTypeDef *pclass);
+
+USBD_StatusTypeDef USBD_RunTestMode(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+USBD_StatusTypeDef USBD_ClrClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+
+USBD_StatusTypeDef USBD_LL_SetupStage(USBD_HandleTypeDef *pdev, uint8_t *psetup);
+USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev, uint8_t epnum, uint8_t *pdata);
+USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev, uint8_t epnum, uint8_t *pdata);
+
+USBD_StatusTypeDef USBD_LL_Reset(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_LL_SetSpeed(USBD_HandleTypeDef *pdev, USBD_SpeedTypeDef speed);
+USBD_StatusTypeDef USBD_LL_Suspend(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_LL_Resume(USBD_HandleTypeDef *pdev);
+
+USBD_StatusTypeDef USBD_LL_SOF(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum);
+USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum);
+
+USBD_StatusTypeDef USBD_LL_DevConnected(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_LL_DevDisconnected(USBD_HandleTypeDef *pdev);
+
+/* USBD Low Level Driver */
+USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_LL_DeInit(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_LL_Start(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_LL_Stop(USBD_HandleTypeDef *pdev);
+
+USBD_StatusTypeDef USBD_LL_OpenEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr,
+ uint8_t ep_type, uint16_t ep_mps);
+
+USBD_StatusTypeDef USBD_LL_CloseEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr);
+USBD_StatusTypeDef USBD_LL_FlushEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr);
+USBD_StatusTypeDef USBD_LL_StallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr);
+USBD_StatusTypeDef USBD_LL_ClearStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr);
+USBD_StatusTypeDef USBD_LL_SetUSBAddress(USBD_HandleTypeDef *pdev, uint8_t dev_addr);
+
+USBD_StatusTypeDef USBD_LL_Transmit(USBD_HandleTypeDef *pdev, uint8_t ep_addr,
+ uint8_t *pbuf, uint32_t size);
+
+USBD_StatusTypeDef USBD_LL_PrepareReceive(USBD_HandleTypeDef *pdev, uint8_t ep_addr,
+ uint8_t *pbuf, uint32_t size);
+
+uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr);
+uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef *pdev, uint8_t ep_addr);
+
+void USBD_LL_Delay(uint32_t Delay);
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_CORE_H */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
+
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ctlreq.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ctlreq.h
new file mode 100644
index 0000000000..f973a8b1b2
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ctlreq.h
@@ -0,0 +1,103 @@
+/**
+ ******************************************************************************
+ * @file usbd_req.h
+ * @author MCD Application Team
+ * @brief Header file for the usbd_req.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_REQUEST_H
+#define __USB_REQUEST_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_def.h"
+
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_REQ
+ * @brief header file for the usbd_req.c file
+ * @{
+ */
+
+/** @defgroup USBD_REQ_Exported_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_REQ_Exported_Types
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_REQ_Exported_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_REQ_Exported_Variables
+ * @{
+ */
+/**
+ * @}
+ */
+
+/** @defgroup USBD_REQ_Exported_FunctionsPrototype
+ * @{
+ */
+
+USBD_StatusTypeDef USBD_StdDevReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+USBD_StatusTypeDef USBD_StdItfReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+USBD_StatusTypeDef USBD_StdEPReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+
+void USBD_CtlError(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+void USBD_ParseSetupRequest(USBD_SetupReqTypedef *req, uint8_t *pdata);
+void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len);
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USB_REQUEST_H */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_def.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_def.h
new file mode 100644
index 0000000000..0463e2f31f
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_def.h
@@ -0,0 +1,393 @@
+/**
+ ******************************************************************************
+ * @file usbd_def.h
+ * @author MCD Application Team
+ * @brief General defines for the usb device library
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_DEF_H
+#define __USBD_DEF_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_conf.h"
+
+/** @addtogroup STM32_USBD_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USB_DEF
+ * @brief general defines for the usb device library file
+ * @{
+ */
+
+/** @defgroup USB_DEF_Exported_Defines
+ * @{
+ */
+
+#ifndef NULL
+#define NULL 0U
+#endif /* NULL */
+
+#ifndef USBD_MAX_NUM_INTERFACES
+#define USBD_MAX_NUM_INTERFACES 1U
+#endif /* USBD_MAX_NUM_CONFIGURATION */
+
+#ifndef USBD_MAX_NUM_CONFIGURATION
+#define USBD_MAX_NUM_CONFIGURATION 1U
+#endif /* USBD_MAX_NUM_CONFIGURATION */
+
+#ifndef USBD_LPM_ENABLED
+#define USBD_LPM_ENABLED 0U
+#endif /* USBD_LPM_ENABLED */
+
+#ifndef USBD_SELF_POWERED
+#define USBD_SELF_POWERED 1U
+#endif /*USBD_SELF_POWERED */
+
+#ifndef USBD_SUPPORT_USER_STRING_DESC
+#define USBD_SUPPORT_USER_STRING_DESC 0U
+#endif /* USBD_SUPPORT_USER_STRING_DESC */
+
+#ifndef USBD_CLASS_USER_STRING_DESC
+#define USBD_CLASS_USER_STRING_DESC 0U
+#endif /* USBD_CLASS_USER_STRING_DESC */
+
+#define USB_LEN_DEV_QUALIFIER_DESC 0x0AU
+#define USB_LEN_DEV_DESC 0x12U
+#define USB_LEN_CFG_DESC 0x09U
+#define USB_LEN_IF_DESC 0x09U
+#define USB_LEN_EP_DESC 0x07U
+#define USB_LEN_OTG_DESC 0x03U
+#define USB_LEN_LANGID_STR_DESC 0x04U
+#define USB_LEN_OTHER_SPEED_DESC_SIZ 0x09U
+
+#define USBD_IDX_LANGID_STR 0x00U
+#define USBD_IDX_MFC_STR 0x01U
+#define USBD_IDX_PRODUCT_STR 0x02U
+#define USBD_IDX_SERIAL_STR 0x03U
+#define USBD_IDX_CONFIG_STR 0x04U
+#define USBD_IDX_INTERFACE_STR 0x05U
+
+#define USB_REQ_TYPE_STANDARD 0x00U
+#define USB_REQ_TYPE_CLASS 0x20U
+#define USB_REQ_TYPE_VENDOR 0x40U
+#define USB_REQ_TYPE_MASK 0x60U
+
+#define USB_REQ_RECIPIENT_DEVICE 0x00U
+#define USB_REQ_RECIPIENT_INTERFACE 0x01U
+#define USB_REQ_RECIPIENT_ENDPOINT 0x02U
+#define USB_REQ_RECIPIENT_MASK 0x03U
+
+#define USB_REQ_GET_STATUS 0x00U
+#define USB_REQ_CLEAR_FEATURE 0x01U
+#define USB_REQ_SET_FEATURE 0x03U
+#define USB_REQ_SET_ADDRESS 0x05U
+#define USB_REQ_GET_DESCRIPTOR 0x06U
+#define USB_REQ_SET_DESCRIPTOR 0x07U
+#define USB_REQ_GET_CONFIGURATION 0x08U
+#define USB_REQ_SET_CONFIGURATION 0x09U
+#define USB_REQ_GET_INTERFACE 0x0AU
+#define USB_REQ_SET_INTERFACE 0x0BU
+#define USB_REQ_SYNCH_FRAME 0x0CU
+
+#define USB_DESC_TYPE_DEVICE 0x01U
+#define USB_DESC_TYPE_CONFIGURATION 0x02U
+#define USB_DESC_TYPE_STRING 0x03U
+#define USB_DESC_TYPE_INTERFACE 0x04U
+#define USB_DESC_TYPE_ENDPOINT 0x05U
+#define USB_DESC_TYPE_DEVICE_QUALIFIER 0x06U
+#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 0x07U
+#define USB_DESC_TYPE_BOS 0x0FU
+
+#define USB_CONFIG_REMOTE_WAKEUP 0x02U
+#define USB_CONFIG_SELF_POWERED 0x01U
+
+#define USB_FEATURE_EP_HALT 0x00U
+#define USB_FEATURE_REMOTE_WAKEUP 0x01U
+#define USB_FEATURE_TEST_MODE 0x02U
+
+#define USB_DEVICE_CAPABITY_TYPE 0x10U
+
+#define USB_HS_MAX_PACKET_SIZE 512U
+#define USB_FS_MAX_PACKET_SIZE 64U
+#define USB_MAX_EP0_SIZE 64U
+
+/* Device Status */
+#define USBD_STATE_DEFAULT 0x01U
+#define USBD_STATE_ADDRESSED 0x02U
+#define USBD_STATE_CONFIGURED 0x03U
+#define USBD_STATE_SUSPENDED 0x04U
+
+
+/* EP0 State */
+#define USBD_EP0_IDLE 0x00U
+#define USBD_EP0_SETUP 0x01U
+#define USBD_EP0_DATA_IN 0x02U
+#define USBD_EP0_DATA_OUT 0x03U
+#define USBD_EP0_STATUS_IN 0x04U
+#define USBD_EP0_STATUS_OUT 0x05U
+#define USBD_EP0_STALL 0x06U
+
+#define USBD_EP_TYPE_CTRL 0x00U
+#define USBD_EP_TYPE_ISOC 0x01U
+#define USBD_EP_TYPE_BULK 0x02U
+#define USBD_EP_TYPE_INTR 0x03U
+
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_DEF_Exported_TypesDefinitions
+ * @{
+ */
+
+typedef struct usb_setup_req
+{
+ uint8_t bmRequest;
+ uint8_t bRequest;
+ uint16_t wValue;
+ uint16_t wIndex;
+ uint16_t wLength;
+} USBD_SetupReqTypedef;
+
+typedef struct
+{
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint8_t wDescriptorLengthLow;
+ uint8_t wDescriptorLengthHigh;
+ uint8_t bNumInterfaces;
+ uint8_t bConfigurationValue;
+ uint8_t iConfiguration;
+ uint8_t bmAttributes;
+ uint8_t bMaxPower;
+} USBD_ConfigDescTypedef;
+
+typedef struct
+{
+ uint8_t bLength;
+ uint8_t bDescriptorType;
+ uint16_t wTotalLength;
+ uint8_t bNumDeviceCaps;
+} USBD_BosDescTypedef;
+
+
+struct _USBD_HandleTypeDef;
+
+typedef struct _Device_cb
+{
+ uint8_t (*Init)(struct _USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+ uint8_t (*DeInit)(struct _USBD_HandleTypeDef *pdev, uint8_t cfgidx);
+ /* Control Endpoints*/
+ uint8_t (*Setup)(struct _USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+ uint8_t (*EP0_TxSent)(struct _USBD_HandleTypeDef *pdev);
+ uint8_t (*EP0_RxReady)(struct _USBD_HandleTypeDef *pdev);
+ /* Class Specific Endpoints*/
+ uint8_t (*DataIn)(struct _USBD_HandleTypeDef *pdev, uint8_t epnum);
+ uint8_t (*DataOut)(struct _USBD_HandleTypeDef *pdev, uint8_t epnum);
+ uint8_t (*SOF)(struct _USBD_HandleTypeDef *pdev);
+ uint8_t (*IsoINIncomplete)(struct _USBD_HandleTypeDef *pdev, uint8_t epnum);
+ uint8_t (*IsoOUTIncomplete)(struct _USBD_HandleTypeDef *pdev, uint8_t epnum);
+
+ uint8_t *(*GetHSConfigDescriptor)(uint16_t *length);
+ uint8_t *(*GetFSConfigDescriptor)(uint16_t *length);
+ uint8_t *(*GetOtherSpeedConfigDescriptor)(uint16_t *length);
+ uint8_t *(*GetDeviceQualifierDescriptor)(uint16_t *length);
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+ uint8_t *(*GetUsrStrDescriptor)(struct _USBD_HandleTypeDef *pdev, uint8_t index, uint16_t *length);
+#endif
+
+} USBD_ClassTypeDef;
+
+/* Following USB Device Speed */
+typedef enum
+{
+ USBD_SPEED_HIGH = 0U,
+ USBD_SPEED_FULL = 1U,
+ USBD_SPEED_LOW = 2U,
+} USBD_SpeedTypeDef;
+
+/* Following USB Device status */
+typedef enum
+{
+ USBD_OK = 0U,
+ USBD_BUSY,
+ USBD_EMEM,
+ USBD_FAIL,
+} USBD_StatusTypeDef;
+
+/* USB Device descriptors structure */
+typedef struct
+{
+ uint8_t *(*GetDeviceDescriptor)(USBD_SpeedTypeDef speed, uint16_t *length);
+ uint8_t *(*GetLangIDStrDescriptor)(USBD_SpeedTypeDef speed, uint16_t *length);
+ uint8_t *(*GetManufacturerStrDescriptor)(USBD_SpeedTypeDef speed, uint16_t *length);
+ uint8_t *(*GetProductStrDescriptor)(USBD_SpeedTypeDef speed, uint16_t *length);
+ uint8_t *(*GetSerialStrDescriptor)(USBD_SpeedTypeDef speed, uint16_t *length);
+ uint8_t *(*GetConfigurationStrDescriptor)(USBD_SpeedTypeDef speed, uint16_t *length);
+ uint8_t *(*GetInterfaceStrDescriptor)(USBD_SpeedTypeDef speed, uint16_t *length);
+#if (USBD_CLASS_USER_STRING_DESC == 1)
+ uint8_t *(*GetUserStrDescriptor)(USBD_SpeedTypeDef speed, uint8_t idx, uint16_t *length);
+#endif
+#if ((USBD_LPM_ENABLED == 1U) || (USBD_CLASS_BOS_ENABLED == 1))
+ uint8_t *(*GetBOSDescriptor)(USBD_SpeedTypeDef speed, uint16_t *length);
+#endif
+} USBD_DescriptorsTypeDef;
+
+/* USB Device handle structure */
+typedef struct
+{
+ uint32_t status;
+ uint32_t total_length;
+ uint32_t rem_length;
+ uint32_t maxpacket;
+ uint16_t is_used;
+ uint16_t bInterval;
+} USBD_EndpointTypeDef;
+
+/* USB Device handle structure */
+typedef struct _USBD_HandleTypeDef
+{
+ uint8_t id;
+ uint32_t dev_config;
+ uint32_t dev_default_config;
+ uint32_t dev_config_status;
+ USBD_SpeedTypeDef dev_speed;
+ USBD_EndpointTypeDef ep_in[16];
+ USBD_EndpointTypeDef ep_out[16];
+ uint32_t ep0_state;
+ uint32_t ep0_data_len;
+ uint8_t dev_state;
+ uint8_t dev_old_state;
+ uint8_t dev_address;
+ uint8_t dev_connection_status;
+ uint8_t dev_test_mode;
+ uint32_t dev_remote_wakeup;
+ uint8_t ConfIdx;
+
+ USBD_SetupReqTypedef request;
+ USBD_DescriptorsTypeDef *pDesc;
+ USBD_ClassTypeDef *pClass;
+ void *pClassData;
+ void *pUserData;
+ void *pData;
+ void *pBosDesc;
+ void *pConfDesc;
+} USBD_HandleTypeDef;
+
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_DEF_Exported_Macros
+ * @{
+ */
+__STATIC_INLINE uint16_t SWAPBYTE(uint8_t *addr)
+{
+ uint16_t _SwapVal, _Byte1, _Byte2;
+ uint8_t *_pbuff = addr;
+
+ _Byte1 = *(uint8_t *)_pbuff;
+ _pbuff++;
+ _Byte2 = *(uint8_t *)_pbuff;
+
+ _SwapVal = (_Byte2 << 8) | _Byte1;
+
+ return _SwapVal;
+}
+
+#define LOBYTE(x) ((uint8_t)((x) & 0x00FFU))
+#define HIBYTE(x) ((uint8_t)(((x) & 0xFF00U) >> 8U))
+#define MIN(a, b) (((a) < (b)) ? (a) : (b))
+#define MAX(a, b) (((a) > (b)) ? (a) : (b))
+
+
+#if defined ( __GNUC__ )
+#ifndef __weak
+#define __weak __attribute__((weak))
+#endif /* __weak */
+#ifndef __packed
+#define __packed __attribute__((__packed__))
+#endif /* __packed */
+#endif /* __GNUC__ */
+
+
+/* In HS mode and when the DMA is used, all variables and data structures dealing
+ with the DMA during the transaction process should be 4-bytes aligned */
+
+#if defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */
+#ifndef __ALIGN_END
+#define __ALIGN_END __attribute__ ((aligned (4U)))
+#endif /* __ALIGN_END */
+#ifndef __ALIGN_BEGIN
+#define __ALIGN_BEGIN
+#endif /* __ALIGN_BEGIN */
+#else
+#ifndef __ALIGN_END
+#define __ALIGN_END
+#endif /* __ALIGN_END */
+#ifndef __ALIGN_BEGIN
+#if defined (__CC_ARM) /* ARM Compiler */
+#define __ALIGN_BEGIN __align(4U)
+#elif defined (__ICCARM__) /* IAR Compiler */
+#define __ALIGN_BEGIN
+#endif /* __CC_ARM */
+#endif /* __ALIGN_BEGIN */
+#endif /* __GNUC__ */
+
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DEF_Exported_Variables
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_DEF_Exported_FunctionsPrototype
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_DEF_H */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_desc_template.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_desc_template.h
new file mode 100644
index 0000000000..8fbbfaa634
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_desc_template.h
@@ -0,0 +1,63 @@
+/**
+ ******************************************************************************
+ * @file usbd_desc_template.h
+ * @author MCD Application Team
+ * @brief Header for usbd_desc_template.c module
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_DESC_TEMPLATE_H
+#define __USBD_DESC_TEMPLATE_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_def.h"
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+#define DEVICE_ID1 (UID_BASE)
+#define DEVICE_ID2 (UID_BASE + 0x4U)
+#define DEVICE_ID3 (UID_BASE + 0x8U)
+
+/*
+ * USB Billboard Class USER string desc Defines Template
+ * index should start form 0x10 to avoid using the reserved device string desc indexes
+ */
+#if (USBD_CLASS_USER_STRING_DESC == 1)
+#define USBD_BB_IF_STRING_INDEX 0x10U
+#define USBD_BB_URL_STRING_INDEX 0x11U
+#define USBD_BB_ALTMODE0_STRING_INDEX 0x12U
+#define USBD_BB_ALTMODE1_STRING_INDEX 0x13U
+/* Add Specific USER string Desc */
+#define USBD_BB_IF_STR_DESC (uint8_t *)"STM32 BillBoard Interface"
+#define USBD_BB_URL_STR_DESC (uint8_t *)"www.st.com"
+#define USBD_BB_ALTMODE0_STR_DESC (uint8_t *)"STM32 Alternate0 Mode"
+#define USBD_BB_ALTMODE1_STR_DESC (uint8_t *)"STM32 Alternate1 Mode"
+#endif
+
+#define USB_SIZ_STRING_SERIAL 0x1AU
+
+#if (USBD_LPM_ENABLED == 1)
+#define USB_SIZ_BOS_DESC 0x0CU
+#elif (USBD_CLASS_BOS_ENABLED == 1)
+#define USB_SIZ_BOS_DESC 0x5DU
+#endif
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+extern USBD_DescriptorsTypeDef XXX_Desc; /* Replace 'XXX_Desc' with your active USB device class, ex: HID_Desc */
+
+#endif /* __USBD_DESC_TEMPLATE_H*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ioreq.h b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ioreq.h
new file mode 100644
index 0000000000..b7159d53b6
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ioreq.h
@@ -0,0 +1,114 @@
+/**
+ ******************************************************************************
+ * @file usbd_ioreq.h
+ * @author MCD Application Team
+ * @brief Header file for the usbd_ioreq.c file
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_IOREQ_H
+#define __USBD_IOREQ_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_def.h"
+#include "usbd_core.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+/** @defgroup USBD_IOREQ
+ * @brief header file for the usbd_ioreq.c file
+ * @{
+ */
+
+/** @defgroup USBD_IOREQ_Exported_Defines
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_IOREQ_Exported_Types
+ * @{
+ */
+
+
+/**
+ * @}
+ */
+
+
+
+/** @defgroup USBD_IOREQ_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_IOREQ_Exported_Variables
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @defgroup USBD_IOREQ_Exported_FunctionsPrototype
+ * @{
+ */
+
+USBD_StatusTypeDef USBD_CtlSendData(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuf, uint32_t len);
+
+USBD_StatusTypeDef USBD_CtlContinueSendData(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuf, uint32_t len);
+
+USBD_StatusTypeDef USBD_CtlPrepareRx(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuf, uint32_t len);
+
+USBD_StatusTypeDef USBD_CtlContinueRx(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuf, uint32_t len);
+
+USBD_StatusTypeDef USBD_CtlSendStatus(USBD_HandleTypeDef *pdev);
+USBD_StatusTypeDef USBD_CtlReceiveStatus(USBD_HandleTypeDef *pdev);
+
+uint32_t USBD_GetRxCount(USBD_HandleTypeDef *pdev, uint8_t ep_addr);
+
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __USBD_IOREQ_H */
+
+/**
+ * @}
+ */
+
+/**
+* @}
+*/
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_conf_template.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_conf_template.c
new file mode 100644
index 0000000000..67b70aa0e3
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_conf_template.c
@@ -0,0 +1,246 @@
+/**
+ ******************************************************************************
+ * @file usbd_conf_template.c
+ * @author MCD Application Team
+ * @brief USB Device configuration and interface file
+ * This template should be copied to the user folder,
+ * renamed and customized following user needs.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_core.h"
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+/**
+ * @brief Initializes the Low Level portion of the Device driver.
+ * @param pdev: Device handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev)
+{
+ UNUSED(pdev);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief De-Initializes the Low Level portion of the Device driver.
+ * @param pdev: Device handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_DeInit(USBD_HandleTypeDef *pdev)
+{
+ UNUSED(pdev);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Starts the Low Level portion of the Device driver.
+ * @param pdev: Device handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_Start(USBD_HandleTypeDef *pdev)
+{
+ UNUSED(pdev);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Stops the Low Level portion of the Device driver.
+ * @param pdev: Device handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_Stop(USBD_HandleTypeDef *pdev)
+{
+ UNUSED(pdev);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Opens an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @param ep_type: Endpoint Type
+ * @param ep_mps: Endpoint Max Packet Size
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_OpenEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr,
+ uint8_t ep_type, uint16_t ep_mps)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+ UNUSED(ep_type);
+ UNUSED(ep_mps);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Closes an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_CloseEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Flushes an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_FlushEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Sets a Stall condition on an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_StallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Clears a Stall condition on an endpoint of the Low Level Driver.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_ClearStallEP(USBD_HandleTypeDef *pdev,
+ uint8_t ep_addr)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Returns Stall condition.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval Stall (1: Yes, 0: No)
+ */
+uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+
+ return 0U;
+}
+
+/**
+ * @brief Assigns a USB address to the device.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_SetUSBAddress(USBD_HandleTypeDef *pdev,
+ uint8_t dev_addr)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Transmits data over an endpoint.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @param pbuf: Pointer to data to be sent
+ * @param size: Data size
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_Transmit(USBD_HandleTypeDef *pdev, uint8_t ep_addr,
+ uint8_t *pbuf, uint32_t size)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+ UNUSED(pbuf);
+ UNUSED(size);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Prepares an endpoint for reception.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @param pbuf: Pointer to data to be received
+ * @param size: Data size
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_LL_PrepareReceive(USBD_HandleTypeDef *pdev,
+ uint8_t ep_addr, uint8_t *pbuf,
+ uint32_t size)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+ UNUSED(pbuf);
+ UNUSED(size);
+
+ return USBD_OK;
+}
+
+/**
+ * @brief Returns the last transferred packet size.
+ * @param pdev: Device handle
+ * @param ep_addr: Endpoint Number
+ * @retval Recived Data Size
+ */
+uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ UNUSED(pdev);
+ UNUSED(ep_addr);
+
+ return 0U;
+}
+
+/**
+ * @brief Delays routine for the USB Device Library.
+ * @param Delay: Delay in ms
+ * @retval None
+ */
+void USBD_LL_Delay(uint32_t Delay)
+{
+ UNUSED(Delay);
+}
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c
new file mode 100644
index 0000000000..3faed3520e
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c
@@ -0,0 +1,669 @@
+/**
+ ******************************************************************************
+ * @file usbd_core.c
+ * @author MCD Application Team
+ * @brief This file provides all the USBD core functions.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_core.h"
+
+/** @addtogroup STM32_USBD_DEVICE_LIBRARY
+* @{
+*/
+
+
+/** @defgroup USBD_CORE
+* @brief usbd core module
+* @{
+*/
+
+/** @defgroup USBD_CORE_Private_TypesDefinitions
+* @{
+*/
+
+/**
+* @}
+*/
+
+
+/** @defgroup USBD_CORE_Private_Defines
+* @{
+*/
+
+/**
+* @}
+*/
+
+
+/** @defgroup USBD_CORE_Private_Macros
+* @{
+*/
+
+/**
+* @}
+*/
+
+
+/** @defgroup USBD_CORE_Private_FunctionPrototypes
+* @{
+*/
+
+/**
+* @}
+*/
+
+/** @defgroup USBD_CORE_Private_Variables
+* @{
+*/
+
+/**
+* @}
+*/
+
+
+/** @defgroup USBD_CORE_Private_Functions
+* @{
+*/
+
+/**
+* @brief USBD_Init
+* Initializes the device stack and load the class driver
+* @param pdev: device instance
+* @param pdesc: Descriptor structure address
+* @param id: Low level core index
+* @retval None
+*/
+USBD_StatusTypeDef USBD_Init(USBD_HandleTypeDef *pdev,
+ USBD_DescriptorsTypeDef *pdesc, uint8_t id)
+{
+ USBD_StatusTypeDef ret;
+
+ /* Check whether the USB Host handle is valid */
+ if (pdev == NULL)
+ {
+#if (USBD_DEBUG_LEVEL > 1U)
+ USBD_ErrLog("Invalid Device handle");
+#endif
+ return USBD_FAIL;
+ }
+
+ /* Unlink previous class */
+ if (pdev->pClass != NULL)
+ {
+ pdev->pClass = NULL;
+ }
+
+ if (pdev->pConfDesc != NULL)
+ {
+ pdev->pConfDesc = NULL;
+ }
+
+ /* Assign USBD Descriptors */
+ if (pdesc != NULL)
+ {
+ pdev->pDesc = pdesc;
+ }
+
+ /* Set Device initial State */
+ pdev->dev_state = USBD_STATE_DEFAULT;
+ pdev->id = id;
+
+ /* Initialize low level driver */
+ ret = USBD_LL_Init(pdev);
+
+ return ret;
+}
+
+/**
+* @brief USBD_DeInit
+* Re-Initialize th device library
+* @param pdev: device instance
+* @retval status: status
+*/
+USBD_StatusTypeDef USBD_DeInit(USBD_HandleTypeDef *pdev)
+{
+ USBD_StatusTypeDef ret;
+
+ /* Set Default State */
+ pdev->dev_state = USBD_STATE_DEFAULT;
+
+ /* Free Class Resources */
+ if (pdev->pClass != NULL)
+ {
+ pdev->pClass->DeInit(pdev, (uint8_t)pdev->dev_config);
+ }
+
+ if (pdev->pConfDesc != NULL)
+ {
+ pdev->pConfDesc = NULL;
+ }
+
+ /* Stop the low level driver */
+ ret = USBD_LL_Stop(pdev);
+
+ if (ret != USBD_OK)
+ {
+ return ret;
+ }
+
+ /* Initialize low level driver */
+ ret = USBD_LL_DeInit(pdev);
+
+ return ret;
+}
+
+/**
+ * @brief USBD_RegisterClass
+ * Link class driver to Device Core.
+ * @param pDevice : Device Handle
+ * @param pclass: Class handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_RegisterClass(USBD_HandleTypeDef *pdev, USBD_ClassTypeDef *pclass)
+{
+ uint16_t len = 0U;
+
+ if (pclass == NULL)
+ {
+#if (USBD_DEBUG_LEVEL > 1U)
+ USBD_ErrLog("Invalid Class handle");
+#endif
+ return USBD_FAIL;
+ }
+
+ /* link the class to the USB Device handle */
+ pdev->pClass = pclass;
+
+ /* Get Device Configuration Descriptor */
+#ifdef USE_USB_FS
+ pdev->pConfDesc = (void *)pdev->pClass->GetFSConfigDescriptor(&len);
+#else /* USE_USB_HS */
+ pdev->pConfDesc = (void *)pdev->pClass->GetHSConfigDescriptor(&len);
+#endif /* USE_USB_FS */
+
+
+ return USBD_OK;
+}
+
+/**
+ * @brief USBD_Start
+ * Start the USB Device Core.
+ * @param pdev: Device Handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_Start(USBD_HandleTypeDef *pdev)
+{
+ /* Start the low level driver */
+ return USBD_LL_Start(pdev);
+}
+
+/**
+ * @brief USBD_Stop
+ * Stop the USB Device Core.
+ * @param pdev: Device Handle
+ * @retval USBD Status
+ */
+USBD_StatusTypeDef USBD_Stop(USBD_HandleTypeDef *pdev)
+{
+ USBD_StatusTypeDef ret;
+
+ /* Free Class Resources */
+ if (pdev->pClass != NULL)
+ {
+ pdev->pClass->DeInit(pdev, (uint8_t)pdev->dev_config);
+ }
+
+ if (pdev->pConfDesc != NULL)
+ {
+ pdev->pConfDesc = NULL;
+ }
+
+ /* Stop the low level driver */
+ ret = USBD_LL_Stop(pdev);
+
+ return ret;
+}
+
+/**
+* @brief USBD_RunTestMode
+* Launch test mode process
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_RunTestMode(USBD_HandleTypeDef *pdev)
+{
+ /* Prevent unused argument compilation warning */
+ UNUSED(pdev);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_SetClassConfig
+* Configure device and start the interface
+* @param pdev: device instance
+* @param cfgidx: configuration index
+* @retval status
+*/
+
+USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ USBD_StatusTypeDef ret = USBD_FAIL;
+
+ if (pdev->pClass != NULL)
+ {
+ /* Set configuration and Start the Class */
+ ret = (USBD_StatusTypeDef)pdev->pClass->Init(pdev, cfgidx);
+ }
+
+ return ret;
+}
+
+/**
+* @brief USBD_ClrClassConfig
+* Clear current configuration
+* @param pdev: device instance
+* @param cfgidx: configuration index
+* @retval status: USBD_StatusTypeDef
+*/
+USBD_StatusTypeDef USBD_ClrClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
+{
+ /* Clear configuration and De-initialize the Class process */
+ if (pdev->pClass != NULL)
+ {
+ pdev->pClass->DeInit(pdev, cfgidx);
+ }
+
+ return USBD_OK;
+}
+
+
+/**
+* @brief USBD_SetupStage
+* Handle the setup stage
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_LL_SetupStage(USBD_HandleTypeDef *pdev, uint8_t *psetup)
+{
+ USBD_StatusTypeDef ret;
+
+ USBD_ParseSetupRequest(&pdev->request, psetup);
+
+ pdev->ep0_state = USBD_EP0_SETUP;
+
+ pdev->ep0_data_len = pdev->request.wLength;
+
+ switch (pdev->request.bmRequest & 0x1FU)
+ {
+ case USB_REQ_RECIPIENT_DEVICE:
+ ret = USBD_StdDevReq(pdev, &pdev->request);
+ break;
+
+ case USB_REQ_RECIPIENT_INTERFACE:
+ ret = USBD_StdItfReq(pdev, &pdev->request);
+ break;
+
+ case USB_REQ_RECIPIENT_ENDPOINT:
+ ret = USBD_StdEPReq(pdev, &pdev->request);
+ break;
+
+ default:
+ ret = USBD_LL_StallEP(pdev, (pdev->request.bmRequest & 0x80U));
+ break;
+ }
+
+ return ret;
+}
+
+/**
+* @brief USBD_DataOutStage
+* Handle data OUT stage
+* @param pdev: device instance
+* @param epnum: endpoint index
+* @retval status
+*/
+USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev,
+ uint8_t epnum, uint8_t *pdata)
+{
+ USBD_EndpointTypeDef *pep;
+ USBD_StatusTypeDef ret;
+
+ if (epnum == 0U)
+ {
+ pep = &pdev->ep_out[0];
+
+ if (pdev->ep0_state == USBD_EP0_DATA_OUT)
+ {
+ if (pep->rem_length > pep->maxpacket)
+ {
+ pep->rem_length -= pep->maxpacket;
+
+ (void)USBD_CtlContinueRx(pdev, pdata, MIN(pep->rem_length, pep->maxpacket));
+ }
+ else
+ {
+ if ((pdev->pClass->EP0_RxReady != NULL) &&
+ (pdev->dev_state == USBD_STATE_CONFIGURED))
+ {
+ pdev->pClass->EP0_RxReady(pdev);
+ }
+ (void)USBD_CtlSendStatus(pdev);
+ }
+ }
+ else
+ {
+#if 0
+ if (pdev->ep0_state == USBD_EP0_STATUS_OUT)
+ {
+ /*
+ * STATUS PHASE completed, update ep0_state to idle
+ */
+ pdev->ep0_state = USBD_EP0_IDLE;
+ (void)USBD_LL_StallEP(pdev, 0U);
+ }
+#endif
+ }
+ }
+ else if ((pdev->pClass->DataOut != NULL) &&
+ (pdev->dev_state == USBD_STATE_CONFIGURED))
+ {
+ ret = (USBD_StatusTypeDef)pdev->pClass->DataOut(pdev, epnum);
+
+ if (ret != USBD_OK)
+ {
+ return ret;
+ }
+ }
+ else
+ {
+ /* should never be in this condition */
+ return USBD_FAIL;
+ }
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_DataInStage
+* Handle data in stage
+* @param pdev: device instance
+* @param epnum: endpoint index
+* @retval status
+*/
+USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev,
+ uint8_t epnum, uint8_t *pdata)
+{
+ USBD_EndpointTypeDef *pep;
+ USBD_StatusTypeDef ret;
+
+ if (epnum == 0U)
+ {
+ pep = &pdev->ep_in[0];
+
+ if (pdev->ep0_state == USBD_EP0_DATA_IN)
+ {
+ if (pep->rem_length > pep->maxpacket)
+ {
+ pep->rem_length -= pep->maxpacket;
+
+ (void)USBD_CtlContinueSendData(pdev, pdata, pep->rem_length);
+
+ /* Prepare endpoint for premature end of transfer */
+ (void)USBD_LL_PrepareReceive(pdev, 0U, NULL, 0U);
+ }
+ else
+ {
+ /* last packet is MPS multiple, so send ZLP packet */
+ if ((pep->maxpacket == pep->rem_length) &&
+ (pep->total_length >= pep->maxpacket) &&
+ (pep->total_length < pdev->ep0_data_len))
+ {
+ (void)USBD_CtlContinueSendData(pdev, NULL, 0U);
+ pdev->ep0_data_len = 0U;
+
+ /* Prepare endpoint for premature end of transfer */
+ (void)USBD_LL_PrepareReceive(pdev, 0U, NULL, 0U);
+ }
+ else
+ {
+ if ((pdev->pClass->EP0_TxSent != NULL) &&
+ (pdev->dev_state == USBD_STATE_CONFIGURED))
+ {
+ pdev->pClass->EP0_TxSent(pdev);
+ }
+ (void)USBD_LL_StallEP(pdev, 0x80U);
+ (void)USBD_CtlReceiveStatus(pdev);
+ }
+ }
+ }
+ else
+ {
+#if 0
+ if ((pdev->ep0_state == USBD_EP0_STATUS_IN) ||
+ (pdev->ep0_state == USBD_EP0_IDLE))
+ {
+ (void)USBD_LL_StallEP(pdev, 0x80U);
+ }
+#endif
+ }
+
+ if (pdev->dev_test_mode == 1U)
+ {
+ (void)USBD_RunTestMode(pdev);
+ pdev->dev_test_mode = 0U;
+ }
+ }
+ else if ((pdev->pClass->DataIn != NULL) &&
+ (pdev->dev_state == USBD_STATE_CONFIGURED))
+ {
+ ret = (USBD_StatusTypeDef)pdev->pClass->DataIn(pdev, epnum);
+
+ if (ret != USBD_OK)
+ {
+ return ret;
+ }
+ }
+ else
+ {
+ /* should never be in this condition */
+ return USBD_FAIL;
+ }
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_LL_Reset
+* Handle Reset event
+* @param pdev: device instance
+* @retval status
+*/
+
+USBD_StatusTypeDef USBD_LL_Reset(USBD_HandleTypeDef *pdev)
+{
+ /* Upon Reset call user call back */
+ pdev->dev_state = USBD_STATE_DEFAULT;
+ pdev->ep0_state = USBD_EP0_IDLE;
+ pdev->dev_config = 0U;
+ pdev->dev_remote_wakeup = 0U;
+
+ if (pdev->pClassData != NULL)
+ {
+ pdev->pClass->DeInit(pdev, (uint8_t)pdev->dev_config);
+ }
+
+ /* Open EP0 OUT */
+ (void)USBD_LL_OpenEP(pdev, 0x00U, USBD_EP_TYPE_CTRL, USB_MAX_EP0_SIZE);
+ pdev->ep_out[0x00U & 0xFU].is_used = 1U;
+
+ pdev->ep_out[0].maxpacket = USB_MAX_EP0_SIZE;
+
+ /* Open EP0 IN */
+ (void)USBD_LL_OpenEP(pdev, 0x80U, USBD_EP_TYPE_CTRL, USB_MAX_EP0_SIZE);
+ pdev->ep_in[0x80U & 0xFU].is_used = 1U;
+
+ pdev->ep_in[0].maxpacket = USB_MAX_EP0_SIZE;
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_LL_Reset
+* Handle Reset event
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_LL_SetSpeed(USBD_HandleTypeDef *pdev,
+ USBD_SpeedTypeDef speed)
+{
+ pdev->dev_speed = speed;
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_Suspend
+* Handle Suspend event
+* @param pdev: device instance
+* @retval status
+*/
+
+USBD_StatusTypeDef USBD_LL_Suspend(USBD_HandleTypeDef *pdev)
+{
+ pdev->dev_old_state = pdev->dev_state;
+ pdev->dev_state = USBD_STATE_SUSPENDED;
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_Resume
+* Handle Resume event
+* @param pdev: device instance
+* @retval status
+*/
+
+USBD_StatusTypeDef USBD_LL_Resume(USBD_HandleTypeDef *pdev)
+{
+ if (pdev->dev_state == USBD_STATE_SUSPENDED)
+ {
+ pdev->dev_state = pdev->dev_old_state;
+ }
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_SOF
+* Handle SOF event
+* @param pdev: device instance
+* @retval status
+*/
+
+USBD_StatusTypeDef USBD_LL_SOF(USBD_HandleTypeDef *pdev)
+{
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ if (pdev->pClass->SOF != NULL)
+ {
+ pdev->pClass->SOF(pdev);
+ }
+ }
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_IsoINIncomplete
+* Handle iso in incomplete event
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev,
+ uint8_t epnum)
+{
+ /* Prevent unused arguments compilation warning */
+ UNUSED(pdev);
+ UNUSED(epnum);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_IsoOUTIncomplete
+* Handle iso out incomplete event
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev,
+ uint8_t epnum)
+{
+ /* Prevent unused arguments compilation warning */
+ UNUSED(pdev);
+ UNUSED(epnum);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_DevConnected
+* Handle device connection event
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_LL_DevConnected(USBD_HandleTypeDef *pdev)
+{
+ /* Prevent unused argument compilation warning */
+ UNUSED(pdev);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_DevDisconnected
+* Handle device disconnection event
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_LL_DevDisconnected(USBD_HandleTypeDef *pdev)
+{
+ /* Free Class Resources */
+ pdev->dev_state = USBD_STATE_DEFAULT;
+
+ if (pdev->pClass != NULL)
+ {
+ pdev->pClass->DeInit(pdev, (uint8_t)pdev->dev_config);
+ }
+
+ return USBD_OK;
+}
+/**
+* @}
+*/
+
+
+/**
+* @}
+*/
+
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c
new file mode 100644
index 0000000000..c31d40e0a0
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c
@@ -0,0 +1,944 @@
+/**
+ ******************************************************************************
+ * @file usbd_req.c
+ * @author MCD Application Team
+ * @brief This file provides the standard USB requests following chapter 9.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ctlreq.h"
+#include "usbd_ioreq.h"
+
+
+/** @addtogroup STM32_USBD_STATE_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_REQ
+ * @brief USB standard requests module
+ * @{
+ */
+
+/** @defgroup USBD_REQ_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_REQ_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_REQ_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_REQ_Private_Variables
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_REQ_Private_FunctionPrototypes
+ * @{
+ */
+static void USBD_GetDescriptor(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void USBD_SetAddress(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static USBD_StatusTypeDef USBD_SetConfig(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void USBD_GetConfig(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void USBD_GetStatus(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void USBD_SetFeature(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static void USBD_ClrFeature(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
+static uint8_t USBD_GetLen(uint8_t *buf);
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_REQ_Private_Functions
+ * @{
+ */
+
+
+/**
+* @brief USBD_StdDevReq
+* Handle standard usb device requests
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+USBD_StatusTypeDef USBD_StdDevReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS:
+ case USB_REQ_TYPE_VENDOR:
+ ret = (USBD_StatusTypeDef)pdev->pClass->Setup(pdev, req);
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_GET_DESCRIPTOR:
+ USBD_GetDescriptor(pdev, req);
+ break;
+
+ case USB_REQ_SET_ADDRESS:
+ USBD_SetAddress(pdev, req);
+ break;
+
+ case USB_REQ_SET_CONFIGURATION:
+ ret = USBD_SetConfig(pdev, req);
+ break;
+
+ case USB_REQ_GET_CONFIGURATION:
+ USBD_GetConfig(pdev, req);
+ break;
+
+ case USB_REQ_GET_STATUS:
+ USBD_GetStatus(pdev, req);
+ break;
+
+ case USB_REQ_SET_FEATURE:
+ USBD_SetFeature(pdev, req);
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ USBD_ClrFeature(pdev, req);
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+
+ return ret;
+}
+
+/**
+* @brief USBD_StdItfReq
+* Handle standard usb interface requests
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+USBD_StatusTypeDef USBD_StdItfReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_StatusTypeDef ret = USBD_OK;
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS:
+ case USB_REQ_TYPE_VENDOR:
+ case USB_REQ_TYPE_STANDARD:
+ switch (pdev->dev_state)
+ {
+ case USBD_STATE_DEFAULT:
+ case USBD_STATE_ADDRESSED:
+ case USBD_STATE_CONFIGURED:
+
+ if (LOBYTE(req->wIndex) <= USBD_MAX_NUM_INTERFACES)
+ {
+ ret = (USBD_StatusTypeDef)pdev->pClass->Setup(pdev, req);
+
+ if ((req->wLength == 0U) && (ret == USBD_OK))
+ {
+ (void)USBD_CtlSendStatus(pdev);
+ }
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+
+ return ret;
+}
+
+/**
+* @brief USBD_StdEPReq
+* Handle standard usb endpoint requests
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+USBD_StatusTypeDef USBD_StdEPReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_EndpointTypeDef *pep;
+ uint8_t ep_addr;
+ USBD_StatusTypeDef ret = USBD_OK;
+ ep_addr = LOBYTE(req->wIndex);
+
+ switch (req->bmRequest & USB_REQ_TYPE_MASK)
+ {
+ case USB_REQ_TYPE_CLASS:
+ case USB_REQ_TYPE_VENDOR:
+ ret = (USBD_StatusTypeDef)pdev->pClass->Setup(pdev, req);
+ break;
+
+ case USB_REQ_TYPE_STANDARD:
+ switch (req->bRequest)
+ {
+ case USB_REQ_SET_FEATURE:
+ switch (pdev->dev_state)
+ {
+ case USBD_STATE_ADDRESSED:
+ if ((ep_addr != 0x00U) && (ep_addr != 0x80U))
+ {
+ (void)USBD_LL_StallEP(pdev, ep_addr);
+ (void)USBD_LL_StallEP(pdev, 0x80U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ }
+ break;
+
+ case USBD_STATE_CONFIGURED:
+ if (req->wValue == USB_FEATURE_EP_HALT)
+ {
+ if ((ep_addr != 0x00U) && (ep_addr != 0x80U) && (req->wLength == 0x00U))
+ {
+ (void)USBD_LL_StallEP(pdev, ep_addr);
+ }
+ }
+ (void)USBD_CtlSendStatus(pdev);
+
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+
+ switch (pdev->dev_state)
+ {
+ case USBD_STATE_ADDRESSED:
+ if ((ep_addr != 0x00U) && (ep_addr != 0x80U))
+ {
+ (void)USBD_LL_StallEP(pdev, ep_addr);
+ (void)USBD_LL_StallEP(pdev, 0x80U);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ }
+ break;
+
+ case USBD_STATE_CONFIGURED:
+ if (req->wValue == USB_FEATURE_EP_HALT)
+ {
+ if ((ep_addr & 0x7FU) != 0x00U)
+ {
+ (void)USBD_LL_ClearStallEP(pdev, ep_addr);
+ }
+ (void)USBD_CtlSendStatus(pdev);
+ (USBD_StatusTypeDef)pdev->pClass->Setup(pdev, req);
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ break;
+
+ case USB_REQ_GET_STATUS:
+ switch (pdev->dev_state)
+ {
+ case USBD_STATE_ADDRESSED:
+ if ((ep_addr != 0x00U) && (ep_addr != 0x80U))
+ {
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ pep = ((ep_addr & 0x80U) == 0x80U) ? &pdev->ep_in[ep_addr & 0x7FU] : \
+ &pdev->ep_out[ep_addr & 0x7FU];
+
+ pep->status = 0x0000U;
+
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&pep->status, 2U);
+ break;
+
+ case USBD_STATE_CONFIGURED:
+ if ((ep_addr & 0x80U) == 0x80U)
+ {
+ if (pdev->ep_in[ep_addr & 0xFU].is_used == 0U)
+ {
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ }
+ else
+ {
+ if (pdev->ep_out[ep_addr & 0xFU].is_used == 0U)
+ {
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ }
+
+ pep = ((ep_addr & 0x80U) == 0x80U) ? &pdev->ep_in[ep_addr & 0x7FU] : \
+ &pdev->ep_out[ep_addr & 0x7FU];
+
+ if ((ep_addr == 0x00U) || (ep_addr == 0x80U))
+ {
+ pep->status = 0x0000U;
+ }
+ else if (USBD_LL_IsStallEP(pdev, ep_addr) != 0U)
+ {
+ pep->status = 0x0001U;
+ }
+ else
+ {
+ pep->status = 0x0000U;
+ }
+
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&pep->status, 2U);
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+
+ return ret;
+}
+
+
+/**
+* @brief USBD_GetDescriptor
+* Handle Get Descriptor requests
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+static void USBD_GetDescriptor(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ uint16_t len = 0U;
+ uint8_t *pbuf = NULL;
+ uint8_t err = 0U;
+
+ switch (req->wValue >> 8)
+ {
+#if ((USBD_LPM_ENABLED == 1U) || (USBD_CLASS_BOS_ENABLED == 1U))
+ case USB_DESC_TYPE_BOS:
+ if (pdev->pDesc->GetBOSDescriptor != NULL)
+ {
+ pbuf = pdev->pDesc->GetBOSDescriptor(pdev->dev_speed, &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+#endif
+ case USB_DESC_TYPE_DEVICE:
+ pbuf = pdev->pDesc->GetDeviceDescriptor(pdev->dev_speed, &len);
+ break;
+
+ case USB_DESC_TYPE_CONFIGURATION:
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ pbuf = pdev->pClass->GetHSConfigDescriptor(&len);
+ pbuf[1] = USB_DESC_TYPE_CONFIGURATION;
+ }
+ else
+ {
+ pbuf = pdev->pClass->GetFSConfigDescriptor(&len);
+ pbuf[1] = USB_DESC_TYPE_CONFIGURATION;
+ }
+ break;
+
+ case USB_DESC_TYPE_STRING:
+ switch ((uint8_t)(req->wValue))
+ {
+ case USBD_IDX_LANGID_STR:
+ if (pdev->pDesc->GetLangIDStrDescriptor != NULL)
+ {
+ pbuf = pdev->pDesc->GetLangIDStrDescriptor(pdev->dev_speed, &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+
+ case USBD_IDX_MFC_STR:
+ if (pdev->pDesc->GetManufacturerStrDescriptor != NULL)
+ {
+ pbuf = pdev->pDesc->GetManufacturerStrDescriptor(pdev->dev_speed, &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+
+ case USBD_IDX_PRODUCT_STR:
+ if (pdev->pDesc->GetProductStrDescriptor != NULL)
+ {
+ pbuf = pdev->pDesc->GetProductStrDescriptor(pdev->dev_speed, &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+
+ case USBD_IDX_SERIAL_STR:
+ if (pdev->pDesc->GetSerialStrDescriptor != NULL)
+ {
+ pbuf = pdev->pDesc->GetSerialStrDescriptor(pdev->dev_speed, &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+
+ case USBD_IDX_CONFIG_STR:
+ if (pdev->pDesc->GetConfigurationStrDescriptor != NULL)
+ {
+ pbuf = pdev->pDesc->GetConfigurationStrDescriptor(pdev->dev_speed, &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+
+ case USBD_IDX_INTERFACE_STR:
+ if (pdev->pDesc->GetInterfaceStrDescriptor != NULL)
+ {
+ pbuf = pdev->pDesc->GetInterfaceStrDescriptor(pdev->dev_speed, &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+
+ default:
+#if (USBD_SUPPORT_USER_STRING_DESC == 1U)
+ if (pdev->pClass->GetUsrStrDescriptor != NULL)
+ {
+ pbuf = pdev->pClass->GetUsrStrDescriptor(pdev, (req->wValue), &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+#elif (USBD_CLASS_USER_STRING_DESC == 1U)
+ if (pdev->pDesc->GetUserStrDescriptor != NULL)
+ {
+ pbuf = pdev->pDesc->GetUserStrDescriptor(pdev->dev_speed, (req->wValue), &len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+#else
+ USBD_CtlError(pdev, req);
+ err++;
+#endif
+ break;
+ }
+ break;
+
+ case USB_DESC_TYPE_DEVICE_QUALIFIER:
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ pbuf = pdev->pClass->GetDeviceQualifierDescriptor(&len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+
+ case USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION:
+ if (pdev->dev_speed == USBD_SPEED_HIGH)
+ {
+ pbuf = pdev->pClass->GetOtherSpeedConfigDescriptor(&len);
+ pbuf[1] = USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION;
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ err++;
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ err++;
+ break;
+ }
+
+ if (err != 0U)
+ {
+ return;
+ }
+ else
+ {
+ if (req->wLength != 0U)
+ {
+ if (len != 0U)
+ {
+ len = MIN(len, req->wLength);
+ (void)USBD_CtlSendData(pdev, pbuf, len);
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ }
+ }
+ else
+ {
+ (void)USBD_CtlSendStatus(pdev);
+ }
+ }
+}
+
+/**
+* @brief USBD_SetAddress
+* Set device address
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+static void USBD_SetAddress(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ uint8_t dev_addr;
+
+ if ((req->wIndex == 0U) && (req->wLength == 0U) && (req->wValue < 128U))
+ {
+ dev_addr = (uint8_t)(req->wValue) & 0x7FU;
+
+ if (pdev->dev_state == USBD_STATE_CONFIGURED)
+ {
+ USBD_CtlError(pdev, req);
+ }
+ else
+ {
+ pdev->dev_address = dev_addr;
+ (void)USBD_LL_SetUSBAddress(pdev, dev_addr);
+ (void)USBD_CtlSendStatus(pdev);
+
+ if (dev_addr != 0U)
+ {
+ pdev->dev_state = USBD_STATE_ADDRESSED;
+ }
+ else
+ {
+ pdev->dev_state = USBD_STATE_DEFAULT;
+ }
+ }
+ }
+ else
+ {
+ USBD_CtlError(pdev, req);
+ }
+}
+
+/**
+* @brief USBD_SetConfig
+* Handle Set device configuration request
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+static USBD_StatusTypeDef USBD_SetConfig(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ USBD_StatusTypeDef ret = USBD_OK;
+ static uint8_t cfgidx;
+
+ cfgidx = (uint8_t)(req->wValue);
+
+ if (cfgidx > USBD_MAX_NUM_CONFIGURATION)
+ {
+ USBD_CtlError(pdev, req);
+ return USBD_FAIL;
+ }
+
+ switch (pdev->dev_state)
+ {
+ case USBD_STATE_ADDRESSED:
+ if (cfgidx != 0U)
+ {
+ pdev->dev_config = cfgidx;
+
+ ret = USBD_SetClassConfig(pdev, cfgidx);
+
+ if (ret != USBD_OK)
+ {
+ USBD_CtlError(pdev, req);
+ }
+ else
+ {
+ (void)USBD_CtlSendStatus(pdev);
+ pdev->dev_state = USBD_STATE_CONFIGURED;
+ }
+ }
+ else
+ {
+ (void)USBD_CtlSendStatus(pdev);
+ }
+ break;
+
+ case USBD_STATE_CONFIGURED:
+ if (cfgidx == 0U)
+ {
+ pdev->dev_state = USBD_STATE_ADDRESSED;
+ pdev->dev_config = cfgidx;
+ (void)USBD_ClrClassConfig(pdev, cfgidx);
+ (void)USBD_CtlSendStatus(pdev);
+ }
+ else if (cfgidx != pdev->dev_config)
+ {
+ /* Clear old configuration */
+ (void)USBD_ClrClassConfig(pdev, (uint8_t)pdev->dev_config);
+
+ /* set new configuration */
+ pdev->dev_config = cfgidx;
+
+ ret = USBD_SetClassConfig(pdev, cfgidx);
+
+ if (ret != USBD_OK)
+ {
+ USBD_CtlError(pdev, req);
+ (void)USBD_ClrClassConfig(pdev, (uint8_t)pdev->dev_config);
+ pdev->dev_state = USBD_STATE_ADDRESSED;
+ }
+ else
+ {
+ (void)USBD_CtlSendStatus(pdev);
+ }
+ }
+ else
+ {
+ (void)USBD_CtlSendStatus(pdev);
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ (void)USBD_ClrClassConfig(pdev, cfgidx);
+ ret = USBD_FAIL;
+ break;
+ }
+
+ return ret;
+}
+
+/**
+* @brief USBD_GetConfig
+* Handle Get device configuration request
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+static void USBD_GetConfig(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ if (req->wLength != 1U)
+ {
+ USBD_CtlError(pdev, req);
+ }
+ else
+ {
+ switch (pdev->dev_state)
+ {
+ case USBD_STATE_DEFAULT:
+ case USBD_STATE_ADDRESSED:
+ pdev->dev_default_config = 0U;
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&pdev->dev_default_config, 1U);
+ break;
+
+ case USBD_STATE_CONFIGURED:
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&pdev->dev_config, 1U);
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+ }
+}
+
+/**
+* @brief USBD_GetStatus
+* Handle Get Status request
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+static void USBD_GetStatus(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ switch (pdev->dev_state)
+ {
+ case USBD_STATE_DEFAULT:
+ case USBD_STATE_ADDRESSED:
+ case USBD_STATE_CONFIGURED:
+ if (req->wLength != 0x2U)
+ {
+ USBD_CtlError(pdev, req);
+ break;
+ }
+
+#if (USBD_SELF_POWERED == 1U)
+ pdev->dev_config_status = USB_CONFIG_SELF_POWERED;
+#else
+ pdev->dev_config_status = 0U;
+#endif
+
+ if (pdev->dev_remote_wakeup != 0U)
+ {
+ pdev->dev_config_status |= USB_CONFIG_REMOTE_WAKEUP;
+ }
+
+ (void)USBD_CtlSendData(pdev, (uint8_t *)&pdev->dev_config_status, 2U);
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+}
+
+
+/**
+* @brief USBD_SetFeature
+* Handle Set device feature request
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+static void USBD_SetFeature(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ if (req->wValue == USB_FEATURE_REMOTE_WAKEUP)
+ {
+ pdev->dev_remote_wakeup = 1U;
+ (void)USBD_CtlSendStatus(pdev);
+ }
+}
+
+
+/**
+* @brief USBD_ClrFeature
+* Handle clear device feature request
+* @param pdev: device instance
+* @param req: usb request
+* @retval status
+*/
+static void USBD_ClrFeature(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ switch (pdev->dev_state)
+ {
+ case USBD_STATE_DEFAULT:
+ case USBD_STATE_ADDRESSED:
+ case USBD_STATE_CONFIGURED:
+ if (req->wValue == USB_FEATURE_REMOTE_WAKEUP)
+ {
+ pdev->dev_remote_wakeup = 0U;
+ (void)USBD_CtlSendStatus(pdev);
+ }
+ break;
+
+ default:
+ USBD_CtlError(pdev, req);
+ break;
+ }
+}
+
+/**
+* @brief USBD_ParseSetupRequest
+* Copy buffer into setup structure
+* @param pdev: device instance
+* @param req: usb request
+* @retval None
+*/
+
+void USBD_ParseSetupRequest(USBD_SetupReqTypedef *req, uint8_t *pdata)
+{
+ uint8_t *pbuff = pdata;
+
+ req->bmRequest = *(uint8_t *)(pbuff);
+
+ pbuff++;
+ req->bRequest = *(uint8_t *)(pbuff);
+
+ pbuff++;
+ req->wValue = SWAPBYTE(pbuff);
+
+ pbuff++;
+ pbuff++;
+ req->wIndex = SWAPBYTE(pbuff);
+
+ pbuff++;
+ pbuff++;
+ req->wLength = SWAPBYTE(pbuff);
+}
+
+/**
+* @brief USBD_CtlError
+* Handle USB low level Error
+* @param pdev: device instance
+* @param req: usb request
+* @retval None
+*/
+
+void USBD_CtlError(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
+{
+ UNUSED(req);
+
+ (void)USBD_LL_StallEP(pdev, 0x80U);
+ (void)USBD_LL_StallEP(pdev, 0U);
+}
+
+
+/**
+ * @brief USBD_GetString
+ * Convert Ascii string into unicode one
+ * @param desc : descriptor buffer
+ * @param unicode : Formatted string buffer (unicode)
+ * @param len : descriptor length
+ * @retval None
+ */
+void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len)
+{
+ uint8_t idx = 0U;
+ uint8_t *pdesc;
+
+ if (desc == NULL)
+ {
+ return;
+ }
+
+ pdesc = desc;
+ *len = ((uint16_t)USBD_GetLen(pdesc) * 2U) + 2U;
+
+ unicode[idx] = *(uint8_t *)len;
+ idx++;
+ unicode[idx] = USB_DESC_TYPE_STRING;
+ idx++;
+
+ while (*pdesc != (uint8_t)'\0')
+ {
+ unicode[idx] = *pdesc;
+ pdesc++;
+ idx++;
+
+ unicode[idx] = 0U;
+ idx++;
+ }
+}
+
+/**
+ * @brief USBD_GetLen
+ * return the string length
+ * @param buf : pointer to the ascii string buffer
+ * @retval string length
+ */
+static uint8_t USBD_GetLen(uint8_t *buf)
+{
+ uint8_t len = 0U;
+ uint8_t *pbuff = buf;
+
+ while (*pbuff != (uint8_t)'\0')
+ {
+ len++;
+ pbuff++;
+ }
+
+ return len;
+}
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c
new file mode 100644
index 0000000000..8ac5491ffe
--- /dev/null
+++ b/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c
@@ -0,0 +1,216 @@
+/**
+ ******************************************************************************
+ * @file usbd_ioreq.c
+ * @author MCD Application Team
+ * @brief This file provides the IO requests APIs for control endpoints.
+ ******************************************************************************
+ * @attention
+ *
+ * © Copyright (c) 2015 STMicroelectronics.
+ * All rights reserved.
+ *
+ * This software component is licensed by ST under Ultimate Liberty license
+ * SLA0044, the "License"; You may not use this file except in compliance with
+ * the License. You may obtain a copy of the License at:
+ * www.st.com/SLA0044
+ *
+ ******************************************************************************
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+
+/** @addtogroup STM32_USB_DEVICE_LIBRARY
+ * @{
+ */
+
+
+/** @defgroup USBD_IOREQ
+ * @brief control I/O requests module
+ * @{
+ */
+
+/** @defgroup USBD_IOREQ_Private_TypesDefinitions
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_IOREQ_Private_Defines
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_IOREQ_Private_Macros
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_IOREQ_Private_Variables
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_IOREQ_Private_FunctionPrototypes
+ * @{
+ */
+/**
+ * @}
+ */
+
+
+/** @defgroup USBD_IOREQ_Private_Functions
+ * @{
+ */
+
+/**
+* @brief USBD_CtlSendData
+* send data on the ctl pipe
+* @param pdev: device instance
+* @param buff: pointer to data buffer
+* @param len: length of data to be sent
+* @retval status
+*/
+USBD_StatusTypeDef USBD_CtlSendData(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuf, uint32_t len)
+{
+ /* Set EP0 State */
+ pdev->ep0_state = USBD_EP0_DATA_IN;
+ pdev->ep_in[0].total_length = len;
+ pdev->ep_in[0].rem_length = len;
+
+ /* Start the transfer */
+ (void)USBD_LL_Transmit(pdev, 0x00U, pbuf, len);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_CtlContinueSendData
+* continue sending data on the ctl pipe
+* @param pdev: device instance
+* @param buff: pointer to data buffer
+* @param len: length of data to be sent
+* @retval status
+*/
+USBD_StatusTypeDef USBD_CtlContinueSendData(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuf, uint32_t len)
+{
+ /* Start the next transfer */
+ (void)USBD_LL_Transmit(pdev, 0x00U, pbuf, len);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_CtlPrepareRx
+* receive data on the ctl pipe
+* @param pdev: device instance
+* @param buff: pointer to data buffer
+* @param len: length of data to be received
+* @retval status
+*/
+USBD_StatusTypeDef USBD_CtlPrepareRx(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuf, uint32_t len)
+{
+ /* Set EP0 State */
+ pdev->ep0_state = USBD_EP0_DATA_OUT;
+ pdev->ep_out[0].total_length = len;
+ pdev->ep_out[0].rem_length = len;
+
+ /* Start the transfer */
+ (void)USBD_LL_PrepareReceive(pdev, 0U, pbuf, len);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_CtlContinueRx
+* continue receive data on the ctl pipe
+* @param pdev: device instance
+* @param buff: pointer to data buffer
+* @param len: length of data to be received
+* @retval status
+*/
+USBD_StatusTypeDef USBD_CtlContinueRx(USBD_HandleTypeDef *pdev,
+ uint8_t *pbuf, uint32_t len)
+{
+ (void)USBD_LL_PrepareReceive(pdev, 0U, pbuf, len);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_CtlSendStatus
+* send zero lzngth packet on the ctl pipe
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_CtlSendStatus(USBD_HandleTypeDef *pdev)
+{
+ /* Set EP0 State */
+ pdev->ep0_state = USBD_EP0_STATUS_IN;
+
+ /* Start the transfer */
+ (void)USBD_LL_Transmit(pdev, 0x00U, NULL, 0U);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_CtlReceiveStatus
+* receive zero lzngth packet on the ctl pipe
+* @param pdev: device instance
+* @retval status
+*/
+USBD_StatusTypeDef USBD_CtlReceiveStatus(USBD_HandleTypeDef *pdev)
+{
+ /* Set EP0 State */
+ pdev->ep0_state = USBD_EP0_STATUS_OUT;
+
+ /* Start the transfer */
+ (void)USBD_LL_PrepareReceive(pdev, 0U, NULL, 0U);
+
+ return USBD_OK;
+}
+
+/**
+* @brief USBD_GetRxCount
+* returns the received data length
+* @param pdev: device instance
+* @param ep_addr: endpoint address
+* @retval Rx Data blength
+*/
+uint32_t USBD_GetRxCount(USBD_HandleTypeDef *pdev, uint8_t ep_addr)
+{
+ return USBD_LL_GetRxDataSize(pdev, ep_addr);
+}
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/