Made MAVLink telemetry shareable with serial Rx.

This commit is contained in:
mikeller 2016-11-21 01:53:47 +13:00
parent ccd759d93a
commit 28f2cf0510
3 changed files with 18 additions and 11 deletions

View File

@ -208,7 +208,7 @@ serialPort_t *findNextSharedSerialPort(uint16_t functionMask, serialPortFunction
} }
#ifdef TELEMETRY #ifdef TELEMETRY
#define ALL_TELEMETRY_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_MAVLINK) #define ALL_TELEMETRY_FUNCTIONS_MASK (TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT)
#else #else
#define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK) #define ALL_TELEMETRY_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_SMARTPORT | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
#endif #endif
@ -221,7 +221,7 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
* rules: * rules:
* - 1 MSP port minimum, max MSP ports is defined and must be adhered to. * - 1 MSP port minimum, max MSP ports is defined and must be adhered to.
* - MSP is allowed to be shared with EITHER any telemetry OR blackbox. * - MSP is allowed to be shared with EITHER any telemetry OR blackbox.
* - serial RX and FrSky / LTM telemetry can be shared * - serial RX and FrSky / LTM / MAVLink telemetry can be shared
* - No other sharing combinations are valid. * - No other sharing combinations are valid.
*/ */
uint8_t mspPortCount = 0; uint8_t mspPortCount = 0;

View File

@ -170,16 +170,23 @@ void configureMAVLinkTelemetryPort(void)
void checkMAVLinkTelemetryState(void) void checkMAVLinkTelemetryState(void)
{ {
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(mavlinkPortSharing); if (portConfig && telemetryCheckRxPortShared(portConfig)) {
if (!mavlinkTelemetryEnabled && telemetrySharedPort != NULL) {
mavlinkPort = telemetrySharedPort;
mavlinkTelemetryEnabled = true;
}
} else {
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(mavlinkPortSharing);
if (newTelemetryEnabledValue == mavlinkTelemetryEnabled) { if (newTelemetryEnabledValue == mavlinkTelemetryEnabled) {
return; return;
}
if (newTelemetryEnabledValue)
configureMAVLinkTelemetryPort();
else
freeMAVLinkTelemetryPort();
} }
if (newTelemetryEnabledValue)
configureMAVLinkTelemetryPort();
else
freeMAVLinkTelemetryPort();
} }
void mavlinkSendSystemStatus(void) void mavlinkSendSystemStatus(void)

View File

@ -59,4 +59,4 @@ 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) #define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)