travis build

different configurations are specified in the configurations directory
 to select one copy it replcing the config.h file (as the travis script does)
 or change the include file directive in crossbow.ino
This commit is contained in:
Magnus Ivarsson
2018-02-05 19:54:40 +01:00
parent 2ac0ce9b49
commit d07a8a09d3
17 changed files with 225 additions and 90 deletions

17
crossbow/config.h Normal file
View File

@@ -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

View File

@@ -0,0 +1,6 @@
#ifndef CONFIG_H
#define CONFIG_H
#define DEVICE_MODE_RX
#endif

View File

@@ -0,0 +1,9 @@
#ifndef CONFIG_H
#define CONFIG_H
#define DEVICE_MODE_TX
#define FEATURE_TX_OLED
#define FEATURE_TX_INPUT_SBUS
#endif

570
crossbow/crossbow.ino Normal file
View File

@@ -0,0 +1,570 @@
/*
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/.
Copyright (c) 20xx, MPL Contributor1 contrib1@example.net
*/
#include "config.h"
#include "lora.h"
#include "variables.h"
#include "main_variables.h"
#include "qsp.h"
#include "sbus.h"
#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
#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];
#include "txbuzzer.h"
BuzzerState_t buzzer;
#ifdef FEATURE_TX_OLED
#include "Wire.h"
#define OLED_RESET -1
#include <Adafruit_SSD1306.h>
Adafruit_SSD1306 display(OLED_RESET);
uint32_t lastOledTaskTime = 0;
#endif
#endif
/*
* Main defines for device working in RX mode
*/
#ifdef DEVICE_MODE_RX
uint32_t sbusTime = 0;
uint8_t sbusPacket[SBUS_PACKET_LENGTH] = {0};
uint32_t lastRxStateTaskTime = 0;
#endif
/*
* Start of QSP protocol implementation
*/
QspConfiguration_t qsp = {};
RxDeviceState_t rxDeviceState = {};
TxDeviceState_t txDeviceState = {};
volatile RadioState_t radioState = {};
uint8_t tmpBuffer[MAX_PACKET_SIZE];
uint8_t getRadioRssi(void)
{
return 164 - constrain(LoRa.packetRssi() * -1, 0, 164);
}
uint8_t getRadioSnr(void)
{
return (uint8_t) constrain(LoRa.packetSnr(), 0, 255);
}
void onQspSuccess(QspConfiguration_t *qsp, TxDeviceState_t *txDeviceState, RxDeviceState_t *rxDeviceState, volatile RadioState_t *radioState) {
//If devide received a valid frame, that means it can start to talk
qsp->canTransmit = true;
//Store the last timestamp when frame was received
if (qsp->frameId < QSP_FRAME_COUNT) {
qsp->lastFrameReceivedAt[qsp->frameId] = millis();
}
qsp->anyFrameRecivedAt = millis();
switch (qsp->frameId) {
case QSP_FRAME_RC_DATA:
qspDecodeRcDataFrame(qsp, rxDeviceState);
break;
case QSP_FRAME_RX_HEALTH:
decodeRxHealthPayload(qsp, rxDeviceState);
break;
case QSP_FRAME_PING:
qsp->forcePongFrame = true;
break;
case QSP_FRAME_PONG:
txDeviceState->roundtrip = qsp->payload[0];
txDeviceState->roundtrip += (uint32_t) qsp->payload[1] << 8;
txDeviceState->roundtrip += (uint32_t) qsp->payload[2] << 16;
txDeviceState->roundtrip += (uint32_t) qsp->payload[3] << 24;
txDeviceState->roundtrip = (micros() - txDeviceState->roundtrip) / 1000;
break;
default:
//Unknown frame
//TODO do something in this case
break;
}
qsp->transmitWindowOpen = true;
}
void onQspFailure(QspConfiguration_t *qsp, TxDeviceState_t *txDeviceState, RxDeviceState_t *rxDeviceState, volatile RadioState_t *radioState) {
}
void setup(void)
{
#ifdef DEBUG_SERIAL
Serial.begin(115200);
#endif
qsp.onSuccessCallback = onQspSuccess;
qsp.onFailureCallback = onQspFailure;
#ifdef DEVICE_MODE_RX
qsp.deviceState = DEVICE_STATE_FAILSAFE;
#else
qsp.deviceState = DEVICE_STATE_OK;
#endif
/*
* Setup hardware
*/
LoRa.setPins(
LORA_SS_PIN,
LORA_RST_PIN,
LORA_DI0_PIN
);
if (!LoRa.begin(radioState.frequency))
{
#ifdef DEBUG_SERIAL
Serial.println("LoRa init failed. Check your connections.");
#endif
while (true);
}
//Configure LoRa module
LoRa.setSignalBandwidth(radioState.loraBandwidth);
LoRa.setSpreadingFactor(radioState.loraSpreadingFactor);
LoRa.setCodingRate4(radioState.loraCodingRate);
LoRa.setTxPower(radioState.loraTxPower);
LoRa.enableCrc();
//Setup ISR callback and start receiving
LoRa.onReceive(onReceive);
LoRa.receive();
radioState.deviceState = RADIO_STATE_RX;
#ifdef DEVICE_MODE_RX
//initiallize default ppm values
for (int i = 0; i < 16; i++)
{
rxDeviceState.channels[i] = PPM_CHANNEL_DEFAULT_VALUE;
}
pinMode(RX_ADC_PIN_1, INPUT);
pinMode(RX_ADC_PIN_2, INPUT);
pinMode(RX_ADC_PIN_3, INPUT);
/*
* Prepare Serial1 for S.Bus processing
*/
Serial1.begin(100000, SERIAL_8E2);
#endif
#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)
display.setTextSize(1);
display.setTextColor(WHITE);
display.clearDisplay();
display.display();
#endif
/*
* TX should start talking imediately after power up
*/
qsp.canTransmit = true;
pinMode(TX_BUZZER_PIN, OUTPUT);
//Play single tune to indicate power up
buzzerSingleMode(BUZZER_MODE_CHIRP, &buzzer);
/*
* Prepare Serial1 for S.Bus processing
*/
txInput.start();
#endif
pinMode(LED_BUILTIN, OUTPUT);
#ifdef DEBUG_SERIAL
qsp.debugConfig |= DEBUG_FLAG_SERIAL;
#endif
#ifdef DEBUG_LED
qsp.debugConfig |= DEBUG_FLAG_LED;
#endif
}
uint8_t currentSequenceIndex = 0;
#define TRANSMIT_SEQUENCE_COUNT 16
#ifdef DEVICE_MODE_RX
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;
}
return retVal;
}
#endif
#ifdef DEVICE_MODE_TX
int8_t getFrameToTransmit(QspConfiguration_t *qsp) {
int8_t retVal = txSendSequence[currentSequenceIndex];
currentSequenceIndex++;
if (currentSequenceIndex >= TRANSMIT_SEQUENCE_COUNT) {
currentSequenceIndex = 0;
}
return retVal;
}
#endif
/*
*
* Main loop starts here!
*
*/
void loop(void)
{
uint32_t currentMillis = millis();
/*
* Detect the moment when radio module stopped transmittig and put it
* back in to receive state
*/
if (
currentMillis > radioState.nextTxCheckMillis &&
radioState.deviceState == RADIO_STATE_TX &&
!LoRa.isTransmitting()
) {
LoRa.receive();
radioState.deviceState = RADIO_STATE_RX;
radioState.nextTxCheckMillis = currentMillis + 1; //We check of TX done every 1ms
}
if (radioState.bytesToRead != NO_DATA_TO_READ) {
LoRa.read(tmpBuffer, radioState.bytesToRead);
for (int i = 0; i < radioState.bytesToRead; i++) {
qspDecodeIncomingFrame(&qsp, tmpBuffer[i], &rxDeviceState, &txDeviceState, &radioState);
}
radioState.rssi = getRadioRssi();
radioState.snr = getRadioSnr();
//After reading, flush radio buffer, we have no need for whatever might be over there
LoRa.sleep();
LoRa.receive();
radioState.deviceState = RADIO_STATE_RX;
radioState.bytesToRead = NO_DATA_TO_READ;
}
bool transmitPayload = false;
/*
* 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;
}
#ifdef DEVICE_MODE_TX
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
/*
* 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 && !txInput.isReceiving()) {
frameToSend = -1;
}
#endif
if (frameToSend > -1) {
qsp.frameToSend = frameToSend;
qspClearPayload(&qsp);
switch (qsp.frameToSend) {
case QSP_FRAME_PING:
encodePingPayload(&qsp, micros());
break;
case QSP_FRAME_RC_DATA:
encodeRcDataPayload(&qsp, txInput.channels, PPM_INPUT_CHANNEL_COUNT);
break;
}
transmitPayload = true;
}
qsp.lastTxSlotTimestamp = currentMillis;
}
#endif
#ifdef DEVICE_MODE_RX
/*
* This routine updates RX device state and updates one of radio channels with RSSI value
*/
if (lastRxStateTaskTime + RX_TASK_HEALTH < currentMillis) {
lastRxStateTaskTime = currentMillis;
updateRxDeviceState(&rxDeviceState);
uint8_t output = constrain(radioState.rssi - 40, 0, 100);
rxDeviceState.channels[RSSI_CHANNEL - 1] = (output * 10) + 1000;
if (qsp.deviceState == DEVICE_STATE_FAILSAFE) {
digitalWrite(LED_BUILTIN, HIGH);
} else {
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
}
}
/*
* Main routine to answer to TX module
*/
if (qsp.transmitWindowOpen && qsp.protocolState == QSP_STATE_IDLE) {
qsp.transmitWindowOpen = false;
int8_t frameToSend = getFrameToTransmit(&qsp);
if (frameToSend > -1) {
qsp.frameToSend = frameToSend;
if (frameToSend != QSP_FRAME_PONG) {
qspClearPayload(&qsp);
}
switch (qsp.frameToSend) {
case QSP_FRAME_PONG:
/*
* Pong frame just responses with received payload
*/
break;
case QSP_FRAME_RX_HEALTH:
encodeRxHealthPayload(&qsp, &rxDeviceState, &radioState);
break;
}
transmitPayload = true;
}
}
if (currentMillis > sbusTime) {
sbusPreparePacket(sbusPacket, rxDeviceState.channels, false, (qsp.deviceState == DEVICE_STATE_FAILSAFE));
Serial1.write(sbusPacket, SBUS_PACKET_LENGTH);
sbusTime = currentMillis + SBUS_UPDATE_RATE;
}
if (qsp.lastFrameReceivedAt[QSP_FRAME_RC_DATA] + RX_FAILSAFE_DELAY < currentMillis) {
qsp.deviceState = DEVICE_STATE_FAILSAFE;
} else {
qsp.deviceState = DEVICE_STATE_OK;
}
#endif
if (qsp.canTransmit && transmitPayload)
{
uint8_t size;
LoRa.beginPacket();
//Prepare packet
qspEncodeFrame(&qsp, tmpBuffer, &size);
//Sent it to radio in one SPI transaction
LoRa.write(tmpBuffer, size);
LoRa.endPacketAsync();
//Set state to be able to detect the moment when TX is done
radioState.deviceState = RADIO_STATE_TX;
transmitPayload = false;
}
#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
// failsafe
if (txDeviceState.isReceiving == false && qsp.anyFrameRecivedAt != 0) {
//TX module started to receive data
buzzerSingleMode(BUZZER_MODE_DOUBLE_CHIRP, &buzzer);
txDeviceState.isReceiving = true;
qsp.deviceState = DEVICE_STATE_OK;
}
//Here we detect failsafe state on TX module
if (
txDeviceState.isReceiving &&
qsp.anyFrameRecivedAt + TX_FAILSAFE_DELAY < currentMillis
) {
txDeviceState.isReceiving = false;
rxDeviceState.a1Voltage = 0;
rxDeviceState.a2Voltage = 0;
rxDeviceState.rxVoltage = 0;
rxDeviceState.rssi = 0;
rxDeviceState.snr = 0;
rxDeviceState.flags = 0;
txDeviceState.roundtrip = 0;
qsp.deviceState = DEVICE_STATE_FAILSAFE;
qsp.anyFrameRecivedAt = 0;
}
//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) {
//Failsafe detected by TX
buzzerContinousMode(BUZZER_MODE_SLOW_BEEP, &buzzer);
} else if (txDeviceState.isReceiving && (rxDeviceState.flags & 0x1) == 1) {
//Failsafe reported by RX module
buzzerContinousMode(BUZZER_MODE_SLOW_BEEP, &buzzer);
} else if (txDeviceState.isReceiving && radioState.rssi < 60) {
buzzerContinousMode(BUZZER_MODE_DOUBLE_CHIRP, &buzzer); // RSSI below 60dB
} else if (txDeviceState.isReceiving && radioState.rssi < 80) {
buzzerContinousMode(BUZZER_MODE_CHIRP, &buzzer); // RSSI below 80dB
} else {
buzzerContinousMode(BUZZER_MODE_OFF, &buzzer);
}
#ifdef FEATURE_TX_OLED
if (
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.setCursor(18, 28);
display.setTextSize(2);
display.print(radioState.snr);
display.setCursor(74, 0);
display.setTextSize(3);
display.print(rxDeviceState.rssi);
display.setCursor(92, 28);
display.setTextSize(2);
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.display();
}
#endif
#endif
}
void onReceive(int packetSize)
{
/*
* We can start reading only when radio is not reading.
* If not reading, then we might start
*/
if (radioState.bytesToRead == NO_DATA_TO_READ) {
if (packetSize >= MIN_PACKET_SIZE && packetSize <= MAX_PACKET_SIZE) {
//We have a packet candidate that might contain a valid QSP packet
radioState.bytesToRead = packetSize;
} else {
/*
That packet was not very interesting, just flush it, we have no use
*/
LoRa.sleep();
LoRa.receive();
radioState.deviceState = RADIO_STATE_RX;
}
}
}

