diff --git a/make/source.mk b/make/source.mk
index b940201ccb..68fe369295 100644
--- a/make/source.mk
+++ b/make/source.mk
@@ -84,6 +84,7 @@ COMMON_SRC = \
sensors/battery.c \
sensors/current.c \
sensors/voltage.c \
+ target/config_helper.c \
OSD_SLAVE_SRC = \
io/displayport_max7456.c \
diff --git a/src/main/target/OMNIBUSF4/config.c b/src/main/target/OMNIBUSF4/config.c
index 4e33cc0eac..157bb3b809 100644
--- a/src/main/target/OMNIBUSF4/config.c
+++ b/src/main/target/OMNIBUSF4/config.c
@@ -24,11 +24,22 @@
#ifdef USE_TARGET_CONFIG
+#include "config_helper.h"
+
#include "io/serial.h"
#include "pg/max7456.h"
#include "pg/pg.h"
+#ifdef EXUAVF4PRO
+static targetSerialPortFunction_t targetSerialPortFunction[] = {
+ { SERIAL_PORT_USART1, FUNCTION_TELEMETRY_SMARTPORT },
+ { SERIAL_PORT_USART3, FUNCTION_VTX_TRAMP },
+ { SERIAL_PORT_UART4, FUNCTION_RCDEVICE },
+ { SERIAL_PORT_USART6, FUNCTION_RX_SERIAL },
+};
+#endif
+
void targetConfiguration(void)
{
#ifdef OMNIBUSF4BASE
@@ -37,10 +48,7 @@ void targetConfiguration(void)
#endif
#ifdef EXUAVF4PRO
- serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
- serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_VTX_TRAMP;
- serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_RCDEVICE;
- serialConfigMutable()->portConfigs[4].functionMask = FUNCTION_RX_SERIAL;
+ targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
#endif
}
#endif
diff --git a/src/main/target/OMNIBUSF7/config.c b/src/main/target/OMNIBUSF7/config.c
index de97012a69..29349b04e4 100644
--- a/src/main/target/OMNIBUSF7/config.c
+++ b/src/main/target/OMNIBUSF7/config.c
@@ -24,16 +24,21 @@
#ifdef USE_TARGET_CONFIG
+#include "config_helper.h"
+
#include "io/serial.h"
+static targetSerialPortFunction_t targetSerialPortFunction[] = {
+#if defined(OMNIBUSF7V2) && defined(ESC_SENSOR_UART)
+ // OMNIBUS F7 V2 has an option to connect UART7_RX to ESC telemetry
+ { ESC_SENSOR_UART, FUNCTION_ESC_SENSOR },
+#else
+ { SERIAL_PORT_NONE, FUNCTION_NONE },
+#endif
+};
+
void targetConfiguration(void)
{
-// OMNIBUS F7 V2 has an option to connect UART7_RX to ESC telemetry
-#if defined(OMNIBUSF7V2) && defined(ESC_SENSOR_UART)
- serialPortConfig_t *serialEscSensorUartConfig = serialFindPortConfiguration(ESC_SENSOR_UART);
- if (serialEscSensorUartConfig) {
- serialEscSensorUartConfig->functionMask = FUNCTION_ESC_SENSOR;
- }
-#endif
+ targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
}
#endif
diff --git a/src/main/target/SPRACINGF3NEO/config.c b/src/main/target/SPRACINGF3NEO/config.c
index 579b96daf0..a9c1137b68 100644
--- a/src/main/target/SPRACINGF3NEO/config.c
+++ b/src/main/target/SPRACINGF3NEO/config.c
@@ -49,13 +49,25 @@
#include "fc/config.h"
#ifdef USE_TARGET_CONFIG
+
+#include "config_helper.h"
+
+#define GPS_UART SERIAL_PORT_USART3
+
+#define TELEMETRY_UART SERIAL_PORT_UART5
+#define TELEMETRY_PROVIDER_DEFAULT FUNCTION_TELEMETRY_SMARTPORT
+
+static targetSerialPortFunction_t targetSerialPortFunction[] = {
+ { SERIAL_PORT_USART1, FUNCTION_MSP },
+ { TELEMETRY_UART, TELEMETRY_PROVIDER_DEFAULT },
+ { GPS_UART, FUNCTION_GPS },
+};
+
void targetConfiguration(void)
{
barometerConfigMutable()->baro_hardware = BARO_DEFAULT;
compassConfigMutable()->mag_hardware = MAG_DEFAULT;
- serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So Bluetooth users don't have to change anything.
- serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = TELEMETRY_PROVIDER_DEFAULT;
- serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS;
+ targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
telemetryConfigMutable()->halfDuplex = true;
}
#endif
diff --git a/src/main/target/SPRACINGF3NEO/target.h b/src/main/target/SPRACINGF3NEO/target.h
index 903449b8e8..537d7954d8 100644
--- a/src/main/target/SPRACINGF3NEO/target.h
+++ b/src/main/target/SPRACINGF3NEO/target.h
@@ -172,14 +172,9 @@
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP)
-#define GPS_UART SERIAL_PORT_USART3
-
#define SERIALRX_UART SERIAL_PORT_USART2
#define SERIALRX_PROVIDER SERIALRX_SBUS
-#define TELEMETRY_UART SERIAL_PORT_UART5
-#define TELEMETRY_PROVIDER_DEFAULT FUNCTION_TELEMETRY_SMARTPORT
-
#define USE_BUTTONS // Physically located on the optional OSD/VTX board.
#define BUTTON_A_PIN PD2
diff --git a/src/main/target/config_helper.c b/src/main/target/config_helper.c
new file mode 100644
index 0000000000..e863efe2f0
--- /dev/null
+++ b/src/main/target/config_helper.c
@@ -0,0 +1,34 @@
+/*
+ * 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 "config_helper.h"
+
+#ifdef USE_TARGET_CONFIG
+
+void targetSerialPortFunctionConfig(targetSerialPortFunction_t *config, size_t count)
+{
+ for (size_t i = 0 ; i < count ; i++) {
+ int index = findSerialPortIndexByIdentifier(config[i].identifier);
+ if (index >= 0) {
+ serialConfigMutable()->portConfigs[index].functionMask = config[i].function;
+ }
+ }
+}
+#endif
diff --git a/src/main/target/config_helper.h b/src/main/target/config_helper.h
new file mode 100644
index 0000000000..7d1f4f9212
--- /dev/null
+++ b/src/main/target/config_helper.h
@@ -0,0 +1,30 @@
+/*
+ * 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
+
+#include "io/serial.h"
+
+typedef struct targetSerialPortFunction_s {
+ serialPortIdentifier_e identifier;
+ serialPortFunction_e function;
+} targetSerialPortFunction_t;
+
+void targetSerialPortFunctionConfig(targetSerialPortFunction_t *config, size_t count);