From 6beeca38c3ad45127b5a7e507183918a2db62e2e Mon Sep 17 00:00:00 2001 From: jflyper Date: Sat, 1 Jun 2019 11:38:42 +0900 Subject: [PATCH] Consolidate F7 and H7 VCP HAL code except usbd_conf.c --- make/mcu/STM32F7.mk | 2 +- make/mcu/STM32H7.mk | 10 +- src/main/drivers/serial_usb_vcp.c | 4 - src/main/io/usb_cdc_hid.c | 7 - src/main/vcp_hal/usbd_cdc_hid.c | 3 +- src/main/vcp_hal/usbd_cdc_interface.c | 8 +- src/main/vcp_hal/usbd_cdc_interface.h | 2 - src/main/vcp_hal/usbd_conf.h | 12 +- .../{usbd_conf.c => usbd_conf_stm32f7xx.c} | 0 .../usbd_conf_stm32h7xx.c} | 0 src/main/vcph7/usbd_cdc_hid.c | 336 ------------ src/main/vcph7/usbd_cdc_interface.c | 479 ------------------ src/main/vcph7/usbd_cdc_interface.h | 98 ---- src/main/vcph7/usbd_conf.h | 113 ----- src/main/vcph7/usbd_desc.c | 354 ------------- src/main/vcph7/usbd_desc.h | 65 --- 16 files changed, 22 insertions(+), 1471 deletions(-) rename src/main/vcp_hal/{usbd_conf.c => usbd_conf_stm32f7xx.c} (100%) rename src/main/{vcph7/usbd_conf.c => vcp_hal/usbd_conf_stm32h7xx.c} (100%) delete mode 100644 src/main/vcph7/usbd_cdc_hid.c delete mode 100644 src/main/vcph7/usbd_cdc_interface.c delete mode 100644 src/main/vcph7/usbd_cdc_interface.h delete mode 100644 src/main/vcph7/usbd_conf.h delete mode 100644 src/main/vcph7/usbd_desc.c delete mode 100644 src/main/vcph7/usbd_desc.h diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk index cd1f2da5f..925d6ce97 100644 --- a/make/mcu/STM32F7.mk +++ b/make/mcu/STM32F7.mk @@ -157,7 +157,7 @@ TARGET_FLAGS = -D$(TARGET) VCP_SRC = \ vcp_hal/usbd_desc.c \ - vcp_hal/usbd_conf.c \ + vcp_hal/usbd_conf_stm32f7xx.c \ vcp_hal/usbd_cdc_hid.c \ vcp_hal/usbd_cdc_interface.c \ drivers/serial_usb_vcp.c \ diff --git a/make/mcu/STM32H7.mk b/make/mcu/STM32H7.mk index c14bf8d1e..fd5b04a75 100644 --- a/make/mcu/STM32H7.mk +++ b/make/mcu/STM32H7.mk @@ -137,7 +137,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(USBMSC_DIR)/Inc \ $(CMSIS_DIR)/Core/Include \ $(ROOT)/lib/main/STM32H7/Drivers/CMSIS/Device/ST/STM32H7xx/Include \ - $(ROOT)/src/main/vcph7 + $(ROOT)/src/main/vcp_hal ifneq ($(filter SDCARD_SPI,$(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ @@ -193,10 +193,10 @@ DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000 TARGET_FLAGS = -D$(TARGET) VCP_SRC = \ - vcph7/usbd_desc.c \ - vcph7/usbd_conf.c \ - vcph7/usbd_cdc_hid.c \ - vcph7/usbd_cdc_interface.c \ + vcp_hal/usbd_desc.c \ + vcp_hal/usbd_conf_stm32h7xx.c \ + vcp_hal/usbd_cdc_hid.c \ + vcp_hal/usbd_cdc_interface.c \ drivers/serial_usb_vcp.c \ drivers/usb_io.c diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 0782bcae2..47266c076 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -41,11 +41,7 @@ #endif #include "usb_io.h" #elif defined(STM32F7) || defined(STM32H7) -#ifdef STM32F7 #include "vcp_hal/usbd_cdc_interface.h" -#else -#include "vcph7/usbd_cdc_interface.h" -#endif #include "usb_io.h" #ifdef USE_USB_CDC_HID #include "usbd_ioreq.h" diff --git a/src/main/io/usb_cdc_hid.c b/src/main/io/usb_cdc_hid.c index 523870890..96b86fb7b 100644 --- a/src/main/io/usb_cdc_hid.c +++ b/src/main/io/usb_cdc_hid.c @@ -31,18 +31,11 @@ //TODO: Make it platform independent in the future #if defined(STM32F4) #include "vcpf4/usbd_cdc_vcp.h" - #include "usbd_hid_core.h" #elif defined(STM32F7) || defined(STM32H7) #include "drivers/serial_usb_vcp.h" #include "usbd_hid.h" - -#if defined(STM32F7) #include "vcp_hal/usbd_cdc_interface.h" -#elif defined(STM32H7) -#include "vcph7/usbd_cdc_interface.h" -#endif - #endif #define USB_CDC_HID_NUM_AXES 8 diff --git a/src/main/vcp_hal/usbd_cdc_hid.c b/src/main/vcp_hal/usbd_cdc_hid.c index 163912d4f..875e0ab9d 100644 --- a/src/main/vcp_hal/usbd_cdc_hid.c +++ b/src/main/vcp_hal/usbd_cdc_hid.c @@ -25,11 +25,10 @@ #ifdef USE_USB_CDC_HID -//#include "usbd_cdc_hid.h" +#include "usbd_conf.h" #include "usbd_desc.h" #include "usbd_ctlreq.h" #include "usbd_def.h" -#include "usbd_conf.h" #include "usbd_cdc.h" #include "usbd_hid.h" diff --git a/src/main/vcp_hal/usbd_cdc_interface.c b/src/main/vcp_hal/usbd_cdc_interface.c index 084fc2b1f..0522cf2c3 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.c +++ b/src/main/vcp_hal/usbd_cdc_interface.c @@ -49,10 +49,9 @@ #include "platform.h" -#include "drivers/serial_usb_vcp.h" -#include "drivers/time.h" +#include "build/atomic.h" -#include "stm32f7xx_hal.h" +#include "usbd_conf.h" #include "usbd_core.h" #include "usbd_desc.h" #include "usbd_cdc.h" @@ -60,7 +59,8 @@ #include "stdbool.h" #include "drivers/nvic.h" -#include "build/atomic.h" +#include "drivers/serial_usb_vcp.h" +#include "drivers/time.h" /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ diff --git a/src/main/vcp_hal/usbd_cdc_interface.h b/src/main/vcp_hal/usbd_cdc_interface.h index f7f0aa20f..47c93b938 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.h +++ b/src/main/vcp_hal/usbd_cdc_interface.h @@ -50,10 +50,8 @@ #define __USBD_CDC_IF_H /* Includes ------------------------------------------------------------------*/ -#include "common/maths.h" #include "usbd_cdc.h" -#include "stm32f7xx_hal.h" #include "usbd_core.h" #include "usbd_desc.h" diff --git a/src/main/vcp_hal/usbd_conf.h b/src/main/vcp_hal/usbd_conf.h index aaef99aaf..483d98b7a 100644 --- a/src/main/vcp_hal/usbd_conf.h +++ b/src/main/vcp_hal/usbd_conf.h @@ -50,7 +50,17 @@ #define __USBD_CONF_H /* Includes ------------------------------------------------------------------*/ +#include "platform.h" // Required for inclusion of stm32Yxx_hal.h below within USB device library code +#include "common/maths.h" // Required for MIN & MAX within USB device library code + +#if defined(STM32F7) #include "stm32f7xx_hal.h" +#elif defined(STM32H7) +#include "stm32h7xx_hal.h" +#else +#error Unknown MCU +#endif + #if (USBD_DEBUG_LEVEL > 0) #include #endif @@ -66,7 +76,7 @@ #define USBD_SUPPORT_USER_STRING 0 #define USBD_SELF_POWERED 1 #define USBD_DEBUG_LEVEL 0 -#define MSC_MEDIA_PACKET 512 +#define MSC_MEDIA_PACKET 512U #define USE_USB_FS /* Exported macro ------------------------------------------------------------*/ diff --git a/src/main/vcp_hal/usbd_conf.c b/src/main/vcp_hal/usbd_conf_stm32f7xx.c similarity index 100% rename from src/main/vcp_hal/usbd_conf.c rename to src/main/vcp_hal/usbd_conf_stm32f7xx.c diff --git a/src/main/vcph7/usbd_conf.c b/src/main/vcp_hal/usbd_conf_stm32h7xx.c similarity index 100% rename from src/main/vcph7/usbd_conf.c rename to src/main/vcp_hal/usbd_conf_stm32h7xx.c diff --git a/src/main/vcph7/usbd_cdc_hid.c b/src/main/vcph7/usbd_cdc_hid.c deleted file mode 100644 index b2e1c3029..000000000 --- a/src/main/vcph7/usbd_cdc_hid.c +++ /dev/null @@ -1,336 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - * - * Author: Chris Hockuba (https://github.com/conkerkh) - * - */ - -#include "platform.h" - -#ifdef USE_USB_CDC_HID - -#include "usbd_desc.h" -#include "usbd_ctlreq.h" -#include "usbd_def.h" -#include "usbd_conf.h" - -#include "usbd_cdc.h" -#include "usbd_hid.h" - -#define USB_HID_CDC_CONFIG_DESC_SIZ (USB_HID_CONFIG_DESC_SIZ - 9 + USB_CDC_CONFIG_DESC_SIZ + 8) - -#define HID_INTERFACE 0x0 -#define HID_POOLING_INTERVAL 0x0A // 10ms - 100Hz update rate - -#define CDC_COM_INTERFACE 0x1 - -#define USBD_VID 0x0483 -#define USBD_PID 0x3256 - -__ALIGN_BEGIN uint8_t USBD_HID_CDC_DeviceDescriptor[USB_LEN_DEV_DESC] __ALIGN_END = -{ - 0x12, /*bLength */ - USB_DESC_TYPE_DEVICE, /*bDescriptorType*/ - 0x00, 0x02, /*bcdUSB */ - 0xEF, /*bDeviceClass*/ - 0x02, /*bDeviceSubClass*/ - 0x01, /*bDeviceProtocol*/ - USB_OTG_MAX_EP0_SIZE, /*bMaxPacketSize*/ - LOBYTE(USBD_VID), HIBYTE(USBD_VID), /*idVendor*/ - LOBYTE(USBD_PID), - HIBYTE(USBD_PID), /*idProduct*/ - 0x00, 0x02, /*bcdDevice rel. 2.00*/ - USBD_IDX_MFC_STR, /*Index of manufacturer string*/ - USBD_IDX_PRODUCT_STR, /*Index of product string*/ - USBD_IDX_SERIAL_STR, /*Index of serial number string*/ - USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/ -}; - -__ALIGN_BEGIN static uint8_t USBD_HID_CDC_CfgDesc[USB_HID_CDC_CONFIG_DESC_SIZ] __ALIGN_END = -{ - 0x09, /* bLength: Configuration Descriptor size */ - USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */ - USB_HID_CDC_CONFIG_DESC_SIZ, - /* wTotalLength: Bytes returned */ - 0x00, - 0x03, /*bNumInterfaces: 2 interfaces (1 for CDC, 1 for HID)*/ - 0x01, /*bConfigurationValue: Configuration value*/ - 0x00, /*iConfiguration: Index of string descriptor describing - the configuration*/ - 0xC0, /*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*/ - HID_INTERFACE, /*bInterfaceNumber: Number of Interface*/ - 0x00, /*bAlternateSetting: Alternate setting*/ - 0x01, /*bNumEndpoints*/ - 0x03, /*bInterfaceClass: HID*/ - 0x00, /*bInterfaceSubClass : 1=BOOT, 0=no boot*/ - 0x00, /*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: 8 Byte max */ - 0x00, - HID_POOLING_INTERVAL, /*bInterval: Polling Interval (10 ms)*/ - /* 34 */ - - /******** /IAD should be positioned just before the CDC interfaces ****** - IAD to associate the two CDC interfaces */ - - 0x08, /* bLength */ - 0x0B, /* bDescriptorType */ - 0x01, /* bFirstInterface */ - 0x02, /* bInterfaceCount */ - 0x02, /* bFunctionClass */ - 0x02, /* bFunctionSubClass */ - 0x01, /* bFunctionProtocol */ - 0x00, /* iFunction (Index of string descriptor describing this function) */ - - /*Interface Descriptor */ - 0x09, /* bLength: Interface Descriptor size */ - USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface */ - /* Interface descriptor type */ - CDC_COM_INTERFACE, /* 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 */ - 0x02, /* bDataInterface: 2 */ - - /*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 */ - 0x01, /* bMasterInterface: Communication class interface */ - 0x02, /* 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), - 0xFF, /* bInterval: */ - - /*---------------------------------------------------------------------------*/ - - /*Data class interface descriptor*/ - 0x09, /* bLength: Endpoint Descriptor size */ - USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */ - 0x02, /* 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 */ -}; - -/* USB Standard Device Descriptor */ -__ALIGN_BEGIN static uint8_t USBD_HID_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, -}; - -/* Wrapper related callbacks */ -static uint8_t USBD_HID_CDC_Init (USBD_HandleTypeDef *pdev, uint8_t cfgidx); -static uint8_t USBD_HID_CDC_DeInit (USBD_HandleTypeDef *pdev, uint8_t cfgidx); - -/* Control Endpoints*/ -static uint8_t USBD_HID_CDC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); -static uint8_t USBD_HID_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev); - -/* Class Specific Endpoints*/ -static uint8_t USBD_HID_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum); -static uint8_t USBD_HID_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum); - -static uint8_t *USBD_HID_CDC_GetFSCfgDesc (uint16_t *length); -uint8_t *USBD_HID_CDC_GetDeviceQualifierDescriptor (uint16_t *length); //Will be NULL Callback because it's unused - -/* CDC interface class callbacks structure */ -USBD_ClassTypeDef USBD_HID_CDC = -{ - USBD_HID_CDC_Init, - USBD_HID_CDC_DeInit, - USBD_HID_CDC_Setup, - NULL, /* EP0_TxSent, */ - USBD_HID_CDC_EP0_RxReady, - USBD_HID_CDC_DataIn, - USBD_HID_CDC_DataOut, - NULL, - NULL, - NULL, - NULL, - USBD_HID_CDC_GetFSCfgDesc, - NULL, - USBD_HID_CDC_GetDeviceQualifierDescriptor, -}; - -static uint8_t USBD_HID_CDC_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx) -{ - //Init CDC - USBD_CDC.Init(pdev, cfgidx); - - //Init HID - USBD_HID.Init(pdev, cfgidx); - - return USBD_OK; -} - -static uint8_t USBD_HID_CDC_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx) -{ - //DeInit CDC - USBD_CDC.DeInit(pdev, cfgidx); - - //DeInit HID - USBD_HID.DeInit(pdev, cfgidx); - - return USBD_OK; -} - -static uint8_t USBD_HID_CDC_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req) -{ - switch(req->bmRequest & USB_REQ_RECIPIENT_MASK) { - case USB_REQ_RECIPIENT_INTERFACE: - if (req->wIndex == HID_INTERFACE) { - return USBD_HID.Setup(pdev, req); - } - else { - return USBD_CDC.Setup(pdev, req); - } - break; - case USB_REQ_RECIPIENT_ENDPOINT: - if (req->wIndex == HID_EPIN_ADDR) { - return USBD_HID.Setup(pdev, req); - } else { - return USBD_CDC.Setup(pdev, req); - } - break; - } - - return USBD_OK; -} - -static uint8_t USBD_HID_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev) -{ - return (USBD_CDC.EP0_RxReady(pdev)); -} - -static uint8_t USBD_HID_CDC_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum) -{ - if (epnum == (CDC_IN_EP &~ 0x80)) { - return USBD_CDC.DataIn(pdev, epnum); - } - else { - return USBD_HID.DataIn(pdev, epnum); - } - - return USBD_OK; -} - -static uint8_t USBD_HID_CDC_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum) -{ - if (epnum == (CDC_OUT_EP &~ 0x80)) { - return (USBD_CDC.DataOut(pdev, epnum)); - } - - return USBD_OK; -} - -static uint8_t *USBD_HID_CDC_GetFSCfgDesc (uint16_t *length) -{ - *length = sizeof(USBD_HID_CDC_CfgDesc); - return USBD_HID_CDC_CfgDesc; -} - -uint8_t *USBD_HID_CDC_GetDeviceQualifierDescriptor (uint16_t *length) -{ - *length = sizeof(USBD_HID_CDC_DeviceQualifierDesc); - return USBD_HID_CDC_DeviceQualifierDesc; -} -#endif diff --git a/src/main/vcph7/usbd_cdc_interface.c b/src/main/vcph7/usbd_cdc_interface.c deleted file mode 100644 index e641a8bb1..000000000 --- a/src/main/vcph7/usbd_cdc_interface.c +++ /dev/null @@ -1,479 +0,0 @@ -/** - ****************************************************************************** - * @file USB_Device/CDC_Standalone/Src/usbd_cdc_interface.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-April-2016 - * @brief Source file for USBD CDC interface - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics International N.V. - * All rights reserved.

- * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted, provided that the following conditions are met: - * - * 1. Redistribution of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of other - * contributors to this software may be used to endorse or promote products - * derived from this software without specific written permission. - * 4. This software, including modifications and/or derivative works of this - * software, must execute solely and exclusively on microcontroller or - * microprocessor devices manufactured by or for STMicroelectronics. - * 5. Redistribution and use of this software other than as permitted under - * this license is void and will automatically terminate your rights under - * this license. - * - * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A - * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY - * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT - * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT - * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, - * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF - * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING - * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, - * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ - -#include "platform.h" - -#include "drivers/serial_usb_vcp.h" -#include "drivers/time.h" - -#include "stm32h7xx_hal.h" -#include "usbd_core.h" -#include "usbd_desc.h" -#include "usbd_cdc.h" -#include "usbd_cdc_interface.h" -#include "stdbool.h" - -#include "drivers/nvic.h" -#include "build/atomic.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -#define APP_RX_DATA_SIZE 2048 -#define APP_TX_DATA_SIZE 2048 - -#define APP_TX_BLOCK_SIZE 512 - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -USBD_CDC_LineCodingTypeDef LineCoding = -{ - 115200, /* baud rate*/ - 0x00, /* stop bits-1*/ - 0x00, /* parity - none*/ - 0x08 /* nb. of bits 8*/ -}; - -volatile uint8_t UserRxBuffer[APP_RX_DATA_SIZE];/* Received Data over USB are stored in this buffer */ -volatile uint8_t UserTxBuffer[APP_TX_DATA_SIZE];/* Received Data over UART (CDC interface) are stored in this buffer */ -uint32_t BuffLength; -volatile uint32_t UserTxBufPtrIn = 0;/* Increment this pointer or roll it back to - start address when data are received over USART */ -volatile uint32_t UserTxBufPtrOut = 0; /* Increment this pointer or roll it back to - start address when data are sent over USB */ - -uint32_t rxAvailable = 0; -uint8_t* rxBuffPtr = NULL; - -/* TIM handler declaration */ -TIM_HandleTypeDef TimHandle; - -static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState); -static void *ctrlLineStateCbContext; -static void (*baudRateCb)(void *context, uint32_t baud); -static void *baudRateCbContext; - -/* Private function prototypes -----------------------------------------------*/ -static int8_t CDC_Itf_Init(void); -static int8_t CDC_Itf_DeInit(void); -static int8_t CDC_Itf_Control(uint8_t cmd, uint8_t* pbuf, uint16_t length); -static int8_t CDC_Itf_Receive(uint8_t* pbuf, uint32_t *Len); - -static void TIM_Config(void); -static void Error_Handler(void); - -USBD_CDC_ItfTypeDef USBD_CDC_fops = -{ - CDC_Itf_Init, - CDC_Itf_DeInit, - CDC_Itf_Control, - CDC_Itf_Receive -}; - - -void TIMx_IRQHandler(void) -{ - HAL_TIM_IRQHandler(&TimHandle); -} - -/* Private functions ---------------------------------------------------------*/ - -/** - * @brief CDC_Itf_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 CDC_Itf_Init(void) -{ - /*##-3- Configure the TIM Base generation #################################*/ - TIM_Config(); - - /*##-4- Start the TIM Base generation in interrupt mode ####################*/ - /* Start Channel1 */ - if (HAL_TIM_Base_Start_IT(&TimHandle) != HAL_OK) - { - /* Starting Error */ - Error_Handler(); - } - - /*##-5- Set Application Buffers ############################################*/ - USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t *)UserTxBuffer, 0); - USBD_CDC_SetRxBuffer(&USBD_Device, (uint8_t *)UserRxBuffer); - - ctrlLineStateCb = NULL; - baudRateCb = NULL; - - return (USBD_OK); -} - -/** - * @brief CDC_Itf_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 CDC_Itf_DeInit(void) -{ - - return (USBD_OK); -} - -/** - * @brief CDC_Itf_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 CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length) -{ - LINE_CODING* plc = (LINE_CODING*)pbuf; - - 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: - if (pbuf && (length == sizeof (*plc))) { - LineCoding.bitrate = plc->bitrate; - LineCoding.format = plc->format; - LineCoding.paritytype = plc->paritytype; - LineCoding.datatype = plc->datatype; - - // If a callback is provided, tell the upper driver of changes in baud rate - if (baudRateCb) { - baudRateCb(baudRateCbContext, LineCoding.bitrate); - } - } - - break; - - case CDC_GET_LINE_CODING: - if (pbuf && (length == sizeof (*plc))) { - plc->bitrate = LineCoding.bitrate; - plc->format = LineCoding.format; - plc->paritytype = LineCoding.paritytype; - plc->datatype = LineCoding.datatype; - } - break; - - case CDC_SET_CONTROL_LINE_STATE: - // If a callback is provided, tell the upper driver of changes in DTR/RTS state - if (pbuf && (length == sizeof (uint16_t))) { - if (ctrlLineStateCb) { - ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)pbuf)); - } - } - break; - - case CDC_SEND_BREAK: - /* Add your code here */ - break; - - default: - break; - } - - return (USBD_OK); -} - -/** - * @brief TIM period elapsed callback - * @param htim: TIM handle - * @retval None - */ -void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) -{ - if (htim->Instance != TIMusb) { - return; - } - - uint32_t buffsize; - static uint32_t lastBuffsize = 0; - - USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pCDC_ClassData; - - if (hcdc->TxState == 0) { - // endpoint has finished transmitting previous block - if (lastBuffsize) { - // move the ring buffer tail based on the previous succesful transmission - UserTxBufPtrOut += lastBuffsize; - if (UserTxBufPtrOut == APP_TX_DATA_SIZE) { - UserTxBufPtrOut = 0; - } - lastBuffsize = 0; - } - if (UserTxBufPtrOut != UserTxBufPtrIn) { - if (UserTxBufPtrOut > UserTxBufPtrIn) { /* Roll-back */ - buffsize = APP_TX_DATA_SIZE - UserTxBufPtrOut; - } else { - buffsize = UserTxBufPtrIn - UserTxBufPtrOut; - } - if (buffsize > APP_TX_BLOCK_SIZE) { - buffsize = APP_TX_BLOCK_SIZE; - } - - USBD_CDC_SetTxBuffer(&USBD_Device, (uint8_t*)&UserTxBuffer[UserTxBufPtrOut], buffsize); - - if (USBD_CDC_TransmitPacket(&USBD_Device) == USBD_OK) { - lastBuffsize = buffsize; - } - } - } -} - -/** - * @brief CDC_Itf_DataRx - * Data received over USB OUT endpoint are sent over CDC 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_Itf_Receive(uint8_t* Buf, uint32_t *Len) -{ - rxAvailable = *Len; - rxBuffPtr = Buf; - return (USBD_OK); -} - -/** - * @brief TIM_Config: Configure TIMusb timer - * @param None. - * @retval None - */ -static void TIM_Config(void) -{ - /* Set TIMusb instance */ - TimHandle.Instance = TIMusb; - - /* Initialize TIMx peripheral as follow: - + Period = 10000 - 1 - + Prescaler = ((SystemCoreClock/2)/10000) - 1 - + ClockDivision = 0 - + Counter direction = Up - */ - TimHandle.Init.Period = (CDC_POLLING_INTERVAL*1000) - 1; - TimHandle.Init.Prescaler = (SystemCoreClock / 2 / (1000000)) - 1; - TimHandle.Init.ClockDivision = 0; - TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; - if (HAL_TIM_Base_Init(&TimHandle) != HAL_OK) - { - /* Initialization Error */ - Error_Handler(); - } - - /*##-6- Enable TIM peripherals Clock #######################################*/ - TIMx_CLK_ENABLE(); - - /*##-7- Configure the NVIC for TIMx ########################################*/ - /* Set Interrupt Group Priority */ - HAL_NVIC_SetPriority(TIMx_IRQn, 6, 0); - - /* Enable the TIMx global Interrupt */ - HAL_NVIC_EnableIRQ(TIMx_IRQn); -} - -/** - * @brief This function is executed in case of error occurrence. - * @param None - * @retval None - */ -static void Error_Handler(void) -{ - /* Add your own code here */ -} - -uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len) -{ - uint32_t count = 0; - if ( (rxBuffPtr != NULL)) - { - while ((rxAvailable > 0) && count < len) - { - recvBuf[count] = rxBuffPtr[0]; - rxBuffPtr++; - rxAvailable--; - count++; - if (rxAvailable < 1) - USBD_CDC_ReceivePacket(&USBD_Device); - } - } - return count; -} - -uint32_t CDC_Receive_BytesAvailable(void) -{ - return rxAvailable; -} - -uint32_t CDC_Send_FreeBytes(void) -{ - /* - return the bytes free in the circular buffer - - functionally equivalent to: - (APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in) - but without the impact of the condition check. - */ - uint32_t freeBytes; - - ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) { - freeBytes = ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1; - } - - return freeBytes; -} - -/** - * @brief CDC_Send_DATA - * CDC received data to be send over USB IN endpoint are managed in - * this function. - * @param ptrBuffer: Buffer of data to be sent - * @param sendLength: Number of data to be sent (in bytes) - * @retval Bytes sent - */ -uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength) -{ - for (uint32_t i = 0; i < sendLength; i++) { - while (CDC_Send_FreeBytes() == 0) { - // block until there is free space in the ring buffer - delay(1); - } - ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) { // Paranoia - UserTxBuffer[UserTxBufPtrIn] = ptrBuffer[i]; - UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE; - } - } - return sendLength; -} - - -/******************************************************************************* - * Function Name : usbIsConfigured. - * Description : Determines if USB VCP is configured or not - * Input : None. - * Output : None. - * Return : True if configured. - *******************************************************************************/ -uint8_t usbIsConfigured(void) -{ - return (USBD_Device.dev_state == USBD_STATE_CONFIGURED); -} - -/******************************************************************************* - * Function Name : usbIsConnected. - * Description : Determines if USB VCP is connected ot not - * Input : None. - * Output : None. - * Return : True if connected. - *******************************************************************************/ -uint8_t usbIsConnected(void) -{ - return (USBD_Device.dev_state != USBD_STATE_DEFAULT); -} - -/******************************************************************************* - * Function Name : CDC_BaudRate. - * Description : Get the current baud rate - * Input : None. - * Output : None. - * Return : Baud rate in bps - *******************************************************************************/ -uint32_t CDC_BaudRate(void) -{ - return LineCoding.bitrate; -} - -/******************************************************************************* - * Function Name : CDC_SetBaudRateCb - * Description : Set a callback to call when baud rate changes - * Input : callback function and context. - * Output : None. - * Return : None. - *******************************************************************************/ -void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context) -{ - baudRateCbContext = context; - baudRateCb = cb; -} - -/******************************************************************************* - * Function Name : CDC_SetCtrlLineStateCb - * Description : Set a callback to call when control line state changes - * Input : callback function and context. - * Output : None. - * Return : None. - *******************************************************************************/ -void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context) -{ - ctrlLineStateCbContext = context; - ctrlLineStateCb = cb; -} - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcph7/usbd_cdc_interface.h b/src/main/vcph7/usbd_cdc_interface.h deleted file mode 100644 index a9d592981..000000000 --- a/src/main/vcph7/usbd_cdc_interface.h +++ /dev/null @@ -1,98 +0,0 @@ -/** - ****************************************************************************** - * @file USB_Device/CDC_Standalone/Inc/usbd_cdc_interface.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-April-2016 - * @brief Header for usbd_cdc_interface.c file. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics International N.V. - * All rights reserved.

- * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted, provided that the following conditions are met: - * - * 1. Redistribution of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of other - * contributors to this software may be used to endorse or promote products - * derived from this software without specific written permission. - * 4. This software, including modifications and/or derivative works of this - * software, must execute solely and exclusively on microcontroller or - * microprocessor devices manufactured by or for STMicroelectronics. - * 5. Redistribution and use of this software other than as permitted under - * this license is void and will automatically terminate your rights under - * this license. - * - * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A - * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY - * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT - * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT - * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, - * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF - * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING - * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, - * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USBD_CDC_IF_H -#define __USBD_CDC_IF_H - -/* Includes ------------------------------------------------------------------*/ -//#include "common/maths.h" - -#include "usbd_cdc.h" -#include "stm32h7xx_hal.h" -#include "usbd_core.h" -#include "usbd_desc.h" - -/* Definition for TIMx clock resources */ -#define TIMusb TIM7 -#define TIMx_IRQn TIM7_IRQn -#define TIMx_IRQHandler TIM7_IRQHandler -#define TIMx_CLK_ENABLE __HAL_RCC_TIM7_CLK_ENABLE - -/* Periodically, the state of the buffer "UserTxBuffer" is checked. - The period depends on CDC_POLLING_INTERVAL */ -#define CDC_POLLING_INTERVAL 5 /* in ms. The max is 65 and the min is 1 */ - -/* Exported typef ------------------------------------------------------------*/ -/* The following structures groups all needed parameters to be configured for the - ComPort. These parameters can modified on the fly by the host through CDC class - command class requests. */ -typedef struct __attribute__ ((packed)) -{ - uint32_t bitrate; - uint8_t format; - uint8_t paritytype; - uint8_t datatype; -} LINE_CODING; - -extern USBD_CDC_ItfTypeDef USBD_CDC_fops; - -uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength); -uint32_t CDC_Send_FreeBytes(void); -uint32_t CDC_Receive_DATA(uint8_t* recvBuf, uint32_t len); -uint32_t CDC_Receive_BytesAvailable(void); -uint8_t usbIsConfigured(void); -uint8_t usbIsConnected(void); -uint32_t CDC_BaudRate(void); -void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context); -void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context); - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -#endif /* __USBD_CDC_IF_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcph7/usbd_conf.h b/src/main/vcph7/usbd_conf.h deleted file mode 100644 index ec2b16ef1..000000000 --- a/src/main/vcph7/usbd_conf.h +++ /dev/null @@ -1,113 +0,0 @@ -/** - ****************************************************************************** - * @file USB_Device/CDC_Standalone/Inc/usbd_conf.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-April-2016 - * @brief General low level driver configuration - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics International N.V. - * All rights reserved.

- * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted, provided that the following conditions are met: - * - * 1. Redistribution of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of other - * contributors to this software may be used to endorse or promote products - * derived from this software without specific written permission. - * 4. This software, including modifications and/or derivative works of this - * software, must execute solely and exclusively on microcontroller or - * microprocessor devices manufactured by or for STMicroelectronics. - * 5. Redistribution and use of this software other than as permitted under - * this license is void and will automatically terminate your rights under - * this license. - * - * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A - * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY - * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT - * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT - * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, - * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF - * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING - * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, - * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USBD_CONF_H -#define __USBD_CONF_H - -/* Includes ------------------------------------------------------------------*/ -#include "common/maths.h" // For MIN and MAX -#include "stm32h7xx_hal.h" - -#if (USBD_DEBUG_LEVEL > 0) -#include -#endif - -#include -#include - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -#define USE_USB_FS - -/* Common Config */ -#define USBD_MAX_NUM_INTERFACES 3 -#define USBD_MAX_NUM_CONFIGURATION 1 -#define USBD_MAX_STR_DESC_SIZ 0x100 -#define USBD_SUPPORT_USER_STRING 0 -#define USBD_SELF_POWERED 1 -#define USBD_DEBUG_LEVEL 0 -#define MSC_MEDIA_PACKET 512 - -/* Exported macro ------------------------------------------------------------*/ -/* Memory management macros */ -#define USBD_malloc malloc -#define USBD_free free -#define USBD_memset memset -#define USBD_memcpy memcpy - -/* DEBUG macros */ -#if (USBD_DEBUG_LEVEL > 0) -#define USBD_UsrLog(...) printf(__VA_ARGS__);\ - printf("\n"); -#else -#define USBD_UsrLog(...) -#endif - -#if (USBD_DEBUG_LEVEL > 1) - -#define USBD_ErrLog(...) printf("ERROR: ") ;\ - printf(__VA_ARGS__);\ - printf("\n"); -#else -#define USBD_ErrLog(...) -#endif - -#if (USBD_DEBUG_LEVEL > 2) -#define USBD_DbgLog(...) printf("DEBUG : ") ;\ - printf(__VA_ARGS__);\ - printf("\n"); -#else -#define USBD_DbgLog(...) -#endif - -/* Exported functions ------------------------------------------------------- */ - -#endif /* __USBD_CONF_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcph7/usbd_desc.c b/src/main/vcph7/usbd_desc.c deleted file mode 100644 index bd0a94ba3..000000000 --- a/src/main/vcph7/usbd_desc.c +++ /dev/null @@ -1,354 +0,0 @@ -/** - ****************************************************************************** - * @file USB_Device/CDC_Standalone/Src/usbd_desc.c - * @author MCD Application Team - * @version V1.0.0 - * @date 22-April-2016 - * @brief This file provides the USBD descriptors and string formating method. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics International N.V. - * All rights reserved.

- * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted, provided that the following conditions are met: - * - * 1. Redistribution of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of other - * contributors to this software may be used to endorse or promote products - * derived from this software without specific written permission. - * 4. This software, including modifications and/or derivative works of this - * software, must execute solely and exclusively on microcontroller or - * microprocessor devices manufactured by or for STMicroelectronics. - * 5. Redistribution and use of this software other than as permitted under - * this license is void and will automatically terminate your rights under - * this license. - * - * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A - * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY - * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT - * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT - * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, - * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF - * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING - * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, - * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_core.h" -#include "usbd_desc.h" -#include "usbd_conf.h" -#include "platform.h" -#include "build/version.h" - -#include "pg/pg.h" -#include "pg/usb.h" -#ifdef USE_USB_MSC -#include "drivers/usb_msc.h" -#endif - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -#define USBD_VID 0x0483 -#define USBD_PID 0x5740 -#define USBD_LANGID_STRING 0x409 -#define USBD_MANUFACTURER_STRING FC_FIRMWARE_NAME -#define USBD_PRODUCT_HS_STRING "STM32 Virtual ComPort in HS Mode" -#define USBD_PRODUCT_FS_STRING "STM32 Virtual ComPort in FS Mode" -#define USBD_CONFIGURATION_HS_STRING "VCP Config" -#define USBD_INTERFACE_HS_STRING "VCP Interface" -#define USBD_CONFIGURATION_FS_STRING "VCP Config" -#define USBD_INTERFACE_FS_STRING "VCP Interface" - -/* Private macro -------------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); -uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); -uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); -uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); -uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); -uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); -uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); -#ifdef USB_SUPPORT_USER_STRING_DESC -uint8_t *USBD_VCP_USRStringDesc (USBD_SpeedTypeDef speed, uint8_t idx, uint16_t *length); -#endif /* USB_SUPPORT_USER_STRING_DESC */ - -/* Private variables ---------------------------------------------------------*/ -USBD_DescriptorsTypeDef VCP_Desc = { - USBD_VCP_DeviceDescriptor, - USBD_VCP_LangIDStrDescriptor, - USBD_VCP_ManufacturerStrDescriptor, - USBD_VCP_ProductStrDescriptor, - USBD_VCP_SerialStrDescriptor, - USBD_VCP_ConfigStrDescriptor, - USBD_VCP_InterfaceStrDescriptor, -}; - -/* USB Standard Device Descriptor */ -#if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 -#endif -__ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = { - 0x12, /* bLength */ - USB_DESC_TYPE_DEVICE, /* bDescriptorType */ - 0x00, /* bcdUSB */ - 0x02, - 0x02, /* bDeviceClass */ - 0x00, /* bDeviceSubClass */ - 0x00, /* bDeviceProtocol */ - USB_MAX_EP0_SIZE, /* bMaxPacketSize */ - LOBYTE(USBD_VID), /* idVendor */ - HIBYTE(USBD_VID), /* idVendor */ - LOBYTE(USBD_PID), /* idVendor */ - HIBYTE(USBD_PID), /* idVendor */ - 0x00, /* bcdDevice rel. 2.00 */ - 0x02, - USBD_IDX_MFC_STR, /* Index of manufacturer string */ - USBD_IDX_PRODUCT_STR, /* Index of product string */ - USBD_IDX_SERIAL_STR, /* Index of serial number string */ - USBD_MAX_NUM_CONFIGURATION /* bNumConfigurations */ -}; /* USB_DeviceDescriptor */ - -#ifdef USE_USB_CDC_HID -extern uint8_t USBD_HID_CDC_DeviceDescriptor[USB_LEN_DEV_DESC]; -#endif - -#ifdef USE_USB_MSC - -#define USBD_PID_MSC 22314 - -__ALIGN_BEGIN uint8_t USBD_MSC_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = -{ - 0x12, /*bLength */ - USB_DESC_TYPE_DEVICE, /*bDescriptorType*/ - 0x00, /*bcdUSB */ - 0x02, - 0x00, /*bDeviceClass*/ - 0x00, /*bDeviceSubClass*/ - 0x00, /*bDeviceProtocol*/ - USB_MAX_EP0_SIZE, /*bMaxPacketSize*/ - LOBYTE(USBD_VID), /*idVendor*/ - HIBYTE(USBD_VID), /*idVendor*/ - LOBYTE(USBD_PID_MSC), /*idProduct*/ - HIBYTE(USBD_PID_MSC), /*idProduct*/ - 0x00, /*bcdDevice rel. 2.00*/ - 0x02, - USBD_IDX_MFC_STR, /*Index of manufacturer string*/ - USBD_IDX_PRODUCT_STR, /*Index of product string*/ - USBD_IDX_SERIAL_STR, /*Index of serial number string*/ - USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/ -}; -#endif - -/* USB Standard Device Descriptor */ -#if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 -#endif -__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_LEN_LANGID_STR_DESC] __ALIGN_END = { - USB_LEN_LANGID_STR_DESC, - USB_DESC_TYPE_STRING, - LOBYTE(USBD_LANGID_STRING), - HIBYTE(USBD_LANGID_STRING), -}; - -uint8_t USBD_StringSerial[USB_SIZ_STRING_SERIAL] = -{ - USB_SIZ_STRING_SERIAL, - USB_DESC_TYPE_STRING, -}; - -#if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 -#endif -__ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END; - -/* Private functions ---------------------------------------------------------*/ -static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len); -static void Get_SerialNum(void); - -/** - * @brief Returns the device descriptor. - * @param speed: Current device speed - * @param length: Pointer to data length variable - * @retval Pointer to descriptor buffer - */ -uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) -{ - (void)speed; -#ifdef USE_USB_MSC - if (mscCheckBoot()) { - *length = sizeof(USBD_MSC_DeviceDesc); - return USBD_MSC_DeviceDesc; - } -#endif -#ifdef USE_USB_CDC_HID - if (usbDevConfig()->type == COMPOSITE) { - *length = sizeof(USBD_HID_CDC_DeviceDescriptor); - return USBD_HID_CDC_DeviceDescriptor; - } -#endif - *length = sizeof(USBD_DeviceDesc); - return (uint8_t*)USBD_DeviceDesc; -} - -/** - * @brief Returns the LangID string descriptor. - * @param speed: Current device speed - * @param length: Pointer to data length variable - * @retval Pointer to descriptor buffer - */ -uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) -{ - (void)speed; - *length = sizeof(USBD_LangIDDesc); - return (uint8_t*)USBD_LangIDDesc; -} - -/** - * @brief Returns the product string descriptor. - * @param speed: Current device speed - * @param length: Pointer to data length variable - * @retval Pointer to descriptor buffer - */ -uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) -{ - if (speed == USBD_SPEED_HIGH) - { - USBD_GetString((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length); - } - else - { - USBD_GetString((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length); - } - return USBD_StrDesc; -} - -/** - * @brief Returns the manufacturer string descriptor. - * @param speed: Current device speed - * @param length: Pointer to data length variable - * @retval Pointer to descriptor buffer - */ -uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) -{ - (void)speed; - USBD_GetString((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length); - return USBD_StrDesc; -} - -/** - * @brief Returns the serial number string descriptor. - * @param speed: Current device speed - * @param length: Pointer to data length variable - * @retval Pointer to descriptor buffer - */ -uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) -{ - (void)speed; - *length = USB_SIZ_STRING_SERIAL; - - /* Update the serial number string descriptor with the data from the unique ID*/ - Get_SerialNum(); - - return (uint8_t*)USBD_StringSerial; -} - -/** - * @brief Returns the configuration string descriptor. - * @param speed: Current device speed - * @param length: Pointer to data length variable - * @retval Pointer to descriptor buffer - */ -uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) -{ - if (speed == USBD_SPEED_HIGH) - { - USBD_GetString((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length); - } - else - { - USBD_GetString((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length); - } - return USBD_StrDesc; -} - -/** - * @brief Returns the interface string descriptor. - * @param speed: Current device speed - * @param length: Pointer to data length variable - * @retval Pointer to descriptor buffer - */ -uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) -{ - if (speed == USBD_SPEED_HIGH) - { - USBD_GetString((uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length); - } - else - { - USBD_GetString((uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length); - } - return USBD_StrDesc; -} - -/** - * @brief Create the serial number string descriptor - * @param None - * @retval None - */ -static void Get_SerialNum(void) -{ - uint32_t deviceserial0, deviceserial1, deviceserial2; - - deviceserial0 = U_ID_0; - deviceserial1 = U_ID_1; - deviceserial2 = U_ID_2; - - deviceserial0 += deviceserial2; - - if (deviceserial0 != 0) - { - IntToUnicode (deviceserial0, &USBD_StringSerial[2] ,8); - IntToUnicode (deviceserial1, &USBD_StringSerial[18] ,4); - } -} - -/** - * @brief Convert Hex 32Bits value into char - * @param value: value to convert - * @param pbuf: pointer to the buffer - * @param len: buffer length - * @retval None - */ -static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len) -{ - uint8_t idx = 0; - - for ( idx = 0; idx < len; idx ++) - { - if ( ((value >> 28)) < 0xA ) - { - pbuf[ 2* idx] = (value >> 28) + '0'; - } - else - { - pbuf[2* idx] = (value >> 28) + 'A' - 10; - } - - value = value << 4; - - pbuf[ 2* idx + 1] = 0; - } -} -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcph7/usbd_desc.h b/src/main/vcph7/usbd_desc.h deleted file mode 100644 index 3baad094f..000000000 --- a/src/main/vcph7/usbd_desc.h +++ /dev/null @@ -1,65 +0,0 @@ -/** - ****************************************************************************** - * @file USB_Device/CDC_Standalone/Inc/usbd_desc.h - * @author MCD Application Team - * @version V1.0.0 - * @date 22-April-2016 - * @brief Header for usbd_desc.c module - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics International N.V. - * All rights reserved.

- * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted, provided that the following conditions are met: - * - * 1. Redistribution of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of other - * contributors to this software may be used to endorse or promote products - * derived from this software without specific written permission. - * 4. This software, including modifications and/or derivative works of this - * software, must execute solely and exclusively on microcontroller or - * microprocessor devices manufactured by or for STMicroelectronics. - * 5. Redistribution and use of this software other than as permitted under - * this license is void and will automatically terminate your rights under - * this license. - * - * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A - * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY - * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT - * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT - * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, - * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF - * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING - * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, - * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USBD_DESC_H -#define __USBD_DESC_H - -/* Includes ------------------------------------------------------------------*/ -#include "usbd_def.h" - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -#define USB_SIZ_STRING_SERIAL 0x1A -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -extern USBD_DescriptorsTypeDef VCP_Desc; - -#endif /* __USBD_DESC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/