557
crossbow/lora.cpp Normal file
View File

@@ -0,0 +1,557 @@
/*
This file was derived from Arduino LoRa library originally licensed as MIT
https://github.com/sandeepmistry/arduino-LoRa
*/
#include "lora.h"
// registers
#define REG_FIFO 0x00
#define REG_OP_MODE 0x01
#define REG_FRF_MSB 0x06
#define REG_FRF_MID 0x07
#define REG_FRF_LSB 0x08
#define REG_PA_CONFIG 0x09
#define REG_LNA 0x0c
#define REG_FIFO_ADDR_PTR 0x0d
#define REG_FIFO_TX_BASE_ADDR 0x0e
#define REG_FIFO_RX_BASE_ADDR 0x0f
#define REG_FIFO_RX_CURRENT_ADDR 0x10
#define REG_IRQ_FLAGS 0x12
#define REG_RX_NB_BYTES 0x13
#define REG_PKT_RSSI_VALUE 0x1a
#define REG_PKT_SNR_VALUE 0x1b
#define REG_MODEM_CONFIG_1 0x1d
#define REG_MODEM_CONFIG_2 0x1e
#define REG_PREAMBLE_MSB 0x20
#define REG_PREAMBLE_LSB 0x21
#define REG_PAYLOAD_LENGTH 0x22
#define REG_MODEM_CONFIG_3 0x26
#define REG_RSSI_WIDEBAND 0x2c
#define REG_DETECTION_OPTIMIZE 0x31
#define REG_DETECTION_THRESHOLD 0x37
#define REG_SYNC_WORD 0x39
#define REG_DIO_MAPPING_1 0x40
#define REG_VERSION 0x42
// modes
#define MODE_LONG_RANGE_MODE 0x80
#define MODE_SLEEP 0x00
#define MODE_STDBY 0x01
#define MODE_TX 0x03
#define MODE_RX_CONTINUOUS 0x05
#define MODE_RX_SINGLE 0x06
// PA config
#define PA_BOOST 0x80
// IRQ masks
#define IRQ_TX_DONE_MASK 0x08
#define IRQ_PAYLOAD_CRC_ERROR_MASK 0x20
#define IRQ_RX_DONE_MASK 0x40
#define MAX_PKT_LENGTH 255
LoRaClass::LoRaClass() :
_spiSettings(8E6, MSBFIRST, SPI_MODE0),
_ss(LORA_DEFAULT_SS_PIN), _reset(LORA_DEFAULT_RESET_PIN), _dio0(LORA_DEFAULT_DIO0_PIN),
_frequency(0),
_packetIndex(0),
_implicitHeaderMode(0),
_onReceive(NULL)
{
}
int LoRaClass::begin(long frequency)
{
// setup pins
pinMode(_ss, OUTPUT);
pinMode(_reset, OUTPUT);
// perform reset
digitalWrite(_reset, LOW);
delay(10);
digitalWrite(_reset, HIGH);
delay(10);
// set SS high
digitalWrite(_ss, HIGH);
// start SPI
SPI.begin();
// check version
uint8_t version = readRegister(REG_VERSION);
if (version != 0x12) {
return 0;
}
// put in sleep mode
sleep();
// set frequency
setFrequency(frequency);
// set base addresses
writeRegister(REG_FIFO_TX_BASE_ADDR, 0);
writeRegister(REG_FIFO_RX_BASE_ADDR, 0);
// set LNA boost
writeRegister(REG_LNA, readRegister(REG_LNA) | 0x03);
// set auto AGC
writeRegister(REG_MODEM_CONFIG_3, 0x04);
// set output power to 17 dBm
setTxPower(17);
// put in standby mode
idle();
return 1;
}
void LoRaClass::end()
{
// put in sleep mode
sleep();
// stop SPI
SPI.end();
}
int LoRaClass::beginPacket(int implicitHeader)
{
// put in standby mode
idle();
if (implicitHeader) {
implicitHeaderMode();
} else {
explicitHeaderMode();
}
// reset FIFO address and paload length
writeRegister(REG_FIFO_ADDR_PTR, 0);
writeRegister(REG_PAYLOAD_LENGTH, 0);
return 1;
}
int LoRaClass::endPacket()
{
// put in TX mode
writeRegister(REG_OP_MODE, MODE_LONG_RANGE_MODE | MODE_TX);
// wait for TX done
while((readRegister(REG_IRQ_FLAGS) & IRQ_TX_DONE_MASK) == 0);
// clear IRQ's
writeRegister(REG_IRQ_FLAGS, IRQ_TX_DONE_MASK);
return 1;
}
//https://github.com/sandeepmistry/arduino-LoRa/pull/62/files
void LoRaClass::endPacketAsync()
{
// put in TX mode
writeRegister(REG_OP_MODE, MODE_LONG_RANGE_MODE | MODE_TX);
// apparently this grace time is required for the radio
delayMicroseconds(150);
}
//https://github.com/sandeepmistry/arduino-LoRa/pull/62/files
bool LoRaClass::isTransmitting()
{
if ((readRegister(REG_OP_MODE) & MODE_TX) == MODE_TX)
return true;
if (!(readRegister(REG_IRQ_FLAGS) & IRQ_TX_DONE_MASK) == 0)
// clear IRQ's
writeRegister(REG_IRQ_FLAGS, IRQ_TX_DONE_MASK);
return false;
}
int LoRaClass::parsePacket(int size)
{
int packetLength = 0;
int irqFlags = readRegister(REG_IRQ_FLAGS);
if (size > 0) {
implicitHeaderMode();
writeRegister(REG_PAYLOAD_LENGTH, size & 0xff);
} else {
explicitHeaderMode();
}
// clear IRQ's
writeRegister(REG_IRQ_FLAGS, irqFlags);
if ((irqFlags & IRQ_RX_DONE_MASK) && (irqFlags & IRQ_PAYLOAD_CRC_ERROR_MASK) == 0) {
// received a packet
_packetIndex = 0;
// read packet length
if (_implicitHeaderMode) {
packetLength = readRegister(REG_PAYLOAD_LENGTH);
} else {
packetLength = readRegister(REG_RX_NB_BYTES);
}
// set FIFO address to current RX address
writeRegister(REG_FIFO_ADDR_PTR, readRegister(REG_FIFO_RX_CURRENT_ADDR));
// put in standby mode
idle();
} else if (readRegister(REG_OP_MODE) != (MODE_LONG_RANGE_MODE | MODE_RX_SINGLE)) {
// not currently in RX mode
// reset FIFO address
writeRegister(REG_FIFO_ADDR_PTR, 0);
// put in single RX mode
writeRegister(REG_OP_MODE, MODE_LONG_RANGE_MODE | MODE_RX_SINGLE);
}
return packetLength;
}
int LoRaClass::packetRssi()
{
return (readRegister(REG_PKT_RSSI_VALUE) - (_frequency < 868E6 ? 164 : 157));
}
float LoRaClass::packetSnr()
{
return ((int8_t)readRegister(REG_PKT_SNR_VALUE)) * 0.25;
}
void LoRaClass::write(uint8_t data)
{
int currentLength = readRegister(REG_PAYLOAD_LENGTH);
writeRegister(REG_FIFO, data);
// update length
writeRegister(REG_PAYLOAD_LENGTH, currentLength + 1);
}
void LoRaClass::write(uint8_t buffer[], size_t size)
{
int currentLength = readRegister(REG_PAYLOAD_LENGTH);
// check size
if ((currentLength + size) > MAX_PKT_LENGTH) {
size = MAX_PKT_LENGTH - currentLength;
}
writeRegister(REG_FIFO, buffer, size);
// update length
writeRegister(REG_PAYLOAD_LENGTH, currentLength + size);
}
int LoRaClass::available()
{
return (readRegister(REG_RX_NB_BYTES) - _packetIndex);
}
int LoRaClass::fastRead() {
_packetIndex++;
return readRegister(REG_FIFO);
}
void LoRaClass::read(uint8_t buffer[], uint8_t size) {
_packetIndex += size;
return readRegister(REG_FIFO, buffer, size);
}
int LoRaClass::read()
{
if (!available()) {
return -1;
}
return fastRead();
}
void LoRaClass::onReceive(void(*callback)(int))
{
_onReceive = callback;
if (callback) {
writeRegister(REG_DIO_MAPPING_1, 0x00);
attachInterrupt(digitalPinToInterrupt(_dio0), LoRaClass::onDio0Rise, RISING);
} else {
detachInterrupt(digitalPinToInterrupt(_dio0));
}
}
void LoRaClass::receive(int size)
{
if (size > 0) {
implicitHeaderMode();
writeRegister(REG_PAYLOAD_LENGTH, size & 0xff);
} else {
explicitHeaderMode();
}
writeRegister(REG_OP_MODE, MODE_LONG_RANGE_MODE | MODE_RX_CONTINUOUS);
}
void LoRaClass::idle()
{
writeRegister(REG_OP_MODE, MODE_LONG_RANGE_MODE | MODE_STDBY);
}
void LoRaClass::sleep()
{
writeRegister(REG_OP_MODE, MODE_LONG_RANGE_MODE | MODE_SLEEP);
}
void LoRaClass::setTxPower(int level, int outputPin)
{
if (PA_OUTPUT_RFO_PIN == outputPin) {
// RFO
if (level < 0) {
level = 0;
} else if (level > 14) {
level = 14;
}
writeRegister(REG_PA_CONFIG, 0x70 | level);
} else {
// PA BOOST
if (level < 2) {
level = 2;
} else if (level > 17) {
level = 17;
}
writeRegister(REG_PA_CONFIG, PA_BOOST | (level - 2));
}
}
void LoRaClass::setFrequency(long frequency)
{
_frequency = frequency;
uint64_t frf = ((uint64_t)frequency << 19) / 32000000;
writeRegister(REG_FRF_MSB, (uint8_t)(frf >> 16));
writeRegister(REG_FRF_MID, (uint8_t)(frf >> 8));
writeRegister(REG_FRF_LSB, (uint8_t)(frf >> 0));
}
void LoRaClass::setSpreadingFactor(int sf)
{
if (sf < 6) {
sf = 6;
} else if (sf > 12) {
sf = 12;
}
if (sf == 6) {
writeRegister(REG_DETECTION_OPTIMIZE, 0xc5);
writeRegister(REG_DETECTION_THRESHOLD, 0x0c);
} else {
writeRegister(REG_DETECTION_OPTIMIZE, 0xc3);
writeRegister(REG_DETECTION_THRESHOLD, 0x0a);
}
writeRegister(REG_MODEM_CONFIG_2, (readRegister(REG_MODEM_CONFIG_2) & 0x0f) | ((sf << 4) & 0xf0));
}
void LoRaClass::setSignalBandwidth(long sbw)
{
int bw;
if (sbw <= 7.8E3) {
bw = 0;
} else if (sbw <= 10.4E3) {
bw = 1;
} else if (sbw <= 15.6E3) {
bw = 2;
} else if (sbw <= 20.8E3) {
bw = 3;
} else if (sbw <= 31.25E3) {
bw = 4;
} else if (sbw <= 41.7E3) {
bw = 5;
} else if (sbw <= 62.5E3) {
bw = 6;
} else if (sbw <= 125E3) {
bw = 7;
} else if (sbw <= 250E3) {
bw = 8;
} else /*if (sbw <= 250E3)*/ {
bw = 9;
}
writeRegister(REG_MODEM_CONFIG_1, (readRegister(REG_MODEM_CONFIG_1) & 0x0f) | (bw << 4));
}
void LoRaClass::setCodingRate4(int denominator)
{
if (denominator < 5) {
denominator = 5;
} else if (denominator > 8) {
denominator = 8;
}
int cr = denominator - 4;
writeRegister(REG_MODEM_CONFIG_1, (readRegister(REG_MODEM_CONFIG_1) & 0xf1) | (cr << 1));
}
void LoRaClass::setPreambleLength(long length)
{
writeRegister(REG_PREAMBLE_MSB, (uint8_t)(length >> 8));
writeRegister(REG_PREAMBLE_LSB, (uint8_t)(length >> 0));
}
void LoRaClass::setSyncWord(int sw)
{
writeRegister(REG_SYNC_WORD, sw);
}
void LoRaClass::enableCrc()
{
writeRegister(REG_MODEM_CONFIG_2, readRegister(REG_MODEM_CONFIG_2) | 0x04);
}
void LoRaClass::disableCrc()
{
writeRegister(REG_MODEM_CONFIG_2, readRegister(REG_MODEM_CONFIG_2) & 0xfb);
}
byte LoRaClass::random()
{
return readRegister(REG_RSSI_WIDEBAND);
}
void LoRaClass::setPins(int ss, int reset, int dio0)
{
_ss = ss;
_reset = reset;
_dio0 = dio0;
}
void LoRaClass::setSPIFrequency(uint32_t frequency)
{
_spiSettings = SPISettings(frequency, MSBFIRST, SPI_MODE0);
}
void LoRaClass::dumpRegisters(Stream& out)
{
for (int i = 0; i < 128; i++) {
out.print("0x");
out.print(i, HEX);
out.print(": 0x");
out.println(readRegister(i), HEX);
}
}
void LoRaClass::explicitHeaderMode()
{
_implicitHeaderMode = 0;
writeRegister(REG_MODEM_CONFIG_1, readRegister(REG_MODEM_CONFIG_1) & 0xfe);
}
void LoRaClass::implicitHeaderMode()
{
_implicitHeaderMode = 1;
writeRegister(REG_MODEM_CONFIG_1, readRegister(REG_MODEM_CONFIG_1) | 0x01);
}
void LoRaClass::handleDio0Rise()
{
int irqFlags = readRegister(REG_IRQ_FLAGS);
// clear IRQ's
writeRegister(REG_IRQ_FLAGS, irqFlags);
if ((irqFlags & IRQ_PAYLOAD_CRC_ERROR_MASK) == 0) {
// received a packet
_packetIndex = 0;
// read packet length
int packetLength = _implicitHeaderMode ? readRegister(REG_PAYLOAD_LENGTH) : readRegister(REG_RX_NB_BYTES);
// set FIFO address to current RX address
writeRegister(REG_FIFO_ADDR_PTR, readRegister(REG_FIFO_RX_CURRENT_ADDR));
if (_onReceive) {
_onReceive(packetLength);
}
// reset FIFO address
writeRegister(REG_FIFO_ADDR_PTR, 0);
}
}
uint8_t LoRaClass::readRegister(uint8_t address)
{
return singleTransfer(address & 0x7f, 0x00);
}
void LoRaClass::writeRegister(uint8_t address, uint8_t value)
{
singleTransfer(address | 0x80, value);
}
uint8_t LoRaClass::singleTransfer(uint8_t address, uint8_t value)
{
uint8_t response;
digitalWrite(_ss, LOW);
SPI.beginTransaction(_spiSettings);
SPI.transfer(address);
response = SPI.transfer(value);
SPI.endTransaction();
digitalWrite(_ss, HIGH);
return response;
}
void LoRaClass::writeRegister(uint8_t address, uint8_t buffer[], size_t size)
{
bufferTransfer(address | 0x80, buffer, size);
}
void LoRaClass::readRegister(uint8_t address, uint8_t buffer[], size_t size)
{
bufferTransfer(address & 0x7f, buffer, size);
}
void LoRaClass::bufferTransfer(uint8_t address, uint8_t buffer[], uint8_t size) {
uint8_t response;
digitalWrite(_ss, LOW);
SPI.beginTransaction(_spiSettings);
SPI.transfer(address);
SPI.transfer(buffer, size);
SPI.endTransaction();
digitalWrite(_ss, HIGH);
}
void LoRaClass::onDio0Rise()
{
LoRa.handleDio0Rise();
}
LoRaClass LoRa;

