diff --git a/src/main/fc/mw.c b/src/main/fc/mw.c index 82e2d5423..e3e767df3 100644 --- a/src/main/fc/mw.c +++ b/src/main/fc/mw.c @@ -373,18 +373,6 @@ void mwDisarm(void) } } -#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_SMARTPORT) - -#ifdef TELEMETRY -static void releaseSharedTelemetryPorts(void) { - serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); - while (sharedPort) { - mspSerialReleasePortIfAllocated(sharedPort); - sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); - } -} -#endif - void mwArm(void) { static bool firstArmingCalibrationWasCompleted; diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index 6b59e72d1..2579187fc 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -35,6 +35,8 @@ #include "fc/rc_controls.h" #include "fc/runtime_config.h" +#include "msp/msp_serial.h" + #include "rx/rx.h" #include "telemetry/telemetry.h" @@ -156,4 +158,13 @@ void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadb #endif } +#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_SMARTPORT) + +void releaseSharedTelemetryPorts(void) { + serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); + while (sharedPort) { + mspSerialReleasePortIfAllocated(sharedPort); + sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP); + } +} #endif diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h index 9355c703d..f656578b9 100644 --- a/src/main/telemetry/telemetry.h +++ b/src/main/telemetry/telemetry.h @@ -60,3 +60,5 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing); void telemetryUseConfig(telemetryConfig_t *telemetryConfig); #define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK) + +void releaseSharedTelemetryPorts(void);