diff --git a/Makefile b/Makefile index 261f1de22..2b881c39f 100644 --- a/Makefile +++ b/Makefile @@ -786,13 +786,15 @@ VCP_SRC = \ vcpf4/usbd_desc.c \ vcpf4/usbd_usr.c \ vcpf4/usbd_cdc_vcp.c \ - drivers/serial_usb_vcp.c + drivers/serial_usb_vcp.c \ + drivers/usb_io.c else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS))) VCP_SRC = \ vcp_hal/usbd_desc.c \ vcp_hal/usbd_conf.c \ vcp_hal/usbd_cdc_interface.c \ - drivers/serial_usb_vcp.c + drivers/serial_usb_vcp.c \ + drivers/usb_io.c else VCP_SRC = \ vcp/hw_config.c \ diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 6014553cb..97fdfe03c 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -28,8 +28,10 @@ #if defined(STM32F4) #include "usb_core.h" #include "usbd_cdc_vcp.h" +#include "usb_io.h" #elif defined(STM32F7) #include "vcp_hal/usbd_cdc_interface.h" +#include "usb_io.h" USBD_HandleTypeDef USBD_Device; #else #include "usb_core.h" @@ -184,10 +186,14 @@ serialPort_t *usbVcpOpen(void) vcpPort_t *s; #if defined(STM32F4) + usbGenerateDisconnectPulse(); + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0); IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0); USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb); #elif defined(STM32F7) + usbGenerateDisconnectPulse(); + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0); IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0); /* Init Device Library */ diff --git a/src/main/drivers/usb_detection.c b/src/main/drivers/usb_detection.c deleted file mode 100644 index d1c0088c9..000000000 --- a/src/main/drivers/usb_detection.c +++ /dev/null @@ -1,55 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it 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 is distributed in the hope that it 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 Cleanflight. If not, see . - */ - -#include -#include - -#include "platform.h" -#include "io.h" -#include "system.h" - -static IO_t usbDetectPin = IO_NONE; - -void usbCableDetectDeinit(void) -{ -#ifdef USB_DETECT_PIN - IOInit(usbDetectPin, OWNER_FREE, 0); - IOConfigGPIO(usbDetectPin, IOCFG_IN_FLOATING); - usbDetectPin = IO_NONE; -#endif -} - -void usbCableDetectInit(void) -{ -#ifdef USB_DETECT_PIN - usbDetectPin = IOGetByTag(IO_TAG(USB_DETECT_PIN)); - - IOInit(usbDetectPin, OWNER_USB_DETECT, 0); - IOConfigGPIO(usbDetectPin, IOCFG_OUT_PP); -#endif -} - -bool usbCableIsInserted(void) -{ - bool result = false; - -#ifdef USB_DETECT_PIN - result = IORead(usbDetectPin) != 0; -#endif - - return result; -} diff --git a/src/main/drivers/usb_detection.h b/src/main/drivers/usb_detection.h deleted file mode 100644 index 5a3c53d6b..000000000 --- a/src/main/drivers/usb_detection.h +++ /dev/null @@ -1,22 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it 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 is distributed in the hope that it 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 Cleanflight. If not, see . - */ - -#pragma once - -void usbCableDetectDeinit(void); -void usbCableDetectInit(void); -bool usbCableIsInserted(void); diff --git a/src/main/drivers/usb_io.c b/src/main/drivers/usb_io.c index 7d2c99fc8..8166dca4b 100644 --- a/src/main/drivers/usb_io.c +++ b/src/main/drivers/usb_io.c @@ -20,7 +20,7 @@ #include "platform.h" -#ifdef USB_IO +#ifdef USE_VCP #include "io.h" #include "system.h" @@ -28,7 +28,6 @@ #include "sdcard.h" - #ifdef USB_DETECT_PIN static IO_t usbDetectPin = IO_NONE; #endif @@ -75,5 +74,4 @@ void usbGenerateDisconnectPulse(void) IOLo(usbPin); } - #endif diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index e5078d370..00bcefbd7 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -488,7 +488,7 @@ void init(void) } #endif -#ifdef USB_CABLE_DETECTION +#ifdef USB_DETECT_PIN usbCableDetectInit(); #endif diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h index 04c906052..6c27ce17b 100755 --- a/src/main/target/BETAFLIGHTF3/target.h +++ b/src/main/target/BETAFLIGHTF3/target.h @@ -49,8 +49,6 @@ #define REMAP_TIM16_DMA #define REMAP_TIM17_DMA -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index ce232c883..38e79644c 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -75,8 +75,6 @@ #define USE_MAG_AK8963 #define USE_MAG_AK8975 -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 51e6d6ae0..0dae0773f 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -91,7 +91,6 @@ #define USE_BARO_BMP280 #define USE_BARO_SPI_BMP280 -#define USB_IO #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 24cc5df74..e9391ac55 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -108,8 +108,6 @@ // Performance logging for SD card operations: // #define AFATFS_USE_INTROSPECTIVE_LOGGING -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/IMPULSERCF3/target.h b/src/main/target/IMPULSERCF3/target.h index 19858114a..468fec4f3 100644 --- a/src/main/target/IMPULSERCF3/target.h +++ b/src/main/target/IMPULSERCF3/target.h @@ -27,8 +27,6 @@ #define USABLE_TIMER_CHANNEL_COUNT 8 -#define USB_IO - #define USE_EXTI #define MPU_INT_EXTI PC13 #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index 3ea53966c..03ef07316 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -113,8 +113,6 @@ #define ACC_MPU6500_ALIGN CW270_DEG #endif -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index d43a2f705..732edb03e 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -60,8 +60,12 @@ #define USB_IO #define USB_CABLE_DETECTION + #define USB_DETECT_PIN PB5 +#undef GPS + + #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/RCEXPLORERF3/target.h b/src/main/target/RCEXPLORERF3/target.h index 3d9becdfa..452d2bab5 100644 --- a/src/main/target/RCEXPLORERF3/target.h +++ b/src/main/target/RCEXPLORERF3/target.h @@ -58,8 +58,6 @@ #define SONAR_TRIGGER_PIN PA6 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) #define SONAR_ECHO_PIN PB1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor ) -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/RG_SSD_F3/target.h b/src/main/target/RG_SSD_F3/target.h index 4d600d3c4..2b45ae55e 100644 --- a/src/main/target/RG_SSD_F3/target.h +++ b/src/main/target/RG_SSD_F3/target.h @@ -78,8 +78,6 @@ #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC3 #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 9ae3a3f2a..362db90c8 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -53,8 +53,6 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_INSTANCE SPI1 -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 374eb1a66..8ab7077f5 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -65,8 +65,6 @@ //#define SONAR -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 1f1712e0b..c74eb4105 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -78,8 +78,6 @@ #define BRUSHED_ESC_AUTODETECT -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 @@ -107,12 +105,13 @@ #define UART3_TX_PIN PB10 // PB10 (AF7) #define UART3_RX_PIN PB11 // PB11 (AF7) - #ifndef TINYBEEF3 #define SOFTSERIAL1_RX_PIN PA0 // PA0 / PAD3 #define SOFTSERIAL1_TX_PIN PA1 // PA1 / PAD4 #endif +#define USB_DETECT_PIN PB5 + #define SONAR_SOFTSERIAL1_EXCLUSIVE #define USE_SPI diff --git a/src/main/target/SPRACINGF3NEO/target.h b/src/main/target/SPRACINGF3NEO/target.h index 4cf44851d..4db3a6316 100755 --- a/src/main/target/SPRACINGF3NEO/target.h +++ b/src/main/target/SPRACINGF3NEO/target.h @@ -53,8 +53,6 @@ #define USE_MAG_AK8975 #define USE_MAG_HMC5883 -#define USB_IO - #define USE_VCP #define USE_UART1 #define USE_UART2 diff --git a/src/main/target/TINYFISH/target.h b/src/main/target/TINYFISH/target.h index 294965d8a..1deffa81b 100644 --- a/src/main/target/TINYFISH/target.h +++ b/src/main/target/TINYFISH/target.h @@ -46,7 +46,6 @@ #if USB_VCP_ENABLED #define USE_VCP - #define USB_IO #define USBD_PRODUCT_STRING "tinyFISH" #define SERIAL_PORT_COUNT 6 #else diff --git a/src/main/vcp/hw_config.c b/src/main/vcp/hw_config.c index f9ec7c32e..508b15a0c 100644 --- a/src/main/vcp/hw_config.c +++ b/src/main/vcp/hw_config.c @@ -37,6 +37,7 @@ #include #include "drivers/system.h" +#include "drivers/usb_io.h" #include "drivers/nvic.h" #include "common/utils.h" @@ -85,30 +86,7 @@ void Set_System(void) RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); #endif /* STM32L1XX_XD */ - /*Pull down PA12 to create USB Disconnect Pulse*/ // HJI -#if defined(STM32F303xC) // HJI - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE); // HJI - - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; // HJI - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; // HJI - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT; // HJI - GPIO_InitStructure.GPIO_OType = GPIO_OType_OD; // HJI - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL; // HJI -#else - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); // HJI - - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;// HJI - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;// HJI - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;// HJI -#endif - - GPIO_Init(GPIOA, &GPIO_InitStructure); // HJI - - GPIO_ResetBits(GPIOA, GPIO_Pin_12); // HJI - - delay(200); // HJI - - GPIO_SetBits(GPIOA, GPIO_Pin_12); // HJI + usbGenerateDisconnectPulse(); #if defined(STM32F37X) || defined(STM32F303xC)