95
crossbow/lora.h Normal file
View File

@@ -0,0 +1,95 @@
/*
This file was derived from Arduino LoRa library originally licensed as MIT
https://github.com/sandeepmistry/arduino-LoRa
*/
#ifndef LORA_H
#define LORA_H
#include <Arduino.h>
#include <SPI.h>
#define LORA_DEFAULT_SS_PIN 10
#define LORA_DEFAULT_RESET_PIN 9
#define LORA_DEFAULT_DIO0_PIN 2
#define PA_OUTPUT_RFO_PIN 0
#define PA_OUTPUT_PA_BOOST_PIN 1
class LoRaClass {
public:
LoRaClass();
int begin(long frequency);
void end();
int beginPacket(int implicitHeader = false);
int endPacket();
void endPacketAsync();
bool isTransmitting();
int parsePacket(int size = 0);
int packetRssi();
float packetSnr();
void write(uint8_t byte);
void write(uint8_t buffer[], size_t size);
int available();
int read();
int fastRead();
void read(uint8_t buffer[], uint8_t size);
void onReceive(void(*callback)(int));
void receive(int size = 0);
void idle();
void sleep();
void setTxPower(int level, int outputPin = PA_OUTPUT_PA_BOOST_PIN);
void setFrequency(long frequency);
void setSpreadingFactor(int sf);
void setSignalBandwidth(long sbw);
void setCodingRate4(int denominator);
void setPreambleLength(long length);
void setSyncWord(int sw);
void enableCrc();
void disableCrc();
byte random();
void setPins(int ss = LORA_DEFAULT_SS_PIN, int reset = LORA_DEFAULT_RESET_PIN, int dio0 = LORA_DEFAULT_DIO0_PIN);
void setSPIFrequency(uint32_t frequency);
void dumpRegisters(Stream& out);
private:
void explicitHeaderMode();
void implicitHeaderMode();
void handleDio0Rise();
uint8_t readRegister(uint8_t address);
void writeRegister(uint8_t address, uint8_t value);
uint8_t singleTransfer(uint8_t address, uint8_t value);
void readRegister(uint8_t address, uint8_t buffer[], size_t size);
void writeRegister(uint8_t address, uint8_t buffer[], size_t size);
void bufferTransfer(uint8_t address, uint8_t buffer[], uint8_t size);
static void onDio0Rise();
private:
SPISettings _spiSettings;
int _ss;
int _reset;
int _dio0;
int _frequency;
int _packetIndex;
int _implicitHeaderMode;
void (*_onReceive)(int);
};
extern LoRaClass LoRa;
#endif

