Reworked radio handling to early reject false packets
This commit is contained in:
2
.vscode/arduino.json
vendored
2
.vscode/arduino.json
vendored
@@ -1,6 +1,6 @@
|
|||||||
{
|
{
|
||||||
"board": "bsfrance:avr:lora32u4",
|
"board": "bsfrance:avr:lora32u4",
|
||||||
"sketch": "crossbow.ino",
|
"sketch": "crossbow.ino",
|
||||||
"port": "COM15",
|
"port": "COM17",
|
||||||
"output": "./build"
|
"output": "./build"
|
||||||
}
|
}
|
||||||
137
crossbow.ino
137
crossbow.ino
@@ -1,15 +1,16 @@
|
|||||||
// #define DEVICE_MODE_TX
|
#define DEVICE_MODE_TX
|
||||||
#define DEVICE_MODE_RX
|
// #define DEVICE_MODE_RX
|
||||||
|
|
||||||
#define FEATURE_TX_OLED
|
#define FEATURE_TX_OLED
|
||||||
|
#define FORCE_TX_WITHOUT_INPUT
|
||||||
|
|
||||||
// #define DEBUG_SERIAL
|
// #define DEBUG_SERIAL
|
||||||
// #define DEBUG_PING_PONG
|
// #define DEBUG_PING_PONG
|
||||||
// #define DEBUG_LED
|
// #define DEBUG_LED
|
||||||
// #define WAIT_FOR_SERIAL
|
|
||||||
|
|
||||||
#include <LoRa.h>
|
#include <LoRa.h>
|
||||||
#include "variables.h"
|
#include "variables.h"
|
||||||
|
#include "main_variables.h"
|
||||||
#include "qsp.h"
|
#include "qsp.h"
|
||||||
|
|
||||||
int ppm[16] = {0};
|
int ppm[16] = {0};
|
||||||
@@ -59,13 +60,11 @@ uint32_t lastOledTaskTime = 0;
|
|||||||
QspConfiguration_t qsp = {};
|
QspConfiguration_t qsp = {};
|
||||||
RxDeviceState_t rxDeviceState = {};
|
RxDeviceState_t rxDeviceState = {};
|
||||||
TxDeviceState_t txDeviceState = {};
|
TxDeviceState_t txDeviceState = {};
|
||||||
|
volatile RadioState_t radioState;
|
||||||
volatile bool doReadPacket = false;
|
|
||||||
|
|
||||||
uint8_t getRadioRssi(void)
|
uint8_t getRadioRssi(void)
|
||||||
{
|
{
|
||||||
//Map from -164:0 to 0:255
|
return 164 - constrain(LoRa.packetRssi() * -1, 0, 164);
|
||||||
return map(constrain(LoRa.packetRssi() * -1, 0, 164), 0, 164, 255, 0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t getRadioSnr(void)
|
uint8_t getRadioSnr(void)
|
||||||
@@ -73,18 +72,6 @@ uint8_t getRadioSnr(void)
|
|||||||
return (uint8_t) constrain(LoRa.packetSnr(), 0, 255);
|
return (uint8_t) constrain(LoRa.packetSnr(), 0, 255);
|
||||||
}
|
}
|
||||||
|
|
||||||
void radioPacketStart(void)
|
|
||||||
{
|
|
||||||
LoRa.beginPacket();
|
|
||||||
}
|
|
||||||
|
|
||||||
void radioPacketEnd(void)
|
|
||||||
{
|
|
||||||
LoRa.endPacket();
|
|
||||||
//After ending packet, put device into receive mode again
|
|
||||||
LoRa.receive();
|
|
||||||
}
|
|
||||||
|
|
||||||
void writeToRadio(uint8_t dataByte, QspConfiguration_t *qsp)
|
void writeToRadio(uint8_t dataByte, QspConfiguration_t *qsp)
|
||||||
{
|
{
|
||||||
//Compute CRC
|
//Compute CRC
|
||||||
@@ -108,12 +95,6 @@ void setup(void)
|
|||||||
qsp.deviceState = DEVICE_STATE_OK;
|
qsp.deviceState = DEVICE_STATE_OK;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef WAIT_FOR_SERIAL
|
|
||||||
while (!Serial) {
|
|
||||||
; // wait for serial port to connect. Needed for native USB
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Setup hardware
|
* Setup hardware
|
||||||
*/
|
*/
|
||||||
@@ -123,7 +104,7 @@ void setup(void)
|
|||||||
LORA32U4_DI0_PIN
|
LORA32U4_DI0_PIN
|
||||||
);
|
);
|
||||||
|
|
||||||
if (!LoRa.begin(870E6))
|
if (!LoRa.begin(radioState.frequency))
|
||||||
{
|
{
|
||||||
#ifdef DEBUG_SERIAL
|
#ifdef DEBUG_SERIAL
|
||||||
Serial.println("LoRa init failed. Check your connections.");
|
Serial.println("LoRa init failed. Check your connections.");
|
||||||
@@ -131,9 +112,9 @@ void setup(void)
|
|||||||
while (true);
|
while (true);
|
||||||
}
|
}
|
||||||
|
|
||||||
LoRa.setSignalBandwidth(250E3);
|
LoRa.setSignalBandwidth(radioState.loraBandwidth);
|
||||||
LoRa.setSpreadingFactor(7);
|
LoRa.setSpreadingFactor(radioState.loraSpreadingFactor);
|
||||||
LoRa.setCodingRate4(6);
|
LoRa.setCodingRate4(radioState.loraCodingRate);
|
||||||
LoRa.enableCrc();
|
LoRa.enableCrc();
|
||||||
LoRa.onReceive(onReceive);
|
LoRa.onReceive(onReceive);
|
||||||
LoRa.receive();
|
LoRa.receive();
|
||||||
@@ -187,44 +168,6 @@ void setup(void)
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
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
|
|
||||||
};
|
|
||||||
|
|
||||||
uint8_t currentSequenceIndex = 0;
|
uint8_t currentSequenceIndex = 0;
|
||||||
#define TRANSMIT_SEQUENCE_COUNT 16
|
#define TRANSMIT_SEQUENCE_COUNT 16
|
||||||
|
|
||||||
@@ -271,21 +214,13 @@ int8_t getFrameToTransmit(QspConfiguration_t *qsp) {
|
|||||||
void loop(void)
|
void loop(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
if (doReadPacket) {
|
if (radioState.bytesToRead != NO_DATA_TO_READ) {
|
||||||
int incomingByte;
|
|
||||||
while (incomingByte = LoRa.read(), incomingByte > -1)
|
for (uint8_t i = 0; i < radioState.bytesToRead; i++) {
|
||||||
{
|
qspDecodeIncomingFrame(&qsp, radioState.data[i], ppm, &rxDeviceState, &txDeviceState);
|
||||||
qspDecodeIncomingFrame(&qsp, incomingByte, ppm, &rxDeviceState, &txDeviceState);
|
|
||||||
}
|
}
|
||||||
#ifdef DEVICE_MODE_TX
|
|
||||||
txDeviceState.rssi = getRadioRssi();
|
radioState.bytesToRead = NO_DATA_TO_READ;
|
||||||
txDeviceState.snr = getRadioSnr();
|
|
||||||
#endif
|
|
||||||
#ifdef DEVICE_MODE_RX
|
|
||||||
rxDeviceState.rssi = getRadioRssi();
|
|
||||||
rxDeviceState.snr = getRadioSnr();
|
|
||||||
#endif
|
|
||||||
doReadPacket = false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t currentMillis = millis();
|
uint32_t currentMillis = millis();
|
||||||
@@ -310,10 +245,12 @@ void loop(void)
|
|||||||
|
|
||||||
int8_t frameToSend = getFrameToTransmit(&qsp);
|
int8_t frameToSend = getFrameToTransmit(&qsp);
|
||||||
|
|
||||||
|
#ifndef FORCE_TX_WITHOUT_INPUT
|
||||||
if (frameToSend == QSP_FRAME_RC_DATA && !ppmReader.isReceiving()) {
|
if (frameToSend == QSP_FRAME_RC_DATA && !ppmReader.isReceiving()) {
|
||||||
frameToSend = -1;
|
frameToSend = -1;
|
||||||
//FIXME uncomment to enable full Failsafe
|
//FIXME uncomment to enable full Failsafe
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (frameToSend > -1) {
|
if (frameToSend > -1) {
|
||||||
|
|
||||||
@@ -346,7 +283,7 @@ void loop(void)
|
|||||||
if (lastRxStateTaskTime + RX_TASK_HEALTH < currentMillis) {
|
if (lastRxStateTaskTime + RX_TASK_HEALTH < currentMillis) {
|
||||||
lastRxStateTaskTime = currentMillis;
|
lastRxStateTaskTime = currentMillis;
|
||||||
updateRxDeviceState(&rxDeviceState);
|
updateRxDeviceState(&rxDeviceState);
|
||||||
ppm[RSSI_CHANNEL - 1] = map(rxDeviceState.rssi, 0, 255, 1000, 2000);
|
ppm[RSSI_CHANNEL - 1] = map(rxDeviceState.rssi, 0, 164, 1000, 2000);
|
||||||
if (qsp.deviceState == DEVICE_STATE_FAILSAFE) {
|
if (qsp.deviceState == DEVICE_STATE_FAILSAFE) {
|
||||||
digitalWrite(LED_BUILTIN, HIGH);
|
digitalWrite(LED_BUILTIN, HIGH);
|
||||||
} else {
|
} else {
|
||||||
@@ -375,7 +312,7 @@ void loop(void)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case QSP_FRAME_RX_HEALTH:
|
case QSP_FRAME_RX_HEALTH:
|
||||||
encodeRxHealthPayload(&qsp, &rxDeviceState);
|
encodeRxHealthPayload(&qsp, &rxDeviceState, &radioState);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -400,9 +337,11 @@ void loop(void)
|
|||||||
|
|
||||||
if (qsp.canTransmit && transmitPayload)
|
if (qsp.canTransmit && transmitPayload)
|
||||||
{
|
{
|
||||||
radioPacketStart();
|
LoRa.beginPacket();
|
||||||
qspEncodeFrame(&qsp);
|
qspEncodeFrame(&qsp);
|
||||||
radioPacketEnd();
|
LoRa.endPacket();
|
||||||
|
//After ending packet, put device into receive mode again
|
||||||
|
LoRa.receive();
|
||||||
transmitPayload = false;
|
transmitPayload = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -445,9 +384,9 @@ void loop(void)
|
|||||||
} else if (txDeviceState.isReceiving && (rxDeviceState.flags & 0x1) == 1) {
|
} else if (txDeviceState.isReceiving && (rxDeviceState.flags & 0x1) == 1) {
|
||||||
//Failsafe reported by RX module
|
//Failsafe reported by RX module
|
||||||
buzzerContinousMode(BUZZER_MODE_SLOW_BEEP, &buzzer);
|
buzzerContinousMode(BUZZER_MODE_SLOW_BEEP, &buzzer);
|
||||||
} else if (txDeviceState.isReceiving && txDeviceState.rssi < 100) {
|
} else if (txDeviceState.isReceiving && radioState.rssi < 100) {
|
||||||
buzzerContinousMode(BUZZER_MODE_DOUBLE_CHIRP, &buzzer);
|
buzzerContinousMode(BUZZER_MODE_DOUBLE_CHIRP, &buzzer);
|
||||||
} else if (txDeviceState.isReceiving && txDeviceState.rssi < 128) {
|
} else if (txDeviceState.isReceiving && radioState.rssi < 128) {
|
||||||
buzzerContinousMode(BUZZER_MODE_CHIRP, &buzzer);
|
buzzerContinousMode(BUZZER_MODE_CHIRP, &buzzer);
|
||||||
} else {
|
} else {
|
||||||
buzzerContinousMode(BUZZER_MODE_OFF, &buzzer);
|
buzzerContinousMode(BUZZER_MODE_OFF, &buzzer);
|
||||||
@@ -464,15 +403,15 @@ void loop(void)
|
|||||||
display.setTextColor(WHITE, BLACK);
|
display.setTextColor(WHITE, BLACK);
|
||||||
display.setCursor(0, 0);
|
display.setCursor(0, 0);
|
||||||
display.setTextSize(3);
|
display.setTextSize(3);
|
||||||
display.print(map(txDeviceState.rssi, 0, 255, 0, 164));
|
display.print(radioState.rssi);
|
||||||
|
|
||||||
display.setCursor(18, 28);
|
display.setCursor(18, 28);
|
||||||
display.setTextSize(2);
|
display.setTextSize(2);
|
||||||
display.print(txDeviceState.snr);
|
display.print(radioState.snr);
|
||||||
|
|
||||||
display.setCursor(74, 0);
|
display.setCursor(74, 0);
|
||||||
display.setTextSize(3);
|
display.setTextSize(3);
|
||||||
display.print(map(rxDeviceState.rssi, 0, 255, 0, 164));
|
display.print(rxDeviceState.rssi);
|
||||||
|
|
||||||
display.setCursor(92, 28);
|
display.setCursor(92, 28);
|
||||||
display.setTextSize(2);
|
display.setTextSize(2);
|
||||||
@@ -496,5 +435,21 @@ void onReceive(int packetSize)
|
|||||||
if (packetSize == 0)
|
if (packetSize == 0)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
doReadPacket = true;
|
if (packetSize >= MIN_PACKET_SIZE && packetSize <= MAX_PACKET_SIZE) {
|
||||||
|
//We have a packet candidate that might contain a valid QSP packet
|
||||||
|
radioState.bytesToRead = packetSize;
|
||||||
|
for (int i = 0; i < packetSize; i++) {
|
||||||
|
radioState.data[i] = LoRa.read();
|
||||||
|
}
|
||||||
|
radioState.rssi = getRadioRssi();
|
||||||
|
radioState.snr = getRadioSnr();
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
If data has been read from radio, flush whetever else there might be left
|
||||||
|
Including packets that are not valid by putting rafio to sleep and then to
|
||||||
|
recive mode again
|
||||||
|
*/
|
||||||
|
LoRa.sleep();
|
||||||
|
LoRa.receive();
|
||||||
}
|
}
|
||||||
39
main_variables.h
Normal file
39
main_variables.h
Normal 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
|
||||||
|
};
|
||||||
6
qsp.cpp
6
qsp.cpp
@@ -54,9 +54,9 @@ void qspComputeCrc(QspConfiguration_t *qsp, uint8_t dataByte)
|
|||||||
qsp->crc ^= dataByte;
|
qsp->crc ^= dataByte;
|
||||||
}
|
}
|
||||||
|
|
||||||
void encodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState) {
|
void encodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState, RadioState_t *radioState) {
|
||||||
qsp->payload[0] = rxDeviceState->rssi;
|
qsp->payload[0] = radioState->rssi;
|
||||||
qsp->payload[1] = rxDeviceState->snr;
|
qsp->payload[1] = radioState->snr;
|
||||||
qsp->payload[2] = rxDeviceState->rxVoltage;
|
qsp->payload[2] = rxDeviceState->rxVoltage;
|
||||||
qsp->payload[3] = rxDeviceState->a1Voltage;
|
qsp->payload[3] = rxDeviceState->a1Voltage;
|
||||||
qsp->payload[4] = rxDeviceState->a2Voltage;
|
qsp->payload[4] = rxDeviceState->a2Voltage;
|
||||||
|
|||||||
2
qsp.h
2
qsp.h
@@ -7,7 +7,7 @@ void decodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceSta
|
|||||||
uint8_t get10bitHighShift(uint8_t channel);
|
uint8_t get10bitHighShift(uint8_t channel);
|
||||||
uint8_t get10bitLowShift(uint8_t channel);
|
uint8_t get10bitLowShift(uint8_t channel);
|
||||||
void qspComputeCrc(QspConfiguration_t *qsp, uint8_t dataByte);
|
void qspComputeCrc(QspConfiguration_t *qsp, uint8_t dataByte);
|
||||||
void encodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState);
|
void encodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState, RadioState_t *radioState);
|
||||||
void encodeRcDataPayload(QspConfiguration_t *qsp, PPMReader *ppmSource, uint8_t noOfChannels);
|
void encodeRcDataPayload(QspConfiguration_t *qsp, PPMReader *ppmSource, uint8_t noOfChannels);
|
||||||
void qspDecodeIncomingFrame(
|
void qspDecodeIncomingFrame(
|
||||||
QspConfiguration_t *qsp,
|
QspConfiguration_t *qsp,
|
||||||
|
|||||||
20
variables.h
20
variables.h
@@ -1,3 +1,5 @@
|
|||||||
|
#include "Arduino.h"
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define OLED_UPDATE_RATE 750
|
#define OLED_UPDATE_RATE 750
|
||||||
@@ -67,6 +69,22 @@ enum debugConfigFlags {
|
|||||||
#define PPM_SIGNAL_POSITIVE_STATE 1 //set polarity of the pulses: 1 is positive, 0 is negative
|
#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 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
|
||||||
|
|
||||||
|
struct RadioState_t {
|
||||||
|
uint32_t frequency = 867000000;
|
||||||
|
uint32_t loraBandwidth = 250000;
|
||||||
|
uint8_t loraSpreadingFactor = 7;
|
||||||
|
uint8_t loraCodingRate = 6;
|
||||||
|
int8_t bytesToRead = -1;
|
||||||
|
uint8_t rssi = 0;
|
||||||
|
uint8_t snr = 0;
|
||||||
|
uint8_t data[20] = {0}; //Max size of packet that can be processed in QSP
|
||||||
|
};
|
||||||
|
|
||||||
struct QspConfiguration_t {
|
struct QspConfiguration_t {
|
||||||
uint8_t protocolState = QSP_STATE_IDLE;
|
uint8_t protocolState = QSP_STATE_IDLE;
|
||||||
uint8_t crc = 0;
|
uint8_t crc = 0;
|
||||||
@@ -86,8 +104,6 @@ struct QspConfiguration_t {
|
|||||||
};
|
};
|
||||||
|
|
||||||
struct TxDeviceState_t {
|
struct TxDeviceState_t {
|
||||||
uint8_t rssi = 0;
|
|
||||||
uint8_t snr = 0;
|
|
||||||
uint8_t flags = 0;
|
uint8_t flags = 0;
|
||||||
uint32_t roundtrip = 0;
|
uint32_t roundtrip = 0;
|
||||||
bool isReceiving = false; //Indicates that TX module is receiving frames from RX module
|
bool isReceiving = false; //Indicates that TX module is receiving frames from RX module
|
||||||
|
|||||||
Reference in New Issue
Block a user