Merge pull request #1729 from mikeller/move_releasesharedselemetryports_to_telemetry
Moved 'releaseSharedTelemetryPorts' to telemetry.c.
This commit is contained in:
commit
3f495d0759
|
@ -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)
|
void mwArm(void)
|
||||||
{
|
{
|
||||||
static bool firstArmingCalibrationWasCompleted;
|
static bool firstArmingCalibrationWasCompleted;
|
||||||
|
|
|
@ -35,6 +35,8 @@
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
#include "fc/runtime_config.h"
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "msp/msp_serial.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
#include "telemetry/telemetry.h"
|
||||||
|
@ -156,4 +158,13 @@ void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadb
|
||||||
#endif
|
#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
|
#endif
|
||||||
|
|
|
@ -60,3 +60,5 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing);
|
||||||
void telemetryUseConfig(telemetryConfig_t *telemetryConfig);
|
void telemetryUseConfig(telemetryConfig_t *telemetryConfig);
|
||||||
|
|
||||||
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
|
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
|
||||||
|
|
||||||
|
void releaseSharedTelemetryPorts(void);
|
||||||
|
|
Loading…
Reference in New Issue