39
crossbow/main_variables.h Normal file
View File

@@ -0,0 +1,39 @@
#include "variables.h"
int8_t txSendSequence[16] = {
QSP_FRAME_PING,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA,
QSP_FRAME_RC_DATA
};
int8_t rxSendSequence[16] = {
QSP_FRAME_RX_HEALTH,
-1,
-1,
-1,
QSP_FRAME_RX_HEALTH,
-1,
-1,
-1,
QSP_FRAME_RX_HEALTH,
-1,
-1,
-1,
QSP_FRAME_RX_HEALTH,
-1,
-1,
-1
};

258
crossbow/qsp.cpp Normal file
View File

@@ -0,0 +1,258 @@
#include "Arduino.h"
#include "variables.h"
void qspDecodeRcDataFrame(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceSate) {
int temporaryPpmOutput[PPM_OUTPUT_CHANNEL_COUNT] = {0};
//TODO fix it, baby :)
temporaryPpmOutput[0] = (uint16_t) (((uint16_t) qsp->payload[0] << 2) & 0x3fc) | ((qsp->payload[1] >> 6) & 0x03);
temporaryPpmOutput[1] = (uint16_t) (((uint16_t) qsp->payload[1] << 4) & 0x3f0) | ((qsp->payload[2] >> 4) & 0x0F);
temporaryPpmOutput[2] = (uint16_t) (((uint16_t) qsp->payload[2] << 6) & 0x3c0) | ((qsp->payload[3] >> 2) & 0x3F);
temporaryPpmOutput[3] = (uint16_t) (((uint16_t) qsp->payload[3] << 8) & 0x300) | ((qsp->payload[4]) & 0xFF);
temporaryPpmOutput[4] = qsp->payload[5];
temporaryPpmOutput[5] = qsp->payload[6];
temporaryPpmOutput[6] = (qsp->payload[7] >> 4) & 0b00001111;
temporaryPpmOutput[7] = qsp->payload[7] & 0b00001111;
temporaryPpmOutput[8] = (qsp->payload[8] >> 4) & 0b00001111;
temporaryPpmOutput[9] = qsp->payload[8] & 0b00001111;
//10bit channels are passed as is
//8bit channels needs to be shifted left 2 places
temporaryPpmOutput[4] = temporaryPpmOutput[4] << 2;
temporaryPpmOutput[5] = temporaryPpmOutput[5] << 2;
//4bit channels needs to be shifted left 6 places
temporaryPpmOutput[6] = temporaryPpmOutput[6] << 6;
temporaryPpmOutput[7] = temporaryPpmOutput[7] << 6;
temporaryPpmOutput[8] = temporaryPpmOutput[8] << 6;
temporaryPpmOutput[9] = temporaryPpmOutput[9] << 6;
/*
* Copy tremporary to real output and add missing 1000
*/
for (uint8_t i = 0; i < PPM_OUTPUT_CHANNEL_COUNT; i++) {
rxDeviceSate->channels[i] = temporaryPpmOutput[i] + 1000;
}
}
uint8_t get10bitHighShift(uint8_t channel) {
return ((channel % 4) * 2) + 2;
}
uint8_t get10bitLowShift(uint8_t channel) {
return 8 - get10bitHighShift(channel);
}
uint8_t crc8_dvb_s2(uint8_t crc, uint8_t a)
{
crc ^= a;
for (int ii = 0; ii < 8; ++ii) {
if (crc & 0x80) {
crc = (crc << 1) ^ 0xD5;
} else {
crc = crc << 1;
}
}
return crc;
}
void qspComputeCrc(QspConfiguration_t *qsp, uint8_t dataByte)
{
qsp->crc = crc8_dvb_s2(qsp->crc, dataByte);
}
void encodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState, volatile RadioState_t *radioState) {
qsp->payload[0] = radioState->rssi;
qsp->payload[1] = radioState->snr;
qsp->payload[2] = rxDeviceState->rxVoltage;
qsp->payload[3] = rxDeviceState->a1Voltage;
qsp->payload[4] = rxDeviceState->a2Voltage;
uint8_t flags = 0;
if (qsp->deviceState == DEVICE_STATE_FAILSAFE) {
flags |= 0x01 << 0;
}
qsp->payload[5] = flags;
qsp->payloadLength = 6;
}
void decodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState) {
rxDeviceState->rssi = qsp->payload[0];
rxDeviceState->snr = qsp->payload[1];
rxDeviceState->rxVoltage = qsp->payload[2];
rxDeviceState->a1Voltage = qsp->payload[3];
rxDeviceState->a2Voltage = qsp->payload[4];
rxDeviceState->flags = qsp->payload[5];
}
/**
* Encode 10 RC channels
*/
void encodeRcDataPayload(QspConfiguration_t *qsp, volatile int16_t channels[], uint8_t noOfChannels)
{
for (uint8_t i = 0; i < noOfChannels; i++)
{
int cV = constrain(channels[i], 1000, 2000) - 1000;
uint16_t channelValue10 = cV & 0x03ff;
uint8_t channelValue8 = (cV >> 2) & 0xff;
uint8_t channelValue4 = (cV >> 6) & 0x0f;
if (i < 4)
{
/*
* First 4 channels encoded with 10 bits
*/
uint8_t bitIndex = i + (i / 4);
qsp->payload[bitIndex] |= (channelValue10 >> get10bitHighShift(i)) & (0x3ff >> get10bitHighShift(i));
qsp->payload[bitIndex + 1] |= (channelValue10 << get10bitLowShift(i)) & 0xff << (8 - get10bitHighShift(i));
}
else if (i == 4 || i == 5)
{
/*
* Next 2 with 8 bits
*/
qsp->payload[i + 1] |= channelValue8;
}
else if (i == 6)
{
/*
* And last 4 with 4 bits per channel
*/
qsp->payload[7] |= (channelValue4 << 4) & B11110000;
}
else if (i == 7)
{
qsp->payload[7] |= channelValue4 & B00001111;
}
else if (i == 8)
{
qsp->payload[8] |= (channelValue4 << 4) & B11110000;
}
else if (i == 9)
{
qsp->payload[8] |= channelValue4 & B00001111;
}
}
qsp->payloadLength = 9;
}
void qspClearPayload(QspConfiguration_t *qsp)
{
for (uint8_t i = 0; i < QSP_PAYLOAD_LENGTH; i++)
{
qsp->payload[i] = 0;
}
qsp->payloadLength = 0;
}
void qspDecodeIncomingFrame(
QspConfiguration_t *qsp,
uint8_t incomingByte,
RxDeviceState_t *rxDeviceState,
TxDeviceState_t *txDeviceState,
volatile RadioState_t *radioState
) {
static uint8_t frameId;
static uint8_t payloadLength;
static uint8_t receivedPayload;
if (qsp->protocolState == QSP_STATE_IDLE)
{
// Check if incomming channel ID is the same as receiver
if (incomingByte == CHANNEL_ID)
{
qsp->frameDecodingStartedAt = millis();
qsp->protocolState = QSP_STATE_CHANNEL_RECEIVED;
qsp->crc = 0;
qspComputeCrc(qsp, incomingByte);
qspClearPayload(qsp);
receivedPayload = 0;
}
else
{
qsp->protocolState = QSP_STATE_IDLE;
}
}
else if (qsp->protocolState == QSP_STATE_CHANNEL_RECEIVED)
{
//Frame ID and payload length
qspComputeCrc(qsp, incomingByte);
qsp->frameId = (incomingByte >> 4) & 0x0f;
payloadLength = incomingByte & 0x0f;
qsp->protocolState = QSP_STATE_FRAME_TYPE_RECEIVED;
}
else if (qsp->protocolState == QSP_STATE_FRAME_TYPE_RECEIVED)
{
if (receivedPayload >= QSP_PAYLOAD_LENGTH) {
qsp->protocolState = QSP_STATE_IDLE;
}
//Now it's time for payload
qspComputeCrc(qsp, incomingByte);
qsp->payload[receivedPayload] = incomingByte;
receivedPayload++;
if (receivedPayload == payloadLength)
{
qsp->protocolState = QSP_STATE_PAYLOAD_RECEIVED;
qsp->payloadLength = payloadLength;
}
}
else if (qsp->protocolState == QSP_STATE_PAYLOAD_RECEIVED)
{
if (qsp->crc == incomingByte) {
//CRC is correct
qsp->onSuccessCallback(qsp, txDeviceState, rxDeviceState, radioState);
} else {
qsp->onFailureCallback(qsp, txDeviceState, rxDeviceState, radioState);
}
// In both cases switch to listening for next preamble
qsp->protocolState = QSP_STATE_IDLE;
}
}
/**
* Encode frame is corrent format and write to hardware
*/
void qspEncodeFrame(QspConfiguration_t *qsp, uint8_t buffer[], uint8_t *size) {
//Zero CRC
qsp->crc = 0;
qspComputeCrc(qsp, CHANNEL_ID);
buffer[0] = CHANNEL_ID;
//Write frame type and length
uint8_t data = qsp->payloadLength & 0x0f;
data |= (qsp->frameToSend << 4) & 0xf0;
qspComputeCrc(qsp, data);
buffer[1] = data;
for (uint8_t i = 0; i < qsp->payloadLength; i++)
{
qspComputeCrc(qsp, qsp->payload[i]);
buffer[i + 2] = qsp->payload[i];
}
buffer[qsp->payloadLength + 2] = qsp->crc;
*size = qsp->payloadLength + 3; //Total length of QSP frame
}
void encodePingPayload(QspConfiguration_t *qsp, uint32_t currentMicros) {
qsp->payload[0] = currentMicros & 255;
qsp->payload[1] = (currentMicros >> 8) & 255;
qsp->payload[2] = (currentMicros >> 16) & 255;
qsp->payload[3] = (currentMicros >> 24) & 255;
qsp->payloadLength = 4;
}

