bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback) { UNUSED(rxConfig); if (callback) *callback = sumhReadRawRC; rxRuntimeConfig->channelCount = SUMH_MAX_CHANNEL_COUNT; serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } #ifdef TELEMETRY bool portShared = telemetryCheckRxPortShared(portConfig); #else bool portShared = false; #endif sumhPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumhDataReceive, SUMH_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED); #ifdef TELEMETRY if (portShared) { telemetrySharedPort = sumhPort; } #endif return sumhPort != NULL; }
bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) { static uint16_t sbusChannelData[SBUS_MAX_CHANNEL]; static sbusFrameData_t sbusFrameData; rxRuntimeConfig->channelData = sbusChannelData; rxRuntimeConfig->frameData = &sbusFrameData; sbusChannelsInit(rxConfig, rxRuntimeConfig); rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL; rxRuntimeConfig->rxRefreshRate = 11000; rxRuntimeConfig->rcFrameStatusFn = sbusFrameStatus; const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } #ifdef USE_TELEMETRY bool portShared = telemetryCheckRxPortShared(portConfig); #else bool portShared = false; #endif serialPort_t *sBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sbusDataReceive, &sbusFrameData, SBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); if (rxConfig->rssi_src_frame_errors) { rssiSource = RSSI_SOURCE_FRAME_ERRORS; } #ifdef USE_TELEMETRY if (portShared) { telemetrySharedPort = sBusPort; } #endif return sBusPort != NULL; }
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 isSerialConfigValid(serialConfig_t *serialConfigToCheck) { UNUSED(serialConfigToCheck); /* * rules: * - 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. * - serial RX and FrSky / LTM telemetry can be shared * - No other sharing combinations are valid. */ uint8_t mspPortCount = 0; uint8_t index; for (index = 0; index < SERIAL_PORT_COUNT; index++) { serialPortConfig_t *portConfig = &serialConfigToCheck->portConfigs[index]; if (portConfig->functionMask & FUNCTION_MSP) { mspPortCount++; } uint8_t bitCount = BITCOUNT(portConfig->functionMask); if (bitCount > 1) { // shared if (bitCount > 2) { return false; } if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) { // MSP & telemetry #ifdef TELEMETRY } else if (telemetryCheckRxPortShared(portConfig)) { // serial RX & telemetry #endif } else { // some other combination return false; } } } if (mspPortCount == 0 || mspPortCount > MAX_MSP_PORT_COUNT) { return false; } 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(); } }
bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) { UNUSED(rxConfig); rxRuntimeConfig->channelCount = MIN(SUMD_MAX_CHANNEL, MAX_SUPPORTED_RC_CHANNEL_COUNT); rxRuntimeConfig->rxRefreshRate = 11000; rxRuntimeConfig->rcReadRawFn = sumdReadRawRC; rxRuntimeConfig->rcFrameStatusFn = sumdFrameStatus; const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } #ifdef USE_TELEMETRY bool portShared = telemetryCheckRxPortShared(portConfig); #else bool portShared = false; #endif serialPort_t *sumdPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, sumdDataReceive, NULL, SUMD_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); #ifdef USE_TELEMETRY if (portShared) { telemetrySharedPort = sumdPort; } #endif return sumdPort != NULL; }