diff --git a/src/main/target/SPRACINGF4EVO/config.c b/src/main/target/SPRACINGF4EVO/config.c index 43a1226e70..8ea9e98586 100644 --- a/src/main/target/SPRACINGF4EVO/config.c +++ b/src/main/target/SPRACINGF4EVO/config.c @@ -37,7 +37,7 @@ void targetConfiguration(void) rxConfigMutable()->sbus_inversion = 1; serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything. serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; - telemetryConfigMutable()->telemetry_inversion = 0; telemetryConfigMutable()->halfDuplex = 0; + telemetryConfigMutable()->telemetry_inversion = 0; } #endif diff --git a/src/main/target/SPRACINGF4NEO/config.c b/src/main/target/SPRACINGF4NEO/config.c index c426d7ecce..f7261352d1 100644 --- a/src/main/target/SPRACINGF4NEO/config.c +++ b/src/main/target/SPRACINGF4NEO/config.c @@ -30,8 +30,8 @@ void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS; - serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = TELEMETRY_PROVIDER_DEFAULT - telemetryConfigMutable()->halfDuplex = TELEMETRY_DEFAULT_HALFDUPLEX; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = TELEMETRY_PROVIDER_DEFAULT; + telemetryConfigMutable()->halfDuplex = false; } #endif diff --git a/src/main/target/SPRACINGF4NEO/target.h b/src/main/target/SPRACINGF4NEO/target.h index 8377d59ae0..fc10fc3544 100644 --- a/src/main/target/SPRACINGF4NEO/target.h +++ b/src/main/target/SPRACINGF4NEO/target.h @@ -18,6 +18,7 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "SP4N" +#define TARGET_CONFIG #ifndef SPRACINGF4NEO_REV #define SPRACINGF4NEO_REV 3 @@ -203,7 +204,6 @@ #define SERIALRX_PROVIDER SERIALRX_SBUS #define TELEMETRY_UART SERIAL_PORT_UART5 -#define TELEMETRY_DEFAULT_HALFDUPLEX 0 // Both pins of UART5 are used for a telemetry circuit #define TELEMETRY_PROVIDER_DEFAULT FUNCTION_TELEMETRY_SMARTPORT #define BUTTONS // Physically located on the optional OSD/VTX board.