From 444e5c43a54facc7c5ec348fbba3be424783df35 Mon Sep 17 00:00:00 2001 From: mikeller Date: Wed, 13 Jun 2018 01:32:29 +1200 Subject: [PATCH 1/6] Fixed USB HID channel mapping in Windows. --- make/source.mk | 2 ++ src/main/fc/fc_tasks.c | 23 ++----------- src/main/io/usb_cdc_hid.c | 70 +++++++++++++++++++++++++++++++++++++++ src/main/io/usb_cdc_hid.h | 23 +++++++++++++ src/main/rx/rx.c | 7 +++- src/main/rx/rx.h | 1 + 6 files changed, 104 insertions(+), 22 deletions(-) create mode 100644 src/main/io/usb_cdc_hid.c create mode 100644 src/main/io/usb_cdc_hid.h 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/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..d4c6957114 --- /dev/null +++ b/src/main/io/usb_cdc_hid.c @@ -0,0 +1,70 @@ +/* + * 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 "rx/rx.h" + +//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 + +#define USB_CDC_HID_NUM_AXES 8 + +// In the windows joystick driver, the axes are defined as shown in the third column. + +const uint8_t hidChannelMapping[] = { + 0, // X, ROLL + 1, // Y, PITCH + 6, // , AUX3 + 3, // Y Rotation, THROTTLE + 4, // Z Rotation, AUX1 + 2, // X Rotation, YAW + 7, // , AUX4 + 5, // Wheel, AUX2 +}; + +void sendRcDataToHid(void) +{ + int8_t report[8]; + for (unsigned i = 0; i < USB_CDC_HID_NUM_AXES; i++) { + const uint8_t channel = getMappedChannel(hidChannelMapping[i]); + report[i] = scaleRange(constrain(rcData[channel], 1000, 2000), 1000, 2000, -127, 127); + if (i == 1 || i == 2) { + report[i] = -report[i]; + } + } +#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 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.c b/src/main/rx/rx.c index f565249d84..37175eb6ab 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -466,11 +466,16 @@ STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, const rx return sample; } +uint8_t getMappedChannel(uint8_t channel) +{ + return channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel; +} + static void readRxChannelsApplyRanges(void) { for (int channel = 0; channel < rxChannelCount; channel++) { - const uint8_t rawChannel = channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel; + const uint8_t rawChannel = getMappedChannel(channel); // sample the channel uint16_t sample = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, rawChannel); diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index cabe221433..2b843e7ae5 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -174,3 +174,4 @@ void resumeRxSignal(void); uint16_t rxGetRefreshRate(void); +uint8_t getMappedChannel(uint8_t channel); From 48ed3d0b15297c2299ca1e253a8adc38d3d0a39e Mon Sep 17 00:00:00 2001 From: mikeller Date: Wed, 13 Jun 2018 23:51:26 +1200 Subject: [PATCH 2/6] Fixes from review. --- src/main/io/usb_cdc_hid.c | 38 ++++++++++++++++----------- src/main/rx/rx.c | 2 +- src/main/rx/rx.h | 2 -- src/main/vcp_hal/usbd_cdc_interface.c | 3 +-- 4 files changed, 25 insertions(+), 20 deletions(-) diff --git a/src/main/io/usb_cdc_hid.c b/src/main/io/usb_cdc_hid.c index d4c6957114..695dedf466 100644 --- a/src/main/io/usb_cdc_hid.c +++ b/src/main/io/usb_cdc_hid.c @@ -24,6 +24,8 @@ #include "common/maths.h" +#include "fc/rc_controls.h" + #include "rx/rx.h" //TODO: Make it platform independent in the future @@ -32,39 +34,45 @@ #include "usbd_hid_core.h" #elif defined(STM32F7) #include "usbd_cdc_interface.h" +#include "usbd_def.h" #include "usbd_hid.h" #endif #define USB_CDC_HID_NUM_AXES 8 -// In the windows joystick driver, the axes are defined as shown in the third column. +#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[] = { - 0, // X, ROLL - 1, // Y, PITCH - 6, // , AUX3 - 3, // Y Rotation, THROTTLE - 4, // Z Rotation, AUX1 - 2, // X Rotation, YAW - 7, // , AUX4 - 5, // Wheel, AUX2 + 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 = getMappedChannel(hidChannelMapping[i]); - report[i] = scaleRange(constrain(rcData[channel], 1000, 2000), 1000, 2000, -127, 127); - if (i == 1 || i == 2) { - report[i] = -report[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]; + } } #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)); +#else +# error "MCU does not support USB HID." #endif } #endif diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 37175eb6ab..3aace0da3c 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -466,7 +466,7 @@ STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, const rx return sample; } -uint8_t getMappedChannel(uint8_t channel) +static uint8_t getMappedChannel(uint8_t channel) { return channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel; } diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 2b843e7ae5..678479e3fa 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -173,5 +173,3 @@ void suspendRxSignal(void); void resumeRxSignal(void); uint16_t rxGetRefreshRate(void); - -uint8_t getMappedChannel(uint8_t channel); diff --git a/src/main/vcp_hal/usbd_cdc_interface.c b/src/main/vcp_hal/usbd_cdc_interface.c index fd9388f7d2..8397394303 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.c +++ b/src/main/vcp_hal/usbd_cdc_interface.c @@ -48,6 +48,7 @@ /* Includes ------------------------------------------------------------------*/ #include "stm32f7xx_hal.h" #include "usbd_core.h" +#include "usbd_def.h" #include "usbd_desc.h" #include "usbd_cdc.h" #include "usbd_cdc_interface.h" @@ -82,8 +83,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; From 39a38fd9515402d5b38bfc6138f54b2141c59b3d Mon Sep 17 00:00:00 2001 From: mikeller Date: Thu, 14 Jun 2018 00:51:36 +1200 Subject: [PATCH 3/6] Fixes from review. --- src/main/rx/rx.c | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 3aace0da3c..f565249d84 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -466,16 +466,11 @@ STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, const rx return sample; } -static uint8_t getMappedChannel(uint8_t channel) -{ - return channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel; -} - static void readRxChannelsApplyRanges(void) { for (int channel = 0; channel < rxChannelCount; channel++) { - const uint8_t rawChannel = getMappedChannel(channel); + const uint8_t rawChannel = channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel; // sample the channel uint16_t sample = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, rawChannel); From 24bbb524f67aa38ae75c773901823aecfca62381 Mon Sep 17 00:00:00 2001 From: mikeller Date: Sat, 16 Jun 2018 14:45:09 +1200 Subject: [PATCH 4/6] Fixed build for F7. --- src/main/drivers/serial_usb_vcp.h | 4 ++++ src/main/io/usb_cdc_hid.c | 11 +++++++---- src/main/vcp_hal/usbd_cdc_interface.c | 2 ++ 3 files changed, 13 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/serial_usb_vcp.h b/src/main/drivers/serial_usb_vcp.h index daeaa2ce22..66d0aaae8b 100644 --- a/src/main/drivers/serial_usb_vcp.h +++ b/src/main/drivers/serial_usb_vcp.h @@ -22,6 +22,8 @@ #include "drivers/serial.h" +#include "vcp_hal/usbd_cdc_interface.h" + typedef struct { serialPort_t port; @@ -32,6 +34,8 @@ typedef struct { bool buffering; } vcpPort_t; +extern USBD_HandleTypeDef USBD_Device; + serialPort_t *usbVcpOpen(void); struct serialPort_s; uint32_t usbVcpGetBaudRate(struct serialPort_s *instance); diff --git a/src/main/io/usb_cdc_hid.c b/src/main/io/usb_cdc_hid.c index 695dedf466..48b6edf156 100644 --- a/src/main/io/usb_cdc_hid.c +++ b/src/main/io/usb_cdc_hid.c @@ -29,12 +29,15 @@ #include "rx/rx.h" //TODO: Make it platform independent in the future -#ifdef STM32F4 +#if defined(STM32F4) #include "vcpf4/usbd_cdc_vcp.h" + #include "usbd_hid_core.h" #elif defined(STM32F7) -#include "usbd_cdc_interface.h" -#include "usbd_def.h" +#include "drivers/serial_usb_vcp.h" + +#include "vcp_hal/usbd_cdc_interface.h" + #include "usbd_hid.h" #endif @@ -67,7 +70,7 @@ void sendRcDataToHid(void) report[i] = -report[i]; } } -#ifdef STM32F4 +#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)); diff --git a/src/main/vcp_hal/usbd_cdc_interface.c b/src/main/vcp_hal/usbd_cdc_interface.c index 8397394303..60bfa9e849 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.c +++ b/src/main/vcp_hal/usbd_cdc_interface.c @@ -53,6 +53,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 -----------------------------------------------------------*/ From b402d85a7758fda1531fbcca5804444e10c02a63 Mon Sep 17 00:00:00 2001 From: mikeller Date: Sat, 16 Jun 2018 14:53:25 +1200 Subject: [PATCH 5/6] Holy moly, these drivers are a mess. --- src/main/drivers/serial_usb_vcp.h | 2 +- src/main/vcp_hal/usbd_cdc_interface.c | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/drivers/serial_usb_vcp.h b/src/main/drivers/serial_usb_vcp.h index 66d0aaae8b..49eb635447 100644 --- a/src/main/drivers/serial_usb_vcp.h +++ b/src/main/drivers/serial_usb_vcp.h @@ -22,7 +22,7 @@ #include "drivers/serial.h" -#include "vcp_hal/usbd_cdc_interface.h" +#include "usbd_cdc.h" typedef struct { serialPort_t port; diff --git a/src/main/vcp_hal/usbd_cdc_interface.c b/src/main/vcp_hal/usbd_cdc_interface.c index 60bfa9e849..5a4b3a6d48 100644 --- a/src/main/vcp_hal/usbd_cdc_interface.c +++ b/src/main/vcp_hal/usbd_cdc_interface.c @@ -48,7 +48,6 @@ /* Includes ------------------------------------------------------------------*/ #include "stm32f7xx_hal.h" #include "usbd_core.h" -#include "usbd_def.h" #include "usbd_desc.h" #include "usbd_cdc.h" #include "usbd_cdc_interface.h" From 11098fba859e0f934e692bc394b960ba0daab1a4 Mon Sep 17 00:00:00 2001 From: mikeller Date: Sat, 16 Jun 2018 15:33:13 +1200 Subject: [PATCH 6/6] Made new includes conditional to F7. --- src/main/drivers/serial_usb_vcp.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/serial_usb_vcp.h b/src/main/drivers/serial_usb_vcp.h index 49eb635447..29b7096d27 100644 --- a/src/main/drivers/serial_usb_vcp.h +++ b/src/main/drivers/serial_usb_vcp.h @@ -22,8 +22,12 @@ #include "drivers/serial.h" +#if defined(STM32F7) #include "usbd_cdc.h" +extern USBD_HandleTypeDef USBD_Device; +#endif + typedef struct { serialPort_t port; @@ -34,8 +38,6 @@ typedef struct { bool buffering; } vcpPort_t; -extern USBD_HandleTypeDef USBD_Device; - serialPort_t *usbVcpOpen(void); struct serialPort_s; uint32_t usbVcpGetBaudRate(struct serialPort_s *instance);