21
crossbow/qsp.h Normal file
View File

@@ -0,0 +1,21 @@
#include "Arduino.h"
void qspDecodeRcDataFrame(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceSate);
void decodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState);
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, volatile int16_t channels[], uint8_t noOfChannels);
void qspDecodeIncomingFrame(
QspConfiguration_t *qsp,
uint8_t incomingByte,
RxDeviceState_t *rxDeviceState,
TxDeviceState_t *txDeviceState,
volatile RadioState_t *radioState
);
void qspClearPayload(QspConfiguration_t *qsp);
void qspEncodeFrame(QspConfiguration_t *qsp, uint8_t buffer[], uint8_t *size);
void encodePingPayload(QspConfiguration_t *qsp, uint32_t currentMicros);

152
crossbow/sbus.cpp Normal file
View File

@@ -0,0 +1,152 @@
#include "Arduino.h"
#include "variables.h"
#include "sbus.h"
#define SBUS_MIN_OFFSET 173
#define SBUS_MID_OFFSET 992
#define SBUS_MAX_OFFSET 1811
#define SBUS_CHANNEL_NUMBER 16
#define SBUS_PACKET_LENGTH 25
#define SBUS_FRAME_HEADER 0x0f
#define SBUS_FRAME_FOOTER 0x00
#define SBUS_FRAME_FOOTER_V2 0x04
#define SBUS_STATE_FAILSAFE 0x08
#define SBUS_STATE_SIGNALLOSS 0x04
#define SBUS_IS_RECEIVING_THRESHOLD 250 //If there is no SBUS input for 250ms, assume connection is broken
/*
Precomputed mapping from 990-2010 to 173:1811
equivalent to
map(channels[i], RC_CHANNEL_MIN, RC_CHANNEL_MAX, SBUS_MIN_OFFSET, SBUS_MAX_OFFSET);
*/
int mapChannelToSbus(int in) {
return (((long) in * 1605l) / 1000l) - 1417;
}
int mapSbusToChannel(int in) {
//TODO, speed up this processing
return map(in, 173, 1811, 990, 2010);
}
void sbusPreparePacket(uint8_t packet[], int16_t channels[], bool isSignalLoss, bool isFailsafe){
static int output[SBUS_CHANNEL_NUMBER] = {0};
/*
* Map 1000-2000 with middle at 1500 chanel values to
* 173-1811 with middle at 992 S.BUS protocol requires
*/
for (uint8_t i = 0; i < SBUS_CHANNEL_NUMBER; i++) {
output[i] = mapChannelToSbus(channels[i]);
}
uint8_t stateByte = 0x00;
if (isSignalLoss) {
stateByte |= SBUS_STATE_SIGNALLOSS;
}
if (isFailsafe) {
stateByte |= SBUS_STATE_FAILSAFE;
}
packet[0] = SBUS_FRAME_HEADER; //Header
packet[1] = (uint8_t) (output[0] & 0x07FF);
packet[2] = (uint8_t) ((output[0] & 0x07FF)>>8 | (output[1] & 0x07FF)<<3);
packet[3] = (uint8_t) ((output[1] & 0x07FF)>>5 | (output[2] & 0x07FF)<<6);
packet[4] = (uint8_t) ((output[2] & 0x07FF)>>2);
packet[5] = (uint8_t) ((output[2] & 0x07FF)>>10 | (output[3] & 0x07FF)<<1);
packet[6] = (uint8_t) ((output[3] & 0x07FF)>>7 | (output[4] & 0x07FF)<<4);
packet[7] = (uint8_t) ((output[4] & 0x07FF)>>4 | (output[5] & 0x07FF)<<7);
packet[8] = (uint8_t) ((output[5] & 0x07FF)>>1);
packet[9] = (uint8_t) ((output[5] & 0x07FF)>>9 | (output[6] & 0x07FF)<<2);
packet[10] = (uint8_t) ((output[6] & 0x07FF)>>6 | (output[7] & 0x07FF)<<5);
packet[11] = (uint8_t) ((output[7] & 0x07FF)>>3);
packet[12] = (uint8_t) ((output[8] & 0x07FF));
packet[13] = (uint8_t) ((output[8] & 0x07FF)>>8 | (output[9] & 0x07FF)<<3);
packet[14] = (uint8_t) ((output[9] & 0x07FF)>>5 | (output[10] & 0x07FF)<<6);
packet[15] = (uint8_t) ((output[10] & 0x07FF)>>2);
packet[16] = (uint8_t) ((output[10] & 0x07FF)>>10 | (output[11] & 0x07FF)<<1);
packet[17] = (uint8_t) ((output[11] & 0x07FF)>>7 | (output[12] & 0x07FF)<<4);
packet[18] = (uint8_t) ((output[12] & 0x07FF)>>4 | (output[13] & 0x07FF)<<7);
packet[19] = (uint8_t) ((output[13] & 0x07FF)>>1);
packet[20] = (uint8_t) ((output[13] & 0x07FF)>>9 | (output[14] & 0x07FF)<<2);
packet[21] = (uint8_t) ((output[14] & 0x07FF)>>6 | (output[15] & 0x07FF)<<5);
packet[22] = (uint8_t) ((output[15] & 0x07FF)>>3);
packet[23] = stateByte; //Flags byte
packet[24] = SBUS_FRAME_FOOTER; //Footer
}
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;
static uint32_t _decoderErrorFrames;
static uint32_t _goodFrames;
while (_serial.available()) {
byte rx = _serial.read();
if (buffer_index == 0 && rx != SBUS_FRAME_HEADER) {
//incorrect start byte, out of sync
_decoderErrorFrames++;
continue;
}
buffer[buffer_index] = rx;
buffer_index++;
if (buffer_index == 25) {
buffer_index = 0;
if (buffer[24] != SBUS_FRAME_FOOTER) {
//incorrect end byte, out of sync
_decoderErrorFrames++;
continue;
}
_goodFrames++;
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++) {
channels[channelIndex] = mapSbusToChannel(channels[channelIndex]);
}
_lastChannelReceivedAt = millis();
}
}
}
bool SbusInput::isReceiving() {
return !(millis() - _lastChannelReceivedAt > SBUS_IS_RECEIVING_THRESHOLD);
}

