void checkLtmTelemetryState(void) { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(ltmPortSharing); if (newTelemetryEnabledValue == ltmEnabled) return; if (newTelemetryEnabledValue) configureLtmTelemetryPort(); else freeLtmTelemetryPort(); }
void checkSmartPortTelemetryState(void) { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(smartPortPortSharing); if (newTelemetryEnabledValue == smartPortTelemetryEnabled) { return; } if (newTelemetryEnabledValue) configureSmartPortTelemetryPort(); else freeSmartPortTelemetryPort(); }
void checkHoTTTelemetryState(void) { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(hottPortSharing); if (newTelemetryEnabledValue == hottTelemetryEnabled) { return; } if (newTelemetryEnabledValue) configureHoTTTelemetryPort(); else freeHoTTTelemetryPort(); }
void checkFrSkyTelemetryState(void) { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(frskyPortSharing); if (newTelemetryEnabledValue == frskyTelemetryEnabled) { return; } if (newTelemetryEnabledValue) configureFrSkyTelemetryPort(); else freeFrSkyTelemetryPort(); }
void checkMAVLinkTelemetryState(void) { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(mavlinkPortSharing); if (newTelemetryEnabledValue == mavlinkTelemetryEnabled) { return; } if (newTelemetryEnabledValue) configureMAVLinkTelemetryPort(); else freeMAVLinkTelemetryPort(); }
void checkLtmTelemetryState(void) { if (portConfig && telemetryCheckRxPortShared(portConfig)) { if (!ltmEnabled && telemetrySharedPort != NULL) { ltmPort = telemetrySharedPort; ltmEnabled = true; } } else { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(ltmPortSharing); if (newTelemetryEnabledValue == ltmEnabled) return; if (newTelemetryEnabledValue) configureLtmTelemetryPort(); else freeLtmTelemetryPort(); } }
bool checkIbusTelemetryState(void) { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(ibusPortSharing); if (newTelemetryEnabledValue == ibusTelemetryEnabled) { return false; } if (newTelemetryEnabledValue) { rescheduleTask(TASK_TELEMETRY, IBUS_TASK_PERIOD_US); configureIbusTelemetryPort(); } else { freeIbusTelemetryPort(); } return true; }
void checkFrSkyTelemetryState(void) { if (portConfig && telemetryCheckRxPortShared(portConfig)) { if (!frskyTelemetryEnabled && telemetrySharedPort != NULL) { frskyPort = telemetrySharedPort; frskyTelemetryEnabled = true; } } else { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(frskyPortSharing); if (newTelemetryEnabledValue == frskyTelemetryEnabled) { return; } if (newTelemetryEnabledValue) configureFrSkyTelemetryPort(); else freeFrSkyTelemetryPort(); } }
void checkMAVLinkTelemetryState(void) { if (portConfig && telemetryCheckRxPortShared(portConfig)) { if (!mavlinkTelemetryEnabled && telemetrySharedPort != NULL) { mavlinkPort = telemetrySharedPort; mavlinkTelemetryEnabled = true; } } else { bool newTelemetryEnabledValue = telemetryDetermineEnabledState(mavlinkPortSharing); if (newTelemetryEnabledValue == mavlinkTelemetryEnabled) { return; } if (newTelemetryEnabledValue) configureMAVLinkTelemetryPort(); else freeMAVLinkTelemetryPort(); } }