Cleaned up implementation of MSP port releasing when shared.

This commit is contained in:
mikeller 2018-05-07 23:33:23 +12:00
parent 7b831f94ee
commit 0cd8c62568
6 changed files with 15 additions and 14 deletions

View File

@ -778,7 +778,7 @@ bool processRx(timeUs_t currentTimeUs)
if ((!telemetryConfig()->telemetry_switch && ARMING_FLAG(ARMED)) ||
(telemetryConfig()->telemetry_switch && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) {
releaseSharedTelemetryPorts();
mspSerialReleaseSharedTelemetryPorts();
} else {
// the telemetry state must be checked immediately so that shared serial ports are released.
telemetryCheckState();

View File

@ -51,6 +51,9 @@ typedef enum {
FUNCTION_LIDAR_TF = (1 << 15), // 32768
} serialPortFunction_e;
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
#define TELEMETRY_PORT_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT)
typedef enum {
BAUD_AUTO = 0,
BAUD_9600,

View File

@ -80,6 +80,16 @@ void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
}
}
#if defined(USE_TELEMETRY)
void mspSerialReleaseSharedTelemetryPorts(void) {
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_PORT_FUNCTIONS_MASK, FUNCTION_MSP);
while (sharedPort) {
mspSerialReleasePortIfAllocated(sharedPort);
sharedPort = findNextSharedSerialPort(TELEMETRY_PORT_FUNCTIONS_MASK, FUNCTION_MSP);
}
}
#endif
static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c)
{
switch (mspPort->c_state) {

View File

@ -115,5 +115,6 @@ bool mspSerialWaiting(void);
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn, mspProcessReplyFnPtr mspProcessReplyFn);
void mspSerialAllocatePorts(void);
void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort);
void mspSerialReleaseSharedTelemetryPorts(void);
int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen, mspDirection_e direction);
uint32_t mspSerialTxBytesFree(void);

View File

@ -221,12 +221,4 @@ void telemetryProcess(uint32_t currentTime)
handleIbusTelemetry();
#endif
}
void releaseSharedTelemetryPorts(void) {
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_PORT_FUNCTIONS_MASK, FUNCTION_MSP);
while (sharedPort) {
mspSerialReleasePortIfAllocated(sharedPort);
sharedPort = findNextSharedSerialPort(TELEMETRY_PORT_FUNCTIONS_MASK, FUNCTION_MSP);
}
}
#endif

View File

@ -58,9 +58,6 @@ typedef struct telemetryConfig_s {
PG_DECLARE(telemetryConfig_t, telemetryConfig);
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
#define TELEMETRY_PORT_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT)
extern serialPort_t *telemetrySharedPort;
void telemetryInit(void);
@ -70,5 +67,3 @@ void telemetryCheckState(void);
void telemetryProcess(uint32_t currentTime);
bool telemetryDetermineEnabledState(portSharing_e portSharing);
void releaseSharedTelemetryPorts(void);