25
crossbow/sbus.h Normal file
View File

@@ -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

21
crossbow/tx_input.h Normal file
View File

@@ -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

66
crossbow/txbuzzer.cpp Normal file
View File

@@ -0,0 +1,66 @@
#include "Arduino.h"
#include "txbuzzer.h"
/**
* This method plays selected pattern only once
* It disables continious mode
*/
void buzzerSingleMode(uint8_t mode, BuzzerState_t *buzzer) {
buzzer->singleModeEnabled = true;
buzzer->enabled = false;
buzzer->mode = mode;
buzzer->tick = 0;
}
void buzzerContinousMode(uint8_t mode, BuzzerState_t *buzzer) {
buzzer->singleModeEnabled = false;
buzzer->enabled = true;
buzzer->mode = mode;
}
void buzzerProcess(uint8_t pin, uint32_t timestamp, BuzzerState_t *buzzer)
{
if (!buzzer->enabled && !buzzer->singleModeEnabled)
{
digitalWrite(pin, LOW);
return;
}
if (timestamp > buzzer->updateTime)
{
int8_t currentPattern = buzzer->pattern[buzzer->mode][buzzer->element];
if (currentPattern == PATTERN_CYCLE_OFF)
{
digitalWrite(pin, LOW);
}
else if (currentPattern == PATTERN_CYCLE_ON)
{
digitalWrite(pin, HIGH);
}
else if (currentPattern == PATTERN_CYCLE_IGNORE || currentPattern == buzzer->tick)
{
if (currentPattern != PATTERN_CYCLE_IGNORE)
{
digitalWrite(pin, !digitalRead(pin));
}
buzzer->element++;
if (buzzer->element == PATTERN_ELEMENT_NUMBER)
{
buzzer->element = 0;
}
}
buzzer->tick++;
if (buzzer->tick >= buzzer->patternMaxTick)
{
buzzer->tick = 0;
buzzer->singleModeEnabled = false;
}
buzzer->updateTime = timestamp + buzzer->patternTickPerdiod;
}
};

