void configureIbusTelemetryPort(void) { if (!ibusSerialPortConfig) { return; } if (isSerialPortShared(ibusSerialPortConfig, FUNCTION_RX_SERIAL, FUNCTION_TELEMETRY_IBUS)) { // serialRx will open port and handle telemetry return; } ibusSerialPort = openSerialPort(ibusSerialPortConfig->identifier, FUNCTION_TELEMETRY_IBUS, NULL, NULL, IBUS_BAUDRATE, IBUS_UART_MODE, SERIAL_BIDIR | (telemetryConfig()->telemetry_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED)); if (!ibusSerialPort) { return; } initSharedIbusTelemetry(ibusSerialPort); ibusTelemetryEnabled = true; outboundBytesToIgnoreOnRxCount = 0; }
bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) { UNUSED(rxConfig); ibusSyncByte = 0; rxRuntimeConfig->channelCount = IBUS_MAX_CHANNEL; rxRuntimeConfig->rxRefreshRate = 20000; // TODO - Verify speed rxRuntimeConfig->rcReadRawFn = ibusReadRawRC; rxRuntimeConfig->rcFrameStatusFn = ibusFrameStatus; const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); if (!portConfig) { return false; } #ifdef TELEMETRY bool portShared = isSerialPortShared(portConfig, FUNCTION_RX_SERIAL, FUNCTION_TELEMETRY_IBUS); #else bool portShared = false; #endif rxBytesToIgnore = 0; serialPort_t *ibusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, ibusDataReceive, IBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, SERIAL_NOT_INVERTED | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0) ); #if defined(TELEMETRY) && defined(TELEMETRY_IBUS) if (portShared) { initSharedIbusTelemetry(ibusPort); } #endif return ibusPort != NULL; }