1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

Add CDC+HID on F7 (#5596)

This commit is contained in:
conkerkh 2018-04-02 04:35:51 +02:00 committed by Michael Keller
parent c091fa8e48
commit a9136e2ba0
19 changed files with 1211 additions and 779 deletions

View file

@ -39,6 +39,11 @@
#elif defined(STM32F7)
#include "vcp_hal/usbd_cdc_interface.h"
#include "usb_io.h"
#ifdef USE_USB_CDC_HID
#include "usbd_cdc_hid.h"
#include "pg/pg.h"
#include "pg/usb.h"
#endif
USBD_HandleTypeDef USBD_Device;
#else
#include "usb_core.h"
@ -234,8 +239,16 @@ serialPort_t *usbVcpOpen(void)
USBD_Init(&USBD_Device, &VCP_Desc, 0);
/* Add Supported Class */
USBD_RegisterClass(&USBD_Device, USBD_CDC_CLASS);
#ifdef USE_USB_CDC_HID
if (usbDevConfig()->type == COMPOSITE) {
USBD_RegisterClass(&USBD_Device, USBD_HID_CDC_CLASS);
} else
#endif
{
USBD_RegisterClass(&USBD_Device, USBD_CDC_CLASS);
}
/* HID Interface doesn't have any callbacks... */
/* Add CDC Interface Class */
USBD_CDC_RegisterInterface(&USBD_Device, &USBD_CDC_fops);

View file

@ -87,8 +87,13 @@
#ifdef USE_USB_CDC_HID
//TODO: Make it platform independent in the future
#ifdef STM32F4
#include "vcpf4/usbd_cdc_vcp.h"
#include "usbd_hid_core.h"
#elif defined(STM32F7)
#include "usbd_cdc_interface.h"
#include "usbd_hid.h"
#endif
#endif
#ifdef USE_BST
@ -151,7 +156,12 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs)
for (int i = 0; i < 8; i++) {
report[i] = scaleRange(constrain(rcData[i], 1000, 2000), 1000, 2000, -127, 127);
}
#ifdef STM32F4
USBD_HID_SendReport(&USB_OTG_dev, (uint8_t*)report, sizeof(report));
#elif defined(STM32F7)
extern USBD_HandleTypeDef USBD_Device;
USBD_HID_SendReport(&USBD_Device, (uint8_t*)report, sizeof(report));
#endif
}
#endif

View file

@ -107,6 +107,10 @@
#undef USE_USB_MSC
#endif
#if !defined(USE_VCP)
#undef USE_USB_CDC_HID
#endif
#if defined(USE_USB_CDC_HID) || defined(USE_USB_MSC)
#define USE_USB_ADVANCED_PROFILES
#endif

View file

@ -69,6 +69,7 @@
#define USE_GYRO_DATA_ANALYSE
#define USE_OVERCLOCK
#define USE_ADC_INTERNAL
#define USE_USB_CDC_HID
#endif
#if defined(STM32F4) || defined(STM32F7)

View file

@ -379,7 +379,7 @@ uint32_t CDC_Send_FreeBytes(void)
*/
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
{
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pClassData;
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pCDC_ClassData;
while (hcdc->TxState != 0);
for (uint32_t i = 0; i < sendLength; i++)

View file

@ -53,6 +53,10 @@
#include "usbd_conf.h"
#include "usbd_cdc_interface.h"
#include "platform.h"
#include "pg/pg.h"
#include "pg/usb.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
@ -402,9 +406,21 @@ USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev)
/* Initialize LL Driver */
HAL_PCD_Init(&hpcd);
#ifdef USE_USB_CDC_HID
if (usbDevConfig()->type == COMPOSITE) {
HAL_PCDEx_SetRxFiFo(&hpcd, 0x80);
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x20);
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x40);
HAL_PCDEx_SetTxFiFo(&hpcd, 2, 0x20);
HAL_PCDEx_SetTxFiFo(&hpcd, 3, 0x40);
} else {
#endif /* CDC_HID */
HAL_PCDEx_SetRxFiFo(&hpcd, 0x80);
HAL_PCDEx_SetTxFiFo(&hpcd, 0, 0x40);
HAL_PCDEx_SetTxFiFo(&hpcd, 1, 0x80);
#ifdef USE_USB_CDC_HID
}
#endif /* CDC_HID */
#endif
#ifdef USE_USB_HS

View file

@ -60,12 +60,13 @@
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Common Config */
#define USBD_MAX_NUM_INTERFACES 0
#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
#define USE_USB_FS
/* Exported macro ------------------------------------------------------------*/

View file

@ -52,6 +52,8 @@
#include "platform.h"
#include "build/version.h"
#include "pg/pg.h"
#include "pg/usb.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
#define USBD_VID 0x0483
@ -114,6 +116,10 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = {
USBD_MAX_NUM_CONFIGURATION /* bNumConfigurations */
}; /* USB_DeviceDescriptor */
#ifdef USE_USB_CDC_HID
extern uint8_t USBD_HID_CDC_DeviceDescriptor[USB_LEN_DEV_DESC];
#endif
/* USB Standard Device Descriptor */
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma data_alignment=4
@ -149,6 +155,12 @@ static void Get_SerialNum(void);
uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
{
(void)speed;
#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;
}