46
crossbow/txbuzzer.h Normal file
View File

@@ -0,0 +1,46 @@
#pragma once
#include "Arduino.h"
#define PATTERN_CYCLE_OFF 127
#define PATTERN_CYCLE_ON -1
#define PATTERN_CYCLE_IGNORE -2
#define PATTERN_MODES_NUMBER 6
#define PATTERN_ELEMENT_NUMBER 4
enum {
BUZZER_MODE_OFF = 0,
BUZZER_MODE_CONTINUOUS = 1,
BUZZER_MODE_SLOW_BEEP = 2,
BUZZER_MODE_FAST_BEEP = 3,
BUZZER_MODE_CHIRP = 4,
BUZZER_MODE_DOUBLE_CHIRP = 5
};
struct BuzzerState_t {
bool enabled = false; //Continous mode buzzer
bool singleModeEnabled = false;
uint8_t mode = BUZZER_MODE_OFF;
uint32_t updateTime = 0;
uint8_t tick = 0;
uint8_t element = 0;
const uint8_t patternMaxTick = 20;
const uint8_t patternTickPerdiod = 75;
const int8_t pattern[PATTERN_MODES_NUMBER][PATTERN_ELEMENT_NUMBER] = {
{PATTERN_CYCLE_OFF},
{PATTERN_CYCLE_ON},
{0, 7, 10, 17},
{0, 4, 10, 14},
{0, 1, PATTERN_CYCLE_IGNORE, PATTERN_CYCLE_IGNORE},
{0, 1, 2, 3}
};
};
void buzzerSingleMode(uint8_t mode, BuzzerState_t *buzzer);
void buzzerContinousMode(uint8_t mode, BuzzerState_t *buzzer);
void buzzerProcess(uint8_t pin, uint32_t timestamp, BuzzerState_t *buzzer);

