Merge remote-tracking branch 'origin/master' into tx-sbus

This commit is contained in:
Pawel Spychalski (DzikuVx)
2018-01-02 21:25:22 +01:00
8 changed files with 82 additions and 23 deletions

View File

@@ -1,6 +1,6 @@
{ {
"board": "bsfrance:avr:lora32u4", "board": "bsfrance:avr:lora32u4",
"sketch": "crossbow.ino", "sketch": "crossbow.ino",
"port": "COM4", "port": "COM3",
"output": "./build" "output": "../build"
} }

View File

@@ -3,12 +3,17 @@
{ {
"name": "Win32", "name": "Win32",
"includePath": [ "includePath": [
"C:\\Users\\pspyc\\AppData\\Local\\Arduino15\\packages\\arduino\\hardware\\avr\\1.6.19\\cores\\arduino" "${workspaceRoot}",
"C:\\Program Files (x86)\\Arduino\\hardware\\arduino\\avr\\cores\\arduino",
"C:\\Program Files (x86)\\Arduino\\hardware\\arduino\\avr\\libraries",
"C:\\Users\\pspyc\\Documents\\Arduino\\libraries",
"C:\\Users\\pspyc\\Documents\\Arduino\\libraries\\PPMReader"
], ],
"browse": { "browse": {
"limitSymbolsToIncludedHeaders": false, "limitSymbolsToIncludedHeaders": false,
"path": [ "path": [
"C:\\Users\\pspyc\\AppData\\Local\\Arduino15\\packages\\arduino\\hardware\\avr\\1.6.19\\cores\\arduino", "C:\\Program Files (x86)\\Arduino\\hardware\\arduino\\avr\\cores\\arduino",
"C:\\Program Files (x86)\\Arduino\\hardware\\arduino\\avr\\libraries",
"${workspaceRoot}", "${workspaceRoot}",
"C:\\Users\\pspyc\\Documents\\Arduino\\libraries" "C:\\Users\\pspyc\\Documents\\Arduino\\libraries"
] ]

View File

@@ -1,10 +1,10 @@
// #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 FORCE_TX_WITHOUT_INPUT
// #define DEBUG_SERIAL #define DEBUG_SERIAL
// #define DEBUG_PING_PONG // #define DEBUG_PING_PONG
// #define DEBUG_LED // #define DEBUG_LED
@@ -60,7 +60,7 @@ 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 RadioState_t radioState = {};
uint8_t tmpBuffer[MAX_PACKET_SIZE]; uint8_t tmpBuffer[MAX_PACKET_SIZE];
@@ -74,7 +74,7 @@ uint8_t getRadioSnr(void)
return (uint8_t) constrain(LoRa.packetSnr(), 0, 255); return (uint8_t) constrain(LoRa.packetSnr(), 0, 255);
} }
void onQspSuccess(QspConfiguration_t *qsp, TxDeviceState_t *txDeviceState, RxDeviceState_t *rxDeviceState, RadioState_t *radioState) { 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 //If devide received a valid frame, that means it can start to talk
qsp->canTransmit = true; qsp->canTransmit = true;
@@ -114,7 +114,7 @@ void onQspSuccess(QspConfiguration_t *qsp, TxDeviceState_t *txDeviceState, RxDev
qsp->transmitWindowOpen = true; qsp->transmitWindowOpen = true;
} }
void onQspFailure(QspConfiguration_t *qsp, TxDeviceState_t *txDeviceState, RxDeviceState_t *rxDeviceState, RadioState_t *radioState) { void onQspFailure(QspConfiguration_t *qsp, TxDeviceState_t *txDeviceState, RxDeviceState_t *rxDeviceState, volatile RadioState_t *radioState) {
} }
@@ -160,6 +160,7 @@ void setup(void)
//Setup ISR callback and start receiving //Setup ISR callback and start receiving
LoRa.onReceive(onReceive); LoRa.onReceive(onReceive);
LoRa.receive(); LoRa.receive();
radioState.deviceState = RADIO_STATE_RX;
#ifdef DEVICE_MODE_RX #ifdef DEVICE_MODE_RX
//initiallize default ppm values //initiallize default ppm values
@@ -253,9 +254,30 @@ int8_t getFrameToTransmit(QspConfiguration_t *qsp) {
} }
#endif #endif
/*
*
* Main loop starts here!
*
*/
void loop(void) 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) { if (radioState.bytesToRead != NO_DATA_TO_READ) {
LoRa.read(tmpBuffer, radioState.bytesToRead); LoRa.read(tmpBuffer, radioState.bytesToRead);
@@ -269,11 +291,11 @@ void loop(void)
//After reading, flush radio buffer, we have no need for whatever might be over there //After reading, flush radio buffer, we have no need for whatever might be over there
LoRa.sleep(); LoRa.sleep();
LoRa.receive(); LoRa.receive();
radioState.deviceState = RADIO_STATE_RX;
radioState.bytesToRead = NO_DATA_TO_READ; radioState.bytesToRead = NO_DATA_TO_READ;
} }
uint32_t currentMillis = millis();
bool transmitPayload = false; bool transmitPayload = false;
/* /*
@@ -293,6 +315,7 @@ void loop(void)
} }
if ( if (
radioState.deviceState == RADIO_STATE_RX &&
qsp.protocolState == QSP_STATE_IDLE && qsp.protocolState == QSP_STATE_IDLE &&
qsp.lastTxSlotTimestamp + TX_TRANSMIT_SLOT_RATE < currentMillis qsp.lastTxSlotTimestamp + TX_TRANSMIT_SLOT_RATE < currentMillis
) { ) {
@@ -400,9 +423,11 @@ void loop(void)
qspEncodeFrame(&qsp, tmpBuffer, &size); qspEncodeFrame(&qsp, tmpBuffer, &size);
//Sent it to radio in one SPI transaction //Sent it to radio in one SPI transaction
LoRa.write(tmpBuffer, size); LoRa.write(tmpBuffer, size);
LoRa.endPacket(); LoRa.endPacketAsync();
//After ending packet, put device into receive mode again
LoRa.receive(); //Set state to be able to detect the moment when TX is done
radioState.deviceState = RADIO_STATE_TX;
transmitPayload = false; transmitPayload = false;
} }
@@ -493,9 +518,6 @@ void loop(void)
void onReceive(int packetSize) void onReceive(int packetSize)
{ {
if (packetSize == 0)
return;
/* /*
* We can start reading only when radio is not reading. * We can start reading only when radio is not reading.
* If not reading, then we might start * If not reading, then we might start
@@ -511,6 +533,7 @@ void onReceive(int packetSize)
*/ */
LoRa.sleep(); LoRa.sleep();
LoRa.receive(); LoRa.receive();
radioState.deviceState = RADIO_STATE_RX;
} }
} }
} }

