diff --git a/make/source.mk b/make/source.mk index 4a80c8e5b4..9c074650ed 100644 --- a/make/source.mk +++ b/make/source.mk @@ -51,6 +51,7 @@ COMMON_SRC = \ io/serial.c \ io/statusindicator.c \ io/transponder_ir.c \ + io/usb_cdc_hid.c \ msp/msp_serial.c \ scheduler/scheduler.c \ sensors/adcinternal.c \ @@ -297,6 +298,7 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ io/serial_4way_avrootloader.c \ io/serial_4way_stk500v2.c \ io/transponder_ir.c \ + io/usb_cdc_hid.c \ msp/msp_serial.c \ cms/cms.c \ cms/cms_menu_blackbox.c \ diff --git a/src/main/drivers/serial_usb_vcp.h b/src/main/drivers/serial_usb_vcp.h index daeaa2ce22..29b7096d27 100644 --- a/src/main/drivers/serial_usb_vcp.h +++ b/src/main/drivers/serial_usb_vcp.h @@ -22,6 +22,12 @@ #include "drivers/serial.h" +#if defined(STM32F7) +#include "usbd_cdc.h" + +extern USBD_HandleTypeDef USBD_Device; +#endif + typedef struct { serialPort_t port; diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 4b781fc0a8..cf52d8bf3e 100644 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -69,6 +69,7 @@ #include "io/transponder_ir.h" #include "io/vtx_tramp.h" // Will be gone #include "io/rcdevice_cam.h" +#include "io/usb_cdc_hid.h" #include "io/vtx.h" #include "msp/msp_serial.h" @@ -91,17 +92,6 @@ #include "telemetry/telemetry.h" -#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 void taskBstMasterProcess(timeUs_t currentTimeUs); #endif @@ -161,16 +151,7 @@ static void taskUpdateRxMain(timeUs_t currentTimeUs) #ifdef USE_USB_CDC_HID if (!ARMING_FLAG(ARMED)) { - int8_t report[8]; - 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 + sendRcDataToHid(); } #endif diff --git a/src/main/io/usb_cdc_hid.c b/src/main/io/usb_cdc_hid.c new file mode 100644 index 0000000000..48b6edf156 --- /dev/null +++ b/src/main/io/usb_cdc_hid.c @@ -0,0 +1,81 @@ +/* + * 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 . + */ + +#include "platform.h" + +#ifdef USE_USB_CDC_HID + +#include "common/maths.h" + +#include "fc/rc_controls.h" + +#include "rx/rx.h" + +//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) +#include "drivers/serial_usb_vcp.h" + +#include "vcp_hal/usbd_cdc_interface.h" + +#include "usbd_hid.h" +#endif + +#define USB_CDC_HID_NUM_AXES 8 + +#define USB_CDC_HID_RANGE_MIN -127 +#define USB_CDC_HID_RANGE_MAX 127 + +// In the windows joystick driver, the axes are defined as shown in the second column. + +const uint8_t hidChannelMapping[] = { + ROLL, // X + PITCH, // Y + AUX3, + YAW, // X Rotation + AUX1, // Z Rotation + THROTTLE, // Y Rotation + AUX4, + AUX2, // Wheel +}; + +void sendRcDataToHid(void) +{ + int8_t report[8]; + for (unsigned i = 0; i < USB_CDC_HID_NUM_AXES; i++) { + const uint8_t channel = hidChannelMapping[i]; + report[i] = scaleRange(constrain(rcData[channel], PWM_RANGE_MIN, PWM_RANGE_MAX), PWM_RANGE_MIN, PWM_RANGE_MAX, USB_CDC_HID_RANGE_MIN, USB_CDC_HID_RANGE_MAX); + if (i == 1) { + // For some reason ROLL is inverted in Windows + report[i] = -report[i]; + } + } +#if defined(STM32F4) + USBD_HID_SendReport(&USB_OTG_dev, (uint8_t*)report, sizeof(report)); +#elif defined(STM32F7) + USBD_HID_SendReport(&USBD_Device, (uint8_t*)report, sizeof(report)); +#else +# error "MCU does not support USB HID." +#endif +} +#endif diff --git a/src/main/io/usb_cdc_hid.h b/src/main/io/usb_cdc_hid.h new file mode 100644 index 0000000000..ff0b538862 --- /dev/null +++ b/src/main/io/usb_cdc_hid.h @@ -0,0 +1,23 @@ +/* + * 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 . + */ + +#pragma once + +void sendRcDataToHid(void); diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index cabe221433..678479e3fa 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -173,4 +173,3 @@ void suspendRxSignal(void); void resumeRxSignal(void); uint16_t rxGetRefreshRate(void); - diff --git a/src/main/vcp_hal/usbd_cdc_interface.c b/src/main/vcp_hal/usbd_cdc_interface.c index fd9388f7d2..5a4b3a6d48 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.c +++ b/src/main/vcp_hal/usbd_cdc_interface.c @@ -52,6 +52,8 @@ #include "usbd_cdc.h" #include "usbd_cdc_interface.h" #include "stdbool.h" + +#include "drivers/serial_usb_vcp.h" #include "drivers/time.h" /* Private typedef -----------------------------------------------------------*/ @@ -82,8 +84,6 @@ uint8_t* rxBuffPtr = NULL; /* TIM handler declaration */ TIM_HandleTypeDef TimHandle; -/* USB handler declaration */ -extern USBD_HandleTypeDef USBD_Device; static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState); static void *ctrlLineStateCbContext;