126
crossbow/variables.h Normal file
View File

@@ -0,0 +1,126 @@
#include "Arduino.h"
#pragma once
#define OLED_UPDATE_RATE 750
#define SBUS_UPDATE_RATE 15 //ms
#define SBUS_PACKET_LENGTH 25
#define RC_CHANNEL_MIN 990
#define RC_CHANNEL_MAX 2010
#define RX_TASK_HEALTH 200 //5Hz should be enough
#define RSSI_CHANNEL 11
#define TX_TRANSMIT_SLOT_RATE 67 //ms
#define RX_FAILSAFE_DELAY (TX_TRANSMIT_SLOT_RATE * 8)
#define TX_FAILSAFE_DELAY (RX_FAILSAFE_DELAY * 4)
#define CHANNEL_ID 0x01
#define QSP_PAYLOAD_LENGTH 32
#define QSP_MAX_FRAME_DECODE_TIME 10 //max time that frame can be decoded in ms
#define QSP_FRAME_RC_DATA 0x0
#define QSP_FRAME_RX_HEALTH 0x1
#define QSP_FRAME_GET_RX_CONFIG 0x2
#define QSP_FRAME_RX_CONFIG 0x3
#define QSP_FRAME_SET_RX_CONFIG 0x4
#define QSP_FRAME_PING 0x5
#define QSP_FRAME_PONG 0x6
#define QSP_FRAME_COUNT 0x7
#define RX_ADC_PIN_1 A0
#define RX_ADC_PIN_2 A1
#define RX_ADC_PIN_3 A2
enum dataStates {
QSP_STATE_IDLE,
QSP_STATE_CHANNEL_RECEIVED,
QSP_STATE_FRAME_TYPE_RECEIVED,
QSP_STATE_PAYLOAD_RECEIVED,
QSP_STATE_CRC_RECEIVED
};
enum deviceStates {
DEVICE_STATE_OK,
DEVICE_STATE_FAILSAFE,
DEVICE_STATE_UNDETERMINED
};
enum debugConfigFlags {
DEBUG_FLAG_SERIAL = 0b00000001,
DEBUG_FLAG_LED = 0b00000010
};
#define PPM_INPUT_PIN 0 // Has to be one of Interrupt pins
#define PPM_INPUT_CHANNEL_COUNT 10
#define PPM_OUTPUT_CHANNEL_COUNT 10
#define TX_BUZZER_PIN A5
#define PPM_CHANNEL_DEFAULT_VALUE 1500 //set the default servo value
#define PPM_FRAME_LENGTH 30500 //set the PPM frame length in microseconds (1ms = 1000µs)
#define PPM_PULSE_LENGTH 300 //set the pulse length
#define PPM_OUTPUT_MULTIPLIER 1 //1 for 8MHz RX, 2 for 16MHz RX
#define PPM_SIGNAL_POSITIVE_STATE 1 //set polarity of the pulses: 1 is positive, 0 is negative
#define PPM_OUTPUT_PIN 10 //set PPM signal output pin on the arduino
#define MIN_PACKET_SIZE 3 //Min theorethical size of valid packet
#define MAX_PACKET_SIZE 20 //Max theorethical size of valid packet
#define NO_DATA_TO_READ -1
#define RADIO_STATE_TX 1
#define RADIO_STATE_RX 2
struct RadioState_t {
uint32_t frequency = 867000000;
uint32_t loraBandwidth = 250000;
uint8_t loraSpreadingFactor = 7;
uint8_t loraCodingRate = 6;
uint8_t loraTxPower = 17; // Defines output power of TX, defined in dBm range from 2-17
int8_t bytesToRead = -1;
uint8_t rssi = 0;
uint8_t snr = 0;
uint8_t deviceState = RADIO_STATE_RX;
uint32_t nextTxCheckMillis = 0;
};
struct TxDeviceState_t {
uint8_t flags = 0;
uint32_t roundtrip = 0;
bool isReceiving = false; //Indicates that TX module is receiving frames from RX module
};
struct RxDeviceState_t {
uint8_t rssi = 0;
uint8_t snr = 0;
uint8_t rxVoltage = 0;
uint8_t a1Voltage = 0;
uint8_t a2Voltage = 0;
uint8_t flags = 0;
int16_t channels[16] = {};
};
struct QspConfiguration_t {
uint8_t protocolState = QSP_STATE_IDLE;
uint8_t crc = 0;
uint8_t payload[QSP_PAYLOAD_LENGTH] = {0};
uint8_t payloadLength = 0;
uint8_t frameToSend = 0;
uint8_t frameId = 0;
uint32_t lastFrameReceivedAt[QSP_FRAME_COUNT] = {0};
uint32_t anyFrameRecivedAt = 0;
uint8_t deviceState = DEVICE_STATE_UNDETERMINED;
void (* onSuccessCallback)(QspConfiguration_t*, TxDeviceState_t*, RxDeviceState_t*, volatile RadioState_t*);
void (* onFailureCallback)(QspConfiguration_t*, TxDeviceState_t*, RxDeviceState_t*, volatile RadioState_t*);
bool canTransmit = false;
bool forcePongFrame = false;
uint8_t debugConfig = 0;
uint32_t frameDecodingStartedAt = 0;
uint32_t lastTxSlotTimestamp = 0;
bool transmitWindowOpen = false;
};