View File

@@ -153,6 +153,29 @@ int LoRaClass::endPacket()
return 1; 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 LoRaClass::parsePacket(int size)
{ {
int packetLength = 0; int packetLength = 0;

3
lora.h
View File

@@ -26,6 +26,9 @@ public:
int beginPacket(int implicitHeader = false); int beginPacket(int implicitHeader = false);
int endPacket(); int endPacket();
void endPacketAsync();
bool isTransmitting();
int parsePacket(int size = 0); int parsePacket(int size = 0);
int packetRssi(); int packetRssi();
float packetSnr(); float packetSnr();

View File

@@ -67,7 +67,7 @@ void qspComputeCrc(QspConfiguration_t *qsp, uint8_t dataByte)
qsp->crc = crc8_dvb_s2(qsp->crc, dataByte); qsp->crc = crc8_dvb_s2(qsp->crc, dataByte);
} }
void encodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState, RadioState_t *radioState) { void encodeRxHealthPayload(QspConfiguration_t *qsp, RxDeviceState_t *rxDeviceState, volatile RadioState_t *radioState) {
qsp->payload[0] = radioState->rssi; qsp->payload[0] = radioState->rssi;
qsp->payload[1] = radioState->snr; qsp->payload[1] = radioState->snr;
qsp->payload[2] = rxDeviceState->rxVoltage; qsp->payload[2] = rxDeviceState->rxVoltage;
@@ -161,7 +161,7 @@ void qspDecodeIncomingFrame(
uint8_t incomingByte, uint8_t incomingByte,
RxDeviceState_t *rxDeviceState, RxDeviceState_t *rxDeviceState,
TxDeviceState_t *txDeviceState, TxDeviceState_t *txDeviceState,
RadioState_t *radioState volatile RadioState_t *radioState
) { ) {
static uint8_t frameId; static uint8_t frameId;
static uint8_t payloadLength; static uint8_t payloadLength;

4
qsp.h
View File

@@ -7,14 +7,14 @@ 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, RadioState_t *radioState); 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, int channels[], uint8_t noOfChannels);
void qspDecodeIncomingFrame( void qspDecodeIncomingFrame(
QspConfiguration_t *qsp, QspConfiguration_t *qsp,
uint8_t incomingByte, uint8_t incomingByte,
RxDeviceState_t *rxDeviceState, RxDeviceState_t *rxDeviceState,
TxDeviceState_t *txDeviceState, TxDeviceState_t *txDeviceState,
RadioState_t *radioState volatile RadioState_t *radioState
); );
void qspClearPayload(QspConfiguration_t *qsp); void qspClearPayload(QspConfiguration_t *qsp);
void qspEncodeFrame(QspConfiguration_t *qsp, uint8_t buffer[], uint8_t *size); void qspEncodeFrame(QspConfiguration_t *qsp, uint8_t buffer[], uint8_t *size);

View File

@@ -74,6 +74,9 @@ enum debugConfigFlags {
#define NO_DATA_TO_READ -1 #define NO_DATA_TO_READ -1
#define RADIO_STATE_TX 1
#define RADIO_STATE_RX 2
struct RadioState_t { struct RadioState_t {
uint32_t frequency = 867000000; uint32_t frequency = 867000000;
uint32_t loraBandwidth = 250000; uint32_t loraBandwidth = 250000;
@@ -83,6 +86,8 @@ struct RadioState_t {
int8_t bytesToRead = -1; int8_t bytesToRead = -1;
uint8_t rssi = 0; uint8_t rssi = 0;
uint8_t snr = 0; uint8_t snr = 0;
uint8_t deviceState = RADIO_STATE_RX;
uint32_t nextTxCheckMillis = 0;
}; };
struct TxDeviceState_t { struct TxDeviceState_t {
@@ -111,8 +116,8 @@ struct QspConfiguration_t {
uint32_t lastFrameReceivedAt[QSP_FRAME_COUNT] = {0}; uint32_t lastFrameReceivedAt[QSP_FRAME_COUNT] = {0};
uint32_t anyFrameRecivedAt = 0; uint32_t anyFrameRecivedAt = 0;
uint8_t deviceState = DEVICE_STATE_UNDETERMINED; uint8_t deviceState = DEVICE_STATE_UNDETERMINED;
void (* onSuccessCallback)(QspConfiguration_t*, TxDeviceState_t*, RxDeviceState_t*, RadioState_t*); void (* onSuccessCallback)(QspConfiguration_t*, TxDeviceState_t*, RxDeviceState_t*, volatile RadioState_t*);
void (* onFailureCallback)(QspConfiguration_t*, TxDeviceState_t*, RxDeviceState_t*, RadioState_t*); void (* onFailureCallback)(QspConfiguration_t*, TxDeviceState_t*, RxDeviceState_t*, volatile RadioState_t*);
bool canTransmit = false; bool canTransmit = false;
bool forcePongFrame = false; bool forcePongFrame = false;
uint8_t debugConfig = 0; uint8_t debugConfig = 0;