diff --git a/src/main/drivers/resource.c b/src/main/drivers/resource.c index 40b9911b28..13cdf530b1 100644 --- a/src/main/drivers/resource.c +++ b/src/main/drivers/resource.c @@ -63,5 +63,6 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = { "VTX", "COMPASS_CS", "SPI_PREINIT", + "RX_BIND_PLUG", }; diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h index 871300bd70..f79990ea89 100644 --- a/src/main/drivers/resource.h +++ b/src/main/drivers/resource.h @@ -63,6 +63,7 @@ typedef enum { OWNER_VTX, OWNER_COMPASS_CS, OWNER_SPI_PREINIT, + OWNER_RX_BIND_PLUG, OWNER_TOTAL_COUNT } resourceOwner_e; diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index d31d6638ef..d09e37d0ff 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -18,6 +18,7 @@ #pragma once #include "drivers/io.h" +#include "config/parameter_group.h" typedef enum portMode_t { MODE_RX = 1 << 0, @@ -86,6 +87,8 @@ typedef struct serialPinConfig_s { ioTag_t ioTagInverter[SERIAL_PORT_MAX_INDEX]; } serialPinConfig_t; +PG_DECLARE(serialPinConfig_t, serialPinConfig); + struct serialPortVTable { void (*serialWrite)(serialPort_t *instance, uint8_t ch); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 3508b89d63..68fb5f4042 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -2828,6 +2828,10 @@ const cliResourceValue_t resourceTable[] = { { OWNER_I2C_SDA, PG_I2C_CONFIG, offsetof(i2cConfig_t, ioTagSda[0]), I2CDEV_COUNT }, #endif { OWNER_LED, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, ioTags[0]), STATUS_LED_NUMBER }, +#ifdef USE_SPEKTRUM_BIND + { OWNER_RX_BIND, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_bind_pin_override_ioTag), 0 }, + { OWNER_RX_BIND_PLUG, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_bind_plug_ioTag), 0 }, +#endif }; static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index) diff --git a/src/main/fc/config.h b/src/main/fc/config.h index 4ced00ee29..a1b96a08a0 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -91,7 +91,6 @@ PG_DECLARE(ppmConfig_t, ppmConfig); PG_DECLARE(pwmConfig_t, pwmConfig); PG_DECLARE(vcdProfile_t, vcdProfile); PG_DECLARE(sdcardConfig_t, sdcardConfig); -PG_DECLARE(serialPinConfig_t, serialPinConfig); struct pidProfile_s; extern struct pidProfile_s *currentPidProfile; diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index f2577f762c..546322f281 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -315,11 +315,12 @@ void init(void) } #endif -#ifdef SPEKTRUM_BIND_PIN +#if defined(USE_SPEKTRUM_BIND) && !defined(SITL) if (feature(FEATURE_RX_SERIAL)) { switch (rxConfig()->serialrx_provider) { case SERIALRX_SPEKTRUM1024: case SERIALRX_SPEKTRUM2048: + case SERIALRX_SRXL: // Spektrum satellite binding if enabled on startup. // Must be called before that 100ms sleep so that we don't lose satellite's binding window after startup. // The rest of Spektrum initialization will happen later - via spektrumInit() diff --git a/src/main/fc/settings.c b/src/main/fc/settings.c index 43518f8fa4..32791c76c8 100644 --- a/src/main/fc/settings.c +++ b/src/main/fc/settings.c @@ -357,7 +357,7 @@ const clivalue_t valueTable[] = { { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) }, { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, sbus_inversion) }, #endif -#ifdef SPEKTRUM_BIND_PIN +#ifdef USE_SPEKTRUM_BIND { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind) }, { "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 1 }, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind_autoreset) }, #endif diff --git a/src/main/rx/msp.c b/src/main/rx/msp.c index 5841182e2c..4a009fa153 100644 --- a/src/main/rx/msp.c +++ b/src/main/rx/msp.c @@ -24,6 +24,7 @@ #include "common/utils.h" +#include "drivers/io.h" #include "rx/rx.h" #include "rx/msp.h" diff --git a/src/main/rx/nrf24_cx10.c b/src/main/rx/nrf24_cx10.c index 280d8398d1..318f02853e 100644 --- a/src/main/rx/nrf24_cx10.c +++ b/src/main/rx/nrf24_cx10.c @@ -28,6 +28,7 @@ #include "build/build_config.h" +#include "drivers/io.h" #include "drivers/rx_nrf24l01.h" #include "drivers/rx_xn297.h" #include "drivers/time.h" diff --git a/src/main/rx/nrf24_h8_3d.c b/src/main/rx/nrf24_h8_3d.c index 855ee5eb3f..54a9938f24 100644 --- a/src/main/rx/nrf24_h8_3d.c +++ b/src/main/rx/nrf24_h8_3d.c @@ -30,6 +30,7 @@ #include "common/utils.h" +#include "drivers/io.h" #include "drivers/rx_nrf24l01.h" #include "drivers/rx_xn297.h" #include "drivers/time.h" diff --git a/src/main/rx/nrf24_inav.c b/src/main/rx/nrf24_inav.c index 766d0b4eba..c3ba65326d 100644 --- a/src/main/rx/nrf24_inav.c +++ b/src/main/rx/nrf24_inav.c @@ -28,6 +28,7 @@ #include "common/utils.h" +#include "drivers/io.h" #include "drivers/rx_nrf24l01.h" #include "drivers/time.h" diff --git a/src/main/rx/nrf24_syma.c b/src/main/rx/nrf24_syma.c index b6eb3a16f2..2d0cdc3fdf 100644 --- a/src/main/rx/nrf24_syma.c +++ b/src/main/rx/nrf24_syma.c @@ -28,6 +28,7 @@ #include "build/build_config.h" +#include "drivers/io.h" #include "drivers/rx_nrf24l01.h" #include "drivers/time.h" diff --git a/src/main/rx/nrf24_v202.c b/src/main/rx/nrf24_v202.c index 0342b7b524..9de7865e83 100644 --- a/src/main/rx/nrf24_v202.c +++ b/src/main/rx/nrf24_v202.c @@ -30,6 +30,7 @@ #include "common/utils.h" +#include "drivers/io.h" #include "drivers/rx_nrf24l01.h" #include "drivers/time.h" diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 46c5f95208..5ae38829e8 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -108,6 +108,14 @@ static uint8_t rcSampleIndex = 0; #define RX_MAX_USEC 2115 #define RX_MID_USEC 1500 +#ifndef SPEKTRUM_BIND_PIN +#define SPEKTRUM_BIND_PIN NONE +#endif + +#ifndef BINDPLUG_PIN +#define BINDPLUG_PIN NONE +#endif + PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 0); void pgResetFn_rxConfig(rxConfig_t *rxConfig) { @@ -116,6 +124,8 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig) .serialrx_provider = SERIALRX_PROVIDER, .rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL, .sbus_inversion = 1, + .spektrum_bind_pin_override_ioTag = IO_TAG(SPEKTRUM_BIND_PIN), + .spektrum_bind_plug_ioTag = IO_TAG(BINDPLUG_PIN), .spektrum_sat_bind = 0, .spektrum_sat_bind_autoreset = 1, .midrc = RX_MID_USEC, diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index e08f5f0720..48772e0d16 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -122,6 +122,8 @@ typedef struct rxConfig_s { uint8_t rx_spi_protocol; // type of nrf24 protocol (0 = v202 250kbps). Must be enabled by FEATURE_RX_NRF24 first. uint32_t rx_spi_id; uint8_t rx_spi_rf_channel_count; + ioTag_t spektrum_bind_pin_override_ioTag; + ioTag_t spektrum_bind_plug_ioTag; uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot uint8_t rssi_channel; diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 0a9adb88ff..f73e2f2a84 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -77,13 +77,6 @@ static volatile uint8_t spekFrame[SPEK_FRAME_SIZE]; static rxRuntimeConfig_t *rxRuntimeConfigPtr; static serialPort_t *serialPort; -#ifdef SPEKTRUM_BIND_PIN -static IO_t BindPin = DEFIO_IO(NONE); -#ifdef BINDPLUG_PIN -static IO_t BindPlug = DEFIO_IO(NONE); -#endif -#endif - static uint8_t telemetryBuf[SRXL_FRAME_SIZE_MAX]; static uint8_t telemetryBufLen = 0; @@ -180,19 +173,22 @@ static uint16_t spektrumReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint return data; } -#ifdef SPEKTRUM_BIND_PIN +#ifdef USE_SPEKTRUM_BIND bool spekShouldBind(uint8_t spektrum_sat_bind) { -#ifdef BINDPLUG_PIN - BindPlug = IOGetByTag(IO_TAG(BINDPLUG_PIN)); - IOInit(BindPlug, OWNER_RX_BIND, 0); - IOConfigGPIO(BindPlug, IOCFG_IPU); +#ifdef USE_SPEKTRUM_BIND_PLUG + IO_t BindPlug = IOGetByTag(rxConfig()->spektrum_bind_plug_ioTag); - // Check status of bind plug and exit if not active - delayMicroseconds(10); // allow configuration to settle - if (IORead(BindPlug)) { - return false; + if (BindPlug) { + IOInit(BindPlug, OWNER_RX_BIND, 0); + IOConfigGPIO(BindPlug, IOCFG_IPU); + + // Check status of bind plug and exit if not active + delayMicroseconds(10); // allow configuration to settle + if (IORead(BindPlug)) { + return false; + } } #endif @@ -202,6 +198,7 @@ bool spekShouldBind(uint8_t spektrum_sat_bind) spektrum_sat_bind > SPEKTRUM_SAT_BIND_MAX ); } + /* spektrumBind function ported from Baseflight. It's used to bind satellite receiver to TX. * Function must be called immediately after startup so that we don't miss satellite bind window. * Known parameters. Tested with DSMX satellite and DX8 radio. Framerate (11ms or 22ms) must be selected from TX. @@ -210,52 +207,92 @@ bool spekShouldBind(uint8_t spektrum_sat_bind) */ void spektrumBind(rxConfig_t *rxConfig) { - int i; if (!spekShouldBind(rxConfig->spektrum_sat_bind)) { return; } + // Determine a pin to use + ioTag_t bindPin; + + if (rxConfig->spektrum_bind_pin_override_ioTag) { + bindPin = rxConfig->spektrum_bind_pin_override_ioTag; + } else { + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); + if (!portConfig) { + return; + } + + int index = SERIAL_PORT_IDENTIFIER_TO_INDEX(portConfig->identifier); + ioTag_t txPin = serialPinConfig()->ioTagTx[index]; + ioTag_t rxPin = serialPinConfig()->ioTagRx[index]; + + // Take care half-duplex case + switch (rxConfig->serialrx_provider) { + case SERIALRX_SRXL: +#ifdef TELEMETRY + if (feature(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig)) { + bindPin = txPin; + } + break; +#endif + default: + bindPin = rxPin; + } + + if (!bindPin) { + return; + } + } + + IO_t bindIO = IOGetByTag(bindPin); + + IOInit(bindIO, OWNER_RX_BIND, 0); + IOConfigGPIO(bindIO, IOCFG_OUT_PP); + LED1_ON; - BindPin = IOGetByTag(IO_TAG(SPEKTRUM_BIND_PIN)); - IOInit(BindPin, OWNER_RX_BIND, 0); - IOConfigGPIO(BindPin, IOCFG_OUT_PP); - // RX line, set high - IOWrite(BindPin, true); + IOWrite(bindIO, true); // Bind window is around 20-140ms after powerup delay(60); LED1_OFF; - for (i = 0; i < rxConfig->spektrum_sat_bind; i++) { - + for (int i = 0; i < rxConfig->spektrum_sat_bind; i++) { LED0_OFF; LED2_OFF; // RX line, drive low for 120us - IOWrite(BindPin, false); + IOWrite(bindIO, false); delayMicroseconds(120); LED0_ON; LED2_ON; // RX line, drive high for 120us - IOWrite(BindPin, true); + IOWrite(bindIO, true); delayMicroseconds(120); } -#ifndef BINDPLUG_PIN + + // Release the bind pin to avoid interference with an actual rx pin, + // when rxConfig->spektrum_bind_pin_override_ioTag is used. + // This happens when the bind pin is connected in parallel to the rx pin. + + if (rxConfig->spektrum_bind_pin_override_ioTag) { + delay(50); // Keep it high for 50msec + IOConfigGPIO(bindIO, IOCFG_IN_FLOATING); + } + // If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config // Don't reset if hardware bind plug is present // Reset only when autoreset is enabled - if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) { + + if (!rxConfig->spektrum_bind_plug_ioTag && rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) { rxConfig->spektrum_sat_bind = 0; saveConfigAndNotify(); } -#endif - } -#endif // SPEKTRUM_BIND_PIN +#endif // USE_SPEKTRUM_BIND bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) { @@ -276,7 +313,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig switch (rxConfig->serialrx_provider) { case SERIALRX_SRXL: #ifdef TELEMETRY - srxlEnabled = (feature(FEATURE_TELEMETRY) && !portShared && rxConfig->serialrx_provider == SERIALRX_SRXL); + srxlEnabled = (feature(FEATURE_TELEMETRY) && !portShared); #endif case SERIALRX_SPEKTRUM2048: // 11 bit frames diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h index 33fb04fb8c..317f1a940e 100644 --- a/src/main/target/AIR32/target.h +++ b/src/main/target/AIR32/target.h @@ -96,8 +96,6 @@ //#define CURRENT_METER_ADC_PIN PA5 #define RSSI_ADC_PIN PB2 -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/AIRHEROF3/target.h b/src/main/target/AIRHEROF3/target.h index f91f87b3ac..3872e070b9 100755 --- a/src/main/target/AIRHEROF3/target.h +++ b/src/main/target/AIRHEROF3/target.h @@ -88,8 +88,6 @@ #define SERIALRX_UART SERIAL_PORT_USART2 #define RX_CHANNELS_TAER -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/ALIENFLIGHTF1/target.h b/src/main/target/ALIENFLIGHTF1/target.h index 596b4f47a7..53a411a08b 100644 --- a/src/main/target/ALIENFLIGHTF1/target.h +++ b/src/main/target/ALIENFLIGHTF1/target.h @@ -62,8 +62,8 @@ #define RSSI_ADC_PIN PA1 #define EXTERNAL1_ADC_PIN PA5 -#define SPEKTRUM_BIND_PIN PA3 - +#define USE_SPEKTRUM_BIND +#define USE_SPEKTRUM_BIND_PLUG #define BINDPLUG_PIN PB5 #define DEFAULT_FEATURES FEATURE_MOTOR_STOP diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index f0ce648bc9..41bf661728 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -114,8 +114,6 @@ // LED strip configuration. #define LED_STRIP -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define BINDPLUG_PIN PB12 #define DEFAULT_FEATURES FEATURE_MOTOR_STOP diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index bb7b3329d0..d149a32e7c 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -162,8 +162,6 @@ // LED strip configuration. #define LED_STRIP -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define BINDPLUG_PIN PB2 #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 7e07c38670..685d997757 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -171,8 +171,6 @@ // LED strip configuration. #define LED_STRIP -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define BINDPLUG_PIN PB2 #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h index cc88854492..fb617e44f1 100755 --- a/src/main/target/BETAFLIGHTF3/target.h +++ b/src/main/target/BETAFLIGHTF3/target.h @@ -127,8 +127,6 @@ #define SBUS_TELEMETRY_UART SERIAL_PORT_USART1 #define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD) -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index a9ec2522bd..e6d7e7b1f3 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -152,8 +152,6 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index d03e0aa676..23e3af7c4c 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -93,8 +93,6 @@ #define VBAT_ADC_PIN PA0 #define RSSI_ADC_PIN PB0 -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE //#define SONAR diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index 84d573b88c..e75e2a7b9b 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -107,7 +107,7 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define USE_RX_MSP -#define SPEKTRUM_BIND_PIN PA3 // UART2, PA3 +#define USE_SPEKTRUM_BIND #endif //USE_RX_NRF24 diff --git a/src/main/target/CLRACINGF4/target.h b/src/main/target/CLRACINGF4/target.h index 8ddfe2e402..c76ca7bc59 100644 --- a/src/main/target/CLRACINGF4/target.h +++ b/src/main/target/CLRACINGF4/target.h @@ -122,8 +122,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_FEATURES ( FEATURE_OSD ) #define CURRENT_METER_SCALE_DEFAULT 250 -#define SPEKTRUM_BIND_PIN UART6_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13))) diff --git a/src/main/target/CLRACINGF7/target.h b/src/main/target/CLRACINGF7/target.h index 09f6c9ec7b..73ec820229 100644 --- a/src/main/target/CLRACINGF7/target.h +++ b/src/main/target/CLRACINGF7/target.h @@ -137,7 +137,6 @@ // LED strip configuration. #define LED_STRIP -#define SPEKTRUM_BIND_PIN UART6_RX_PIN #define BINDPLUG_PIN PB2 #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index a59e827abc..519f61c14e 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -130,8 +130,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // !!TODO - check the TARGET_IO_PORTs are correct diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index 91280a0fa5..2e6f518e9f 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -146,8 +146,6 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define SPEKTRUM_BIND_PIN UART6_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/FF_FORTINIF4/target.h b/src/main/target/FF_FORTINIF4/target.h index 5e5069d0c7..d754e40d60 100644 --- a/src/main/target/FF_FORTINIF4/target.h +++ b/src/main/target/FF_FORTINIF4/target.h @@ -103,8 +103,6 @@ #define SERIAL_PORT_COUNT 5 //SPECKTRUM BIND -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define CMS #define USE_MSP_DISPLAYPORT /*---------------------------------*/ diff --git a/src/main/target/FF_PIKOBLX/target.h b/src/main/target/FF_PIKOBLX/target.h index 2b7d9ed722..b42237047e 100644 --- a/src/main/target/FF_PIKOBLX/target.h +++ b/src/main/target/FF_PIKOBLX/target.h @@ -94,12 +94,6 @@ #define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_USART3 -#if defined(FF_RADIANCE) -#define SPEKTRUM_BIND_PIN UART2_RX_PIN -#else -#define SPEKTRUM_BIND_PIN UART3_RX_PIN -#endif - #define TRANSPONDER #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/FF_PIKOF4/target.h b/src/main/target/FF_PIKOF4/target.h index ab0cb499cc..4d34b84f11 100644 --- a/src/main/target/FF_PIKOF4/target.h +++ b/src/main/target/FF_PIKOF4/target.h @@ -98,8 +98,6 @@ #define UART6_TX_PIN PC6 #define SERIAL_PORT_COUNT 4 -//SPECKTRUM BIND -#define SPEKTRUM_BIND_PIN UART3_RX_PIN #define CMS #define USE_MSP_DISPLAYPORT diff --git a/src/main/target/FRSKYF3/config.c b/src/main/target/FRSKYF3/config.c index 1ba41e1a5c..d39e3c48af 100644 --- a/src/main/target/FRSKYF3/config.c +++ b/src/main/target/FRSKYF3/config.c @@ -19,6 +19,7 @@ #include #ifdef TARGET_CONFIG +#include "drivers/io.h" #include "rx/rx.h" #include "io/serial.h" diff --git a/src/main/target/FRSKYF3/target.h b/src/main/target/FRSKYF3/target.h index 550666518b..9e73b25663 100644 --- a/src/main/target/FRSKYF3/target.h +++ b/src/main/target/FRSKYF3/target.h @@ -138,8 +138,6 @@ #define TELEMETRY_UART SERIAL_PORT_USART3 #define SERIALRX_UART SERIAL_PORT_USART2 -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/FRSKYF4/config.c b/src/main/target/FRSKYF4/config.c index 1ba41e1a5c..d39e3c48af 100644 --- a/src/main/target/FRSKYF4/config.c +++ b/src/main/target/FRSKYF4/config.c @@ -19,6 +19,7 @@ #include #ifdef TARGET_CONFIG +#include "drivers/io.h" #include "rx/rx.h" #include "io/serial.h" diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h index 7369bf4f62..06470b0ace 100644 --- a/src/main/target/FRSKYF4/target.h +++ b/src/main/target/FRSKYF4/target.h @@ -117,8 +117,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define DEFAULT_FEATURES (FEATURE_OSD) #define AVOID_UART1_FOR_PWM_PPM -#define SPEKTRUM_BIND_PIN UART1_RX_PIN - #define SERIALRX_PROVIDER SERIALRX_SBUS #define TELEMETRY_UART SERIAL_PORT_USART6 #define SERIALRX_UART SERIAL_PORT_USART1 diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 5a9d893841..5785dde8d6 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -169,8 +169,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_ESC_SENSOR diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index 182b662e30..69d47398cd 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -179,8 +179,6 @@ #define SERIALRX_UART SERIAL_PORT_USART1 #define SERIALRX_PROVIDER SERIALRX_SBUS -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/FURYF7/target.h b/src/main/target/FURYF7/target.h index 335d1513a1..96fa4bb4ac 100644 --- a/src/main/target/FURYF7/target.h +++ b/src/main/target/FURYF7/target.h @@ -138,7 +138,11 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define SERIALRX_PROVIDER SERIALRX_SBUS -#define SPEKTRUM_BIND_PIN PB11 +// XXX To target maintainer: +// USE_SPEKTRUM_BIND is enabled for this target, and it will use +// RX (or TX if half-duplex) pin of the UART the receiver is connected. +// If PB11 is critical for this target, please resurrect this line. +//#define SPEKTRUM_BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/IMPULSERCF3/target.h b/src/main/target/IMPULSERCF3/target.h index f63687d568..5efa651d02 100644 --- a/src/main/target/IMPULSERCF3/target.h +++ b/src/main/target/IMPULSERCF3/target.h @@ -91,8 +91,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define SERIALRX_UART SERIAL_PORT_USART2 -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 41a478ffa5..18454b71b0 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -81,8 +81,6 @@ #undef LED_STRIP -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE /* diff --git a/src/main/target/ISHAPEDF3/target.h b/src/main/target/ISHAPEDF3/target.h index 2367ef2151..3d3040bdcd 100644 --- a/src/main/target/ISHAPEDF3/target.h +++ b/src/main/target/ISHAPEDF3/target.h @@ -105,8 +105,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 46e7b3c445..0509f46404 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -101,8 +101,6 @@ #define AVOID_UART2_FOR_PWM_PPM -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h index 0f72485724..ce21303499 100644 --- a/src/main/target/KIWIF4/target.h +++ b/src/main/target/KIWIF4/target.h @@ -178,8 +178,6 @@ #define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_USART1 -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index fea3621eea..d8b8d4e127 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -157,8 +157,6 @@ #define DEFAULT_FEATURES (FEATURE_TELEMETRY) #endif -#define SPEKTRUM_BIND_PIN UART1_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_ESCSERIAL diff --git a/src/main/target/MICROSCISKY/target.h b/src/main/target/MICROSCISKY/target.h index 7c2431aa44..ab0db600f1 100644 --- a/src/main/target/MICROSCISKY/target.h +++ b/src/main/target/MICROSCISKY/target.h @@ -70,7 +70,7 @@ #define USE_I2C_DEVICE_2 #define I2C_DEVICE (I2CDEV_2) -#define SPEKTRUM_BIND_PIN PA3 +#define USE_SPEKTRUM_BIND #define BRUSHED_MOTORS #define DEFAULT_FEATURES FEATURE_MOTOR_STOP diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index f9e0d681ff..c9c60b6f55 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -98,8 +98,6 @@ #define USE_ESC_SENSOR -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/MULTIFLITEPICO/target.h b/src/main/target/MULTIFLITEPICO/target.h index 0e249af074..38caeb8f0e 100755 --- a/src/main/target/MULTIFLITEPICO/target.h +++ b/src/main/target/MULTIFLITEPICO/target.h @@ -123,8 +123,6 @@ #define SERIALRX_UART SERIAL_PORT_USART3 #define RX_CHANNELS_TAER -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define BINDPLUG_PIN PA13 #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 1de6785bf4..4c24d3f375 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -146,7 +146,7 @@ #define RSSI_ADC_PIN PA1 #define EXTERNAL1_ADC_PIN PA5 -#define SPEKTRUM_BIND_PIN PA3 +#define USE_SPEKTRUM_BIND_PIN #define DEFAULT_RX_FEATURE FEATURE_RX_PPM diff --git a/src/main/target/NERO/target.h b/src/main/target/NERO/target.h index 3106be009f..225f3c03c4 100644 --- a/src/main/target/NERO/target.h +++ b/src/main/target/NERO/target.h @@ -128,8 +128,6 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 5e47a26e11..d929657e6c 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -169,10 +169,6 @@ //#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3 -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - -#define BINDPLUG_PIN PB0 - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 3775074832..4be0de9714 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -189,8 +189,6 @@ #define DEFAULT_FEATURES (FEATURE_OSD) #define AVOID_UART1_FOR_PWM_PPM -#define SPEKTRUM_BIND_PIN UART1_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13))) diff --git a/src/main/target/RCEXPLORERF3/target.h b/src/main/target/RCEXPLORERF3/target.h index 93f1e37309..2aa351b0d2 100644 --- a/src/main/target/RCEXPLORERF3/target.h +++ b/src/main/target/RCEXPLORERF3/target.h @@ -109,8 +109,6 @@ #define NAV_GPS_GLITCH_DETECTION #define NAV_MAX_WAYPOINTS 60 -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 0c3926c7e5..c9ddb3d1a6 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -258,8 +258,6 @@ #define DEFAULT_FEATURES FEATURE_TELEMETRY #endif -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index 67c178b5b4..178d782f66 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -84,8 +84,6 @@ #define VBAT_ADC_PIN PA6 #define RSSI_ADC_PIN PA5 -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff diff --git a/src/main/target/RG_SSD_F3/target.h b/src/main/target/RG_SSD_F3/target.h index b83c875a10..62b2830b13 100644 --- a/src/main/target/RG_SSD_F3/target.h +++ b/src/main/target/RG_SSD_F3/target.h @@ -144,8 +144,6 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - // IO - stm32f303rc in 64pin package #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 34fbef33fa..4d2a62ea7f 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -92,8 +92,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define SERIALRX_UART SERIAL_PORT_USART2 -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 52b68f9cbc..287612fb08 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -148,8 +148,6 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_OSD) diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index ef2fb481f0..8730eb9260 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -90,8 +90,6 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - //#define SONAR //#define SONAR_ECHO_PIN PB1 //#define SONAR_TRIGGER_PIN PA2 diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index baf48775ea..b2c5f4875c 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -189,8 +189,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY) -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 80da46617b..19c19b478c 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -172,8 +172,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY) -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index eefad26999..cc6af1328c 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -186,8 +186,6 @@ #define BINDPLUG_PIN BUTTON_B_PIN #endif -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) diff --git a/src/main/target/SPRACINGF3NEO/target.h b/src/main/target/SPRACINGF3NEO/target.h index de917c8595..3986fcc095 100755 --- a/src/main/target/SPRACINGF3NEO/target.h +++ b/src/main/target/SPRACINGF3NEO/target.h @@ -184,8 +184,6 @@ #define BUTTONS // Physically located on the optional OSD/VTX board. #define BUTTON_A_PIN PD2 -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - // FIXME While it's possible to use the button on the OSD/VTX board for binding enabling it here will break binding unless you have the OSD/VTX connected. //#define BINDPLUG_PIN BUTTON_A_PIN diff --git a/src/main/target/SPRACINGF4EVO/target.h b/src/main/target/SPRACINGF4EVO/target.h index 256e1a31c9..0065aa4d36 100644 --- a/src/main/target/SPRACINGF4EVO/target.h +++ b/src/main/target/SPRACINGF4EVO/target.h @@ -176,8 +176,6 @@ #define TELEMETRY_UART SERIAL_PORT_UART5 #define SERIALRX_PROVIDER SERIALRX_SBUS -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/SPRACINGF4NEO/target.h b/src/main/target/SPRACINGF4NEO/target.h index 04b18fde14..01960602e2 100644 --- a/src/main/target/SPRACINGF4NEO/target.h +++ b/src/main/target/SPRACINGF4NEO/target.h @@ -214,8 +214,6 @@ #define BUTTON_A_PIN PB8 #endif -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - // FIXME While it's possible to use the button on the OSD/VTX board for binding enabling it here will break binding unless you have the OSD/VTX connected. //#define BINDPLUG_PIN BUTTON_A_PIN diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 460e8c1d94..a5fefed4d1 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -175,8 +175,6 @@ #define USE_ESC_SENSOR -#define SPEKTRUM_BIND_PIN PA3 // USART2, PA3 - #define SONAR #define SONAR_TRIGGER_PIN PB0 #define SONAR_ECHO_PIN PB1 diff --git a/src/main/target/VRRACE/target.h b/src/main/target/VRRACE/target.h index 814cd2acbe..20a96924ad 100644 --- a/src/main/target/VRRACE/target.h +++ b/src/main/target/VRRACE/target.h @@ -165,10 +165,6 @@ //#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -/* -#define SPEKTRUM_BIND_PIN PB11 -*/ - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 5984c6accf..8762fac962 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -115,8 +115,6 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define SPEKTRUM_BIND_PIN UART3_RX_PIN - #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/common_fc_pre.h b/src/main/target/common_fc_pre.h index 534e788507..b53a0ddb76 100644 --- a/src/main/target/common_fc_pre.h +++ b/src/main/target/common_fc_pre.h @@ -122,6 +122,11 @@ #define VTX_CONTROL #define VTX_SMARTAUDIO #define VTX_TRAMP + +#ifdef USE_SERIALRX_SPEKTRUM +#define USE_SPEKTRUM_BIND +#define USE_SPEKTRUM_BIND_PLUG +#endif #endif #if (FLASH_SIZE > 256) diff --git a/src/test/unit/flight_failsafe_unittest.cc b/src/test/unit/flight_failsafe_unittest.cc index afc75d113a..5edb8c45de 100644 --- a/src/test/unit/flight_failsafe_unittest.cc +++ b/src/test/unit/flight_failsafe_unittest.cc @@ -39,6 +39,7 @@ extern "C" { #include "io/beeper.h" + #include "drivers/io.h" #include "rx/rx.h" extern boxBitmask_t rcModeActivationMask; diff --git a/src/test/unit/ledstrip_unittest.cc b/src/test/unit/ledstrip_unittest.cc index d4d47cb1d9..b2b712bcba 100644 --- a/src/test/unit/ledstrip_unittest.cc +++ b/src/test/unit/ledstrip_unittest.cc @@ -31,6 +31,7 @@ extern "C" { #include "sensors/battery.h" + #include "drivers/io.h" #include "rx/rx.h" #include "fc/config.h" diff --git a/src/test/unit/rx_ranges_unittest.cc b/src/test/unit/rx_ranges_unittest.cc index c75d26ec84..d86d1db04e 100644 --- a/src/test/unit/rx_ranges_unittest.cc +++ b/src/test/unit/rx_ranges_unittest.cc @@ -23,6 +23,7 @@ extern "C" { #include "platform.h" + #include "drivers/io.h" #include "common/maths.h" #include "config/parameter_group_ids.h" #include "fc/rc_controls.h" diff --git a/src/test/unit/rx_rx_unittest.cc b/src/test/unit/rx_rx_unittest.cc index db4b9c6515..5daad55c57 100644 --- a/src/test/unit/rx_rx_unittest.cc +++ b/src/test/unit/rx_rx_unittest.cc @@ -23,6 +23,7 @@ extern "C" { #include "platform.h" + #include "drivers/io.h" #include "rx/rx.h" #include "fc/rc_modes.h" #include "common/maths.h"