diff --git a/.travis.yml b/.travis.yml new file mode 100644 index 0000000..6a3b878 --- /dev/null +++ b/.travis.yml @@ -0,0 +1,33 @@ +language: c +env: + matrix: + - BOARD="adafruit:samd:adafruit_feather_m0" CONFIG="tx_sbus" + - BOARD="adafruit:samd:adafruit_feather_m0" CONFIG="rx" + - BOARD="adafruit:avr:feather32u4" CONFIG="tx_sbus" + - BOARD="adafruit:avr:feather32u4" CONFIG="rx" +before_install: + - "/sbin/start-stop-daemon --start --quiet --pidfile /tmp/custom_xvfb_1.pid --make-pidfile --background --exec /usr/bin/Xvfb -- :1 -ac -screen 0 1280x1024x16" + - sleep 3 + - export DISPLAY=:1.0 + - wget http://downloads.arduino.cc/arduino-1.8.5-linux64.tar.xz + - tar xf arduino-1.8.5-linux64.tar.xz + - sudo mv arduino-1.8.5 /usr/local/share/arduino + - sudo ln -s /usr/local/share/arduino/arduino /usr/local/bin/arduino + - arduino --pref "boardsmanager.additional.urls=https://adafruit.github.io/arduino-board-index/package_adafruit_index.json" --save-prefs + - if [[ "$BOARD" =~ "adafruit:avr:" ]]; then + arduino --install-boards adafruit:avr > /tmp/install_boards.log || cat /tmp/install_boards.log ; + fi + - if [[ "$BOARD" =~ "adafruit:samd:" ]]; then + arduino --install-boards arduino:samd > /tmp/install_boards.log || cat /tmp/install_boards.log ; + arduino --install-boards adafruit:samd > /tmp/install_boards.log || cat /tmp/install_boards.log ; + fi + - arduino --pref "boardsmanager.additional.urls=" --save-prefs +install: + - arduino --install-library "Adafruit SSD1306","Adafruit GFX Library" +script: + - cp -f $PWD/crossbow/configurations/config_${CONFIG}.h $PWD/crossbow/config.h && + arduino --verify --board $BOARD $PWD/crossbow/crossbow.ino +notifications: + email: + on_success: change + on_failure: change \ No newline at end of file diff --git a/crossbow/config.h b/crossbow/config.h new file mode 100644 index 0000000..a104194 --- /dev/null +++ b/crossbow/config.h @@ -0,0 +1,17 @@ +#ifndef CONFIG_H +#define CONFIG_H + +#define DEVICE_MODE_TX +// #define DEVICE_MODE_RX + +#define FEATURE_TX_OLED +// #define FORCE_TX_WITHOUT_INPUT +#define FEATURE_TX_INPUT_PPM +// #define FEATURE_TX_INPUT_SBUS + +// #define DEBUG_SERIAL +// #define DEBUG_PING_PONG +// #define DEBUG_LED +// #define DEBUG_TX_INPUT_ON_OLED + +#endif diff --git a/crossbow/configurations/config_rx.h b/crossbow/configurations/config_rx.h new file mode 100644 index 0000000..0b90016 --- /dev/null +++ b/crossbow/configurations/config_rx.h @@ -0,0 +1,6 @@ +#ifndef CONFIG_H +#define CONFIG_H + +#define DEVICE_MODE_RX + +#endif diff --git a/crossbow/configurations/config_tx_sbus.h b/crossbow/configurations/config_tx_sbus.h new file mode 100644 index 0000000..123676a --- /dev/null +++ b/crossbow/configurations/config_tx_sbus.h @@ -0,0 +1,9 @@ +#ifndef CONFIG_H +#define CONFIG_H + +#define DEVICE_MODE_TX + +#define FEATURE_TX_OLED +#define FEATURE_TX_INPUT_SBUS + +#endif diff --git a/crossbow.ino b/crossbow/crossbow.ino similarity index 88% rename from crossbow.ino rename to crossbow/crossbow.ino index 80a29db..a880816 100644 --- a/crossbow.ino +++ b/crossbow/crossbow.ino @@ -1,12 +1,13 @@ -#define DEVICE_MODE_TX -// #define DEVICE_MODE_RX +/* +This Source Code Form is subject to the terms of the Mozilla Public +License, v. 2.0. If a copy of the MPL was not distributed with this file, +You can obtain one at http://mozilla.org/MPL/2.0/. -// #define FEATURE_TX_OLED -// #define FORCE_TX_WITHOUT_INPUT +Copyright (c) 20xx, MPL Contributor1 contrib1@example.net +*/ + +#include "config.h" -#define DEBUG_SERIAL -// #define DEBUG_PING_PONG -// #define DEBUG_LED #include "lora.h" #include "variables.h" @@ -14,27 +15,44 @@ #include "qsp.h" #include "sbus.h" -// LoRa32u4 ports -#define LORA32U4_SS_PIN 8 -#define LORA32U4_RST_PIN 4 -#define LORA32U4_DI0_PIN 7 +#ifdef ARDUINO_AVR_FEATHER32U4 + #define LORA_SS_PIN 8 + #define LORA_RST_PIN 4 + #define LORA_DI0_PIN 7 +#elif defined(ARDUINO_SAMD_FEATHER_M0) + #define LORA_SS_PIN 8 + #define LORA_RST_PIN 4 + #define LORA_DI0_PIN 3 +#else + #error please select hardware +#endif /* * Main defines for device working in TX mode */ #ifdef DEVICE_MODE_TX -// #include -// PPMReader ppmReader(PPM_INPUT_PIN, PPM_INPUT_INTERRUPT, true); -SbusInput_t sbusInput = {}; +#ifdef FEATURE_TX_INPUT_PPM + #include "ppm_reader.h" + PPM_Reader txInput(PPM_INPUT_PIN, true); + +#elif defined(FEATURE_TX_INPUT_SBUS) + #include "sbus.h" + SbusInput txInput(Serial1); + +#else + #error please select tx input source +#endif + +volatile int16_t TxInput::channels[TX_INPUT_CHANNEL_COUNT]; -// FUTABA_SBUS sBus; #include "txbuzzer.h" BuzzerState_t buzzer; #ifdef FEATURE_TX_OLED +#include "Wire.h" #define OLED_RESET -1 #include @@ -129,7 +147,7 @@ void setup(void) #ifdef DEVICE_MODE_RX qsp.deviceState = DEVICE_STATE_FAILSAFE; -#else +#else qsp.deviceState = DEVICE_STATE_OK; #endif @@ -137,11 +155,11 @@ void setup(void) * Setup hardware */ LoRa.setPins( - LORA32U4_SS_PIN, - LORA32U4_RST_PIN, - LORA32U4_DI0_PIN + LORA_SS_PIN, + LORA_RST_PIN, + LORA_DI0_PIN ); - + if (!LoRa.begin(radioState.frequency)) { #ifdef DEBUG_SERIAL @@ -156,7 +174,7 @@ void setup(void) LoRa.setCodingRate4(radioState.loraCodingRate); LoRa.setTxPower(radioState.loraTxPower); LoRa.enableCrc(); - + //Setup ISR callback and start receiving LoRa.onReceive(onReceive); LoRa.receive(); @@ -182,7 +200,6 @@ void setup(void) #ifdef DEVICE_MODE_TX #ifdef FEATURE_TX_OLED - Wire.setClock(400000); display.begin(SSD1306_SWITCHCAPVCC, 0x3C); // initialize with the I2C addr 0x3C (for the 128x32) @@ -205,7 +222,7 @@ void setup(void) /* * Prepare Serial1 for S.Bus processing */ - Serial1.begin(100000, SERIAL_8N2); + txInput.start(); #endif pinMode(LED_BUILTIN, OUTPUT); @@ -228,17 +245,17 @@ void updateRxDeviceState(RxDeviceState_t *rxDeviceState) { rxDeviceState->rxVoltage = map(analogRead(RX_ADC_PIN_1), 0, 1024, 0, 255); rxDeviceState->a1Voltage = map(analogRead(RX_ADC_PIN_2), 0, 1024, 0, 255); rxDeviceState->a2Voltage = map(analogRead(RX_ADC_PIN_3), 0, 1024, 0, 255); -} +} int8_t getFrameToTransmit(QspConfiguration_t *qsp) { - + if (qsp->forcePongFrame) { qsp->forcePongFrame = false; return QSP_FRAME_PONG; } int8_t retVal = rxSendSequence[currentSequenceIndex]; - + currentSequenceIndex++; if (currentSequenceIndex >= TRANSMIT_SEQUENCE_COUNT) { currentSequenceIndex = 0; @@ -263,9 +280,9 @@ int8_t getFrameToTransmit(QspConfiguration_t *qsp) { #endif /* - * + * * Main loop starts here! - * + * */ void loop(void) { @@ -278,7 +295,7 @@ void loop(void) */ if ( currentMillis > radioState.nextTxCheckMillis && - radioState.deviceState == RADIO_STATE_TX && + radioState.deviceState == RADIO_STATE_TX && !LoRa.isTransmitting() ) { LoRa.receive(); @@ -290,9 +307,9 @@ void loop(void) LoRa.read(tmpBuffer, radioState.bytesToRead); for (int i = 0; i < radioState.bytesToRead; i++) { - qspDecodeIncomingFrame(&qsp, tmpBuffer[i], &rxDeviceState, &txDeviceState, &radioState); + qspDecodeIncomingFrame(&qsp, tmpBuffer[i], &rxDeviceState, &txDeviceState, &radioState); } - + radioState.rssi = getRadioRssi(); radioState.snr = getRadioSnr(); @@ -310,24 +327,22 @@ void loop(void) * Watchdog for frame decoding stuck somewhere in the middle of a process */ if ( - qsp.protocolState != QSP_STATE_IDLE && - qsp.frameDecodingStartedAt + QSP_MAX_FRAME_DECODE_TIME < currentMillis + qsp.protocolState != QSP_STATE_IDLE && + qsp.frameDecodingStartedAt + QSP_MAX_FRAME_DECODE_TIME < currentMillis ) { qsp.protocolState = QSP_STATE_IDLE; } #ifdef DEVICE_MODE_TX - if (Serial1.available()) { - sbusRead(Serial1, &sbusInput); - } + txInput.loop(); if ( radioState.deviceState == RADIO_STATE_RX && qsp.protocolState == QSP_STATE_IDLE && qsp.lastTxSlotTimestamp + TX_TRANSMIT_SLOT_RATE < currentMillis ) { - + int8_t frameToSend = getFrameToTransmit(&qsp); #ifndef FORCE_TX_WITHOUT_INPUT @@ -335,7 +350,7 @@ void loop(void) * If module is not receiving data from radio, do not send RC DATA * This is the only way to trigger failsafe in that case */ - if (frameToSend == QSP_FRAME_RC_DATA && !isReceivingSbus(&sbusInput)) { + if (frameToSend == QSP_FRAME_RC_DATA && !txInput.isReceiving()) { frameToSend = -1; } #endif @@ -351,7 +366,7 @@ void loop(void) break; case QSP_FRAME_RC_DATA: - encodeRcDataPayload(&qsp, sbusInput.channels, PPM_INPUT_CHANNEL_COUNT); + encodeRcDataPayload(&qsp, txInput.channels, PPM_INPUT_CHANNEL_COUNT); break; } @@ -381,7 +396,7 @@ void loop(void) digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); } } - + /* * Main routine to answer to TX module */ @@ -443,10 +458,10 @@ void loop(void) } #ifdef DEVICE_MODE_TX - + buzzerProcess(TX_BUZZER_PIN, currentMillis, &buzzer); - // This routing enables when TX starts to receive signal from RX for a first time or after + // This routing enables when TX starts to receive signal from RX for a first time or after // failsafe if (txDeviceState.isReceiving == false && qsp.anyFrameRecivedAt != 0) { //TX module started to receive data @@ -457,7 +472,7 @@ void loop(void) //Here we detect failsafe state on TX module if ( - txDeviceState.isReceiving && + txDeviceState.isReceiving && qsp.anyFrameRecivedAt + TX_FAILSAFE_DELAY < currentMillis ) { txDeviceState.isReceiving = false; @@ -472,7 +487,7 @@ void loop(void) qsp.anyFrameRecivedAt = 0; } - //FIXME rxDeviceState should be resetted also in RC_HEALT frame is not received in a long period + //FIXME rxDeviceState should be resetted also in RC_HEALT frame is not received in a long period //Handle audible alarms if (qsp.deviceState == DEVICE_STATE_FAILSAFE) { @@ -494,36 +509,41 @@ void loop(void) currentMillis - lastOledTaskTime > OLED_UPDATE_RATE ) { lastOledTaskTime = currentMillis; - display.clearDisplay(); display.setTextColor(WHITE, BLACK); display.setCursor(0, 0); display.setTextSize(3); - display.print(radioState.rssi); + display.print(radioState.rssi); display.setCursor(18, 28); display.setTextSize(2); display.print(radioState.snr); - + display.setCursor(74, 0); display.setTextSize(3); - display.print(rxDeviceState.rssi); + display.print(rxDeviceState.rssi); display.setCursor(92, 28); display.setTextSize(2); - display.print(rxDeviceState.snr); + display.print(rxDeviceState.snr); + + #ifdef DEBUG_TX_INPUT_ON_OLED + display.setCursor(0, 48); + display.setTextSize(2); + display.print(txInput.channels[0]); + #endif display.setCursor(54, 48); display.setTextSize(2); - display.print(txDeviceState.roundtrip); + display.print(txDeviceState.roundtrip); - display.display(); + display.display(); } #endif #endif - + } diff --git a/lora.cpp b/crossbow/lora.cpp similarity index 100% rename from lora.cpp rename to crossbow/lora.cpp diff --git a/lora.h b/crossbow/lora.h similarity index 100% rename from lora.h rename to crossbow/lora.h diff --git a/main_variables.h b/crossbow/main_variables.h similarity index 100% rename from main_variables.h rename to crossbow/main_variables.h diff --git a/qsp.cpp b/crossbow/qsp.cpp similarity index 98% rename from qsp.cpp rename to crossbow/qsp.cpp index cc3b019..b125c56 100644 --- a/qsp.cpp +++ b/crossbow/qsp.cpp @@ -1,6 +1,5 @@ #include "Arduino.h" #include "variables.h" -#include void qspDecodeRcDataFrame(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceSate) { int temporaryPpmOutput[PPM_OUTPUT_CHANNEL_COUNT] = {0}; @@ -93,7 +92,7 @@ void decodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceSta /** * Encode 10 RC channels */ -void encodeRcDataPayload(QspConfiguration_t *qsp, int channels[], uint8_t noOfChannels) +void encodeRcDataPayload(QspConfiguration_t *qsp, volatile int16_t channels[], uint8_t noOfChannels) { for (uint8_t i = 0; i < noOfChannels; i++) { diff --git a/qsp.h b/crossbow/qsp.h similarity index 87% rename from qsp.h rename to crossbow/qsp.h index fff211a..d9ee307 100644 --- a/qsp.h +++ b/crossbow/qsp.h @@ -1,5 +1,4 @@ #include "Arduino.h" -#include void qspDecodeRcDataFrame(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceSate); void decodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState); @@ -8,7 +7,7 @@ uint8_t get10bitHighShift(uint8_t channel); uint8_t get10bitLowShift(uint8_t channel); void qspComputeCrc(QspConfiguration_t *qsp, uint8_t dataByte); void encodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState, volatile RadioState_t *radioState); -void encodeRcDataPayload(QspConfiguration_t *qsp, int channels[], uint8_t noOfChannels); +void encodeRcDataPayload(QspConfiguration_t *qsp, volatile int16_t channels[], uint8_t noOfChannels); void qspDecodeIncomingFrame( QspConfiguration_t *qsp, uint8_t incomingByte, diff --git a/sbus.cpp b/crossbow/sbus.cpp similarity index 66% rename from sbus.cpp rename to crossbow/sbus.cpp index b9e08a2..c1fb430 100644 --- a/sbus.cpp +++ b/crossbow/sbus.cpp @@ -1,5 +1,6 @@ #include "Arduino.h" #include "variables.h" +#include "sbus.h" #define SBUS_MIN_OFFSET 173 #define SBUS_MID_OFFSET 992 @@ -28,7 +29,7 @@ int mapSbusToChannel(int in) { return map(in, 173, 1811, 990, 2010); } -void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe){ +void sbusPreparePacket(uint8_t packet[], int16_t channels[], bool isSignalLoss, bool isFailsafe){ static int output[SBUS_CHANNEL_NUMBER] = {0}; @@ -76,7 +77,24 @@ void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool packet[24] = SBUS_FRAME_FOOTER; //Footer } -void sbusRead(HardwareSerial &_serial, SbusInput_t *sbusInput) { +SbusInput::SbusInput(HardwareSerial &serial) : _serial(serial) +{ +} + + +void SbusInput::loop(void) +{ + if (_serial.available()) { + sbusRead(); + } +} + +void SbusInput::start(void) +{ + _serial.begin(100000, SERIAL_8N2); +} + +void SbusInput::sbusRead() { static byte buffer[25]; static byte buffer_index = 0; @@ -103,33 +121,32 @@ void sbusRead(HardwareSerial &_serial, SbusInput_t *sbusInput) { } _goodFrames++; - sbusInput->channels[0] = ((buffer[1] |buffer[2]<<8) & 0x07FF); - sbusInput->channels[1] = ((buffer[2]>>3 |buffer[3]<<5) & 0x07FF); - sbusInput->channels[2] = ((buffer[3]>>6 |buffer[4]<<2 |buffer[5]<<10) & 0x07FF); - sbusInput->channels[3] = ((buffer[5]>>1 |buffer[6]<<7) & 0x07FF); - sbusInput->channels[4] = ((buffer[6]>>4 |buffer[7]<<4) & 0x07FF); - sbusInput->channels[5] = ((buffer[7]>>7 |buffer[8]<<1 |buffer[9]<<9) & 0x07FF); - sbusInput->channels[6] = ((buffer[9]>>2 |buffer[10]<<6) & 0x07FF); - sbusInput->channels[7] = ((buffer[10]>>5|buffer[11]<<3) & 0x07FF); - sbusInput->channels[8] = ((buffer[12] |buffer[13]<<8) & 0x07FF); - sbusInput->channels[9] = ((buffer[13]>>3|buffer[14]<<5) & 0x07FF); - sbusInput->channels[10] = ((buffer[14]>>6|buffer[15]<<2|buffer[16]<<10) & 0x07FF); - sbusInput->channels[11] = ((buffer[16]>>1|buffer[17]<<7) & 0x07FF); - sbusInput->channels[12] = ((buffer[17]>>4|buffer[18]<<4) & 0x07FF); - sbusInput->channels[13] = ((buffer[18]>>7|buffer[19]<<1|buffer[20]<<9) & 0x07FF); - sbusInput->channels[14] = ((buffer[20]>>2|buffer[21]<<6) & 0x07FF); - sbusInput->channels[15] = ((buffer[21]>>5|buffer[22]<<3) & 0x07FF); + channels[0] = ((buffer[1] |buffer[2]<<8) & 0x07FF); + channels[1] = ((buffer[2]>>3 |buffer[3]<<5) & 0x07FF); + channels[2] = ((buffer[3]>>6 |buffer[4]<<2 |buffer[5]<<10) & 0x07FF); + channels[3] = ((buffer[5]>>1 |buffer[6]<<7) & 0x07FF); + channels[4] = ((buffer[6]>>4 |buffer[7]<<4) & 0x07FF); + channels[5] = ((buffer[7]>>7 |buffer[8]<<1 |buffer[9]<<9) & 0x07FF); + channels[6] = ((buffer[9]>>2 |buffer[10]<<6) & 0x07FF); + channels[7] = ((buffer[10]>>5|buffer[11]<<3) & 0x07FF); + channels[8] = ((buffer[12] |buffer[13]<<8) & 0x07FF); + channels[9] = ((buffer[13]>>3|buffer[14]<<5) & 0x07FF); + channels[10] = ((buffer[14]>>6|buffer[15]<<2|buffer[16]<<10) & 0x07FF); + channels[11] = ((buffer[16]>>1|buffer[17]<<7) & 0x07FF); + channels[12] = ((buffer[17]>>4|buffer[18]<<4) & 0x07FF); + channels[13] = ((buffer[18]>>7|buffer[19]<<1|buffer[20]<<9) & 0x07FF); + channels[14] = ((buffer[20]>>2|buffer[21]<<6) & 0x07FF); + channels[15] = ((buffer[21]>>5|buffer[22]<<3) & 0x07FF); for (uint8_t channelIndex = 0; channelIndex < SBUS_CHANNEL_NUMBER; channelIndex++) { - sbusInput->channels[channelIndex] = mapSbusToChannel(sbusInput->channels[channelIndex]); + channels[channelIndex] = mapSbusToChannel(channels[channelIndex]); } - sbusInput->lastChannelReceivedAt = millis(); + _lastChannelReceivedAt = millis(); } - } } -bool isReceivingSbus(SbusInput_t *sbusInput) { - return !(millis() - sbusInput->lastChannelReceivedAt > SBUS_IS_RECEIVING_THRESHOLD); +bool SbusInput::isReceiving() { + return !(millis() - _lastChannelReceivedAt > SBUS_IS_RECEIVING_THRESHOLD); } \ No newline at end of file diff --git a/crossbow/sbus.h b/crossbow/sbus.h new file mode 100644 index 0000000..261b49e --- /dev/null +++ b/crossbow/sbus.h @@ -0,0 +1,25 @@ + +#ifndef SBUS_INPUT +#define SBUS_INPUT + +#include "Arduino.h" +#include "tx_input.h" + + +class SbusInput : public TxInput +{ + public: + SbusInput(HardwareSerial &serial); + void start(void); + void loop(void); + bool isReceiving(void); + private: + HardwareSerial &_serial; + uint32_t _lastChannelReceivedAt = 0; + void sbusRead(void); +}; + +void sbusPreparePacket(uint8_t packet[], int16_t channels[], bool isSignalLoss, bool isFailsafe); + +#endif + diff --git a/crossbow/tx_input.h b/crossbow/tx_input.h new file mode 100644 index 0000000..5e56099 --- /dev/null +++ b/crossbow/tx_input.h @@ -0,0 +1,21 @@ + +#ifndef TX_INPUT_H +#define TX_INPUT_H + +#include "Arduino.h" + +#define TX_INPUT_CHANNEL_COUNT 16 + +class TxInput +{ + public: + virtual ~TxInput() {} + int get(uint8_t channel) { return channels[channel]; }; + virtual void start(void) {}; + virtual void stop(void) {}; + virtual bool isReceiving(void) { return false; }; + virtual void loop(void) {}; + volatile static int16_t channels[TX_INPUT_CHANNEL_COUNT]; +}; + +#endif diff --git a/txbuzzer.cpp b/crossbow/txbuzzer.cpp similarity index 100% rename from txbuzzer.cpp rename to crossbow/txbuzzer.cpp diff --git a/txbuzzer.h b/crossbow/txbuzzer.h similarity index 100% rename from txbuzzer.h rename to crossbow/txbuzzer.h diff --git a/variables.h b/crossbow/variables.h similarity index 95% rename from variables.h rename to crossbow/variables.h index 245d1cf..2622352 100644 --- a/variables.h +++ b/crossbow/variables.h @@ -55,7 +55,6 @@ enum debugConfigFlags { }; #define PPM_INPUT_PIN 0 // Has to be one of Interrupt pins -#define PPM_INPUT_INTERRUPT 2 // For Pro Micro 1, For Pro Mini 0 #define PPM_INPUT_CHANNEL_COUNT 10 #define PPM_OUTPUT_CHANNEL_COUNT 10 @@ -125,8 +124,3 @@ struct QspConfiguration_t { uint32_t lastTxSlotTimestamp = 0; bool transmitWindowOpen = false; }; - -struct SbusInput_t { - int16_t channels[16] = {}; - uint32_t lastChannelReceivedAt = 0; -}; \ No newline at end of file diff --git a/sbus.h b/sbus.h deleted file mode 100644 index d9ac2c1..0000000 --- a/sbus.h +++ /dev/null @@ -1,5 +0,0 @@ -#include "Arduino.h" - -void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe); -void sbusRead(HardwareSerial &_serial, SbusInput_t *sbusInput); -bool isReceivingSbus(SbusInput_t *sbusInput); \ No newline at end of file