Skip to content

Commit 2f442c2

Browse files
committed
Change to RSSI LEDs. Add TX/RX LED.
1 parent 3048b9a commit 2f442c2

File tree

8 files changed

+197
-55
lines changed

8 files changed

+197
-55
lines changed

Firmware/LoRaSerial_Firmware/Commands.ino

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,8 +54,7 @@ void checkCommand()
5454
generateHopTable(); //Generate freq with new settings
5555
configureRadio(); //Apply any new settings
5656

57-
digitalWrite(pin_linkLED, LOW);
58-
digitalWrite(pin_activityLED, LOW);
57+
setRSSI(0); //Turn off LEDs
5958
if (settings.pointToPoint == true)
6059
changeState(RADIO_NO_LINK_RECEIVING_STANDBY);
6160
else
@@ -713,7 +712,7 @@ void displayParameters()
713712
systemPrint("R"); //If someone is asking for our settings over RF, respond with 'R' style settings
714713
else
715714
systemPrint("A");
716-
715+
717716
systemPrint("TS");
718717
systemPrint(x);
719718
systemPrint(":");

Firmware/LoRaSerial_Firmware/LoRaSerial_Firmware.ino

Lines changed: 13 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -69,18 +69,21 @@ uint8_t pin_dio0 = 255;
6969
uint8_t pin_dio1 = 255;
7070
uint8_t pin_rts = 255;
7171
uint8_t pin_cts = 255;
72-
uint8_t pin_linkLED = 255;
73-
uint8_t pin_activityLED = 255;
7472
uint8_t pin_txLED = 255;
7573
uint8_t pin_rxLED = 255;
76-
uint8_t pin_setupButton = 255;
74+
uint8_t pin_trainButton = 255;
75+
uint8_t pin_rssi1LED = 255;
76+
uint8_t pin_rssi2LED = 255;
77+
uint8_t pin_rssi3LED = 255;
78+
uint8_t pin_rssi4LED = 255;
79+
uint8_t pin_boardID = 255;
7780

7881
uint8_t pin_trigger = 255;
7982
//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
8083

8184
//EEPROM for storing settings
8285
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
83-
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_ARCH_ESP32)
86+
#if defined(ARDUINO_ARCH_ESP32)
8487

8588
#include <EEPROM.h>
8689
#define EEPROM_SIZE 1024 //ESP32 emulates EEPROM in non-volatile storage (external flash IC). Max is 508k.
@@ -123,20 +126,15 @@ WDTZero myWatchDog;
123126
#include <JC_Button.h> // http://librarymanager/All#JC_Button
124127
Button *trainBtn = NULL; //We can't instantiate the button here because we don't yet know what pin number to use
125128

126-
const int trainButtonTime = 4000; //ms press and hold before entering training
127-
const int trainWithDefaultsButtonTime = 10000; //ms press and hold before entering training
129+
const int trainButtonTime = 2000; //ms press and hold before entering training
130+
const int trainWithDefaultsButtonTime = 5000; //ms press and hold before entering training
128131
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
129132

130133
//Global variables - Serial
131134
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
132135
//Buffer to store bytes incoming from serial before broadcasting over LoRa
133-
#if defined(ARDUINO_AVR_UNO)
134-
//uint8_t serialReceiveBuffer[512]; //Conserve RAM due to limitations
135-
uint8_t serialReceiveBuffer[32]; //Conserve RAM due to limitations
136-
#else
137136
uint8_t serialReceiveBuffer[1024 * 4]; //Bytes received from UART waiting to be RF transmitted. Buffer up to 1s of bytes at 4k
138137
uint8_t serialTransmitBuffer[1024 * 4]; //Bytes received from RF waiting to be printed out UART. Buffer up to 1s of bytes at 4k
139-
#endif
140138

141139
uint16_t txHead = 0;
142140
uint16_t txTail = 0;
@@ -152,7 +150,7 @@ uint16_t commandRXTail = 0;
152150

153151
unsigned long lastByteReceived_ms = 0; //Track when last transmission was. Send partial buffer once time has expired.
154152

155-
char platformPrefix[15]; //Used for printing platform specific device name
153+
char platformPrefix[25]; //Used for printing platform specific device name, ie "SAMD21 1W 915MHz"
156154
uint8_t escapeCharsReceived = 0; //Used to enter command mode
157155
unsigned long lastEscapeReceived_ms = 0; //Tracks end of serial traffic
158156
const long minEscapeTime_ms = 2000; //Serial traffic must stop this amount before an escape char is recognized
@@ -205,6 +203,9 @@ long startTime = 0; //Used for air time of TX frames
205203
long stopTime = 0;
206204

207205
bool confirmDeliveryBeforeRadioConfig = false; //Goes true when we have remotely configured a radio
206+
207+
int trainCylonNumber = 0b0001;
208+
int trainCylonDirection = -1;
208209
//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
209210

210211
void setup()

Firmware/LoRaSerial_Firmware/Radio.ino

Lines changed: 1 addition & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -323,8 +323,6 @@ void configureRadio()
323323

324324
void returnToReceiving()
325325
{
326-
digitalWrite(pin_activityLED, LOW);
327-
328326
if (settings.autoTuneFrequency == true)
329327
radio.setFrequency(channels[radio.getFHSSChannel()] - frequencyCorrection);
330328
else
@@ -595,8 +593,6 @@ void sendPacket()
595593
if (settings.airSpeed == 28800 || settings.airSpeed == 38400)
596594
delay(2);
597595

598-
digitalWrite(pin_activityLED, HIGH);
599-
600596
radio.setFrequency(channels[radio.getFHSSChannel()]); //Return home before every transmission
601597

602598
LRS_DEBUG_PRINT("Transmitting @ ");
@@ -702,7 +698,7 @@ void generateHopTable()
702698

703699
if (settings.encryptData == true)
704700
{
705-
for (int x = 0 ; x < sizeof(settings.encryptionKey) ; x++)
701+
for (uint8_t x = 0 ; x < sizeof(settings.encryptionKey) ; x++)
706702
myRandSeed += settings.encryptionKey[x];
707703
}
708704

@@ -829,8 +825,6 @@ bool receiveInProcess()
829825
//3 is lowest allowed setting using SX1276+RadioLib
830826
uint8_t covertdBmToSetting(uint8_t userSetting)
831827
{
832-
if(userSetting < 14) return 3; //Error check
833-
834828
switch (userSetting)
835829
{
836830
case 14: return (2); break;
@@ -852,6 +846,4 @@ uint8_t covertdBmToSetting(uint8_t userSetting)
852846
case 30: return (20); break;
853847
default: return (3); break;
854848
}
855-
856-
857849
}

Firmware/LoRaSerial_Firmware/Serial.ino

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,8 @@ void updateSerial()
4040
{
4141
if (isCTS())
4242
{
43+
txLED(true); //Turn on LED during serial transmissions
44+
4345
//Print data to both ports
4446
for (int x = 0 ; x < availableTXBytes() ; x++)
4547
{
@@ -65,6 +67,8 @@ void updateSerial()
6567
txTail++;
6668
txTail %= sizeof(serialTransmitBuffer);
6769
}
70+
71+
txLED(false); //Turn off LED
6872
}
6973
}
7074
}
@@ -76,6 +80,8 @@ void updateSerial()
7680
while (Serial.available() && transactionComplete == false)
7781
#endif
7882
{
83+
rxLED(true); //Turn on LED during serial reception
84+
7985
//Take a break if there are ISRs to attend to
8086
petWDT();
8187
if (timeToHop == true) hopChannel();
@@ -158,6 +164,9 @@ void updateSerial()
158164
serialReceiveBuffer[rxHead++] = incoming; //Push char to holding buffer
159165
rxHead %= sizeof(serialReceiveBuffer);
160166
} //End process rx buffer
167+
168+
rxLED(false); //Turn off LED
169+
161170
} //End Serial.available()
162171

163172
//Process any remote commands sitting in buffer

Firmware/LoRaSerial_Firmware/States.ino

Lines changed: 41 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ void updateRadioState()
1717
hopChannel();
1818

1919
//Check to see if we need to send a ping
20-
else if ( (millis() - packetTimestamp) > (settings.heartbeatTimeout + random(0, 1000)) //Avoid pinging each other at same time
20+
else if ( (millis() - packetTimestamp) > (unsigned int)(settings.heartbeatTimeout + random(0, 1000)) //Avoid pinging each other at same time
2121
|| sentFirstPing == false) //Immediately send pings at POR
2222
{
2323
if (receiveInProcess() == false)
@@ -46,7 +46,7 @@ void updateRadioState()
4646
//We're done transmitting our ack packet
4747
//Yay! Return to normal communication
4848
packetsLost = 0; //Reset, used for linkLost testing
49-
digitalWrite(pin_linkLED, HIGH);
49+
updateRSSI(); //Adjust LEDs to RSSI level. We will soon be linked.
5050
returnToReceiving();
5151
changeState(RADIO_LINKED_RECEIVING_STANDBY);
5252
}
@@ -96,7 +96,7 @@ void updateRadioState()
9696
{
9797
//Yay! Return to normal communication
9898
packetsLost = 0; //Reset, used for linkLost testing
99-
digitalWrite(pin_linkLED, HIGH);
99+
updateRSSI(); //Adjust LEDs to RSSI level
100100
returnToReceiving();
101101
changeState(RADIO_LINKED_RECEIVING_STANDBY);
102102
}
@@ -108,11 +108,14 @@ void updateRadioState()
108108
else if (packetType == PACKET_PING)
109109
{
110110
triggerEvent(TRIGGER_NOLINK_IDENT_PACKET);
111+
updateRSSI(); //Adjust LEDs to RSSI level. We will soon be linked.
111112
sendAckPacket(); //Someone is pinging us
112113
changeState(RADIO_NO_LINK_TRANSMITTING);
113114
}
114115
else if (packetType == PACKET_DATA)
116+
{
115117
; //No data packets allowed when not linked
118+
}
116119
}
117120
break;
118121

@@ -122,7 +125,7 @@ void updateRadioState()
122125
{
123126
if (linkLost())
124127
{
125-
digitalWrite(pin_linkLED, LOW);
128+
setRSSI(0);
126129

127130
//Return to home channel and begin linking process
128131
returnToReceiving();
@@ -139,7 +142,7 @@ void updateRadioState()
139142
else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
140143
hopChannel();
141144

142-
else if ((millis() - packetTimestamp) > (settings.heartbeatTimeout + random(0, 1000))) //Avoid pinging each other at same time
145+
else if ((millis() - packetTimestamp) > (unsigned int)(settings.heartbeatTimeout + random(0, 1000))) //Avoid pinging each other at same time
143146
{
144147
if (receiveInProcess() == false)
145148
{
@@ -190,7 +193,7 @@ void updateRadioState()
190193
sendCommandDataPacket();
191194
}
192195

193-
if(availableTXCommandBytes() == 0)
196+
if (availableTXCommandBytes() == 0)
194197
printerEndpoint = PRINT_TO_SERIAL; //Once the response is received, we need to print it to serial
195198

196199
changeState(RADIO_LINKED_TRANSMITTING);
@@ -285,6 +288,7 @@ void updateRadioState()
285288
systemPrintln();
286289
}
287290
packetsLost = 0; //Reset, used for linkLost testing
291+
updateRSSI(); //Adjust LEDs to RSSI level
288292
frequencyCorrection += radio.getFrequencyError() / 1000000.0;
289293
returnToReceiving();
290294
changeState(RADIO_LINKED_RECEIVING_STANDBY);
@@ -294,6 +298,7 @@ void updateRadioState()
294298
//It's a duplicate. Ack then throw data away.
295299
triggerEvent(TRIGGER_LINK_DUPLICATE_PACKET);
296300
packetsLost = 0; //Reset, used for linkLost testing
301+
updateRSSI(); //Adjust LEDs to RSSI level
297302
frequencyCorrection += radio.getFrequencyError() / 1000000.0;
298303
sendAckPacket();
299304
changeState(RADIO_LINKED_TRANSMITTING);
@@ -303,6 +308,7 @@ void updateRadioState()
303308
//Someone is pinging us. Ack back.
304309
triggerEvent(TRIGGER_LINK_CONTROL_PACKET);
305310
packetsLost = 0; //Reset, used for linkLost testing
311+
updateRSSI(); //Adjust LEDs to RSSI level
306312
frequencyCorrection += radio.getFrequencyError() / 1000000.0;
307313
sendAckPacket();
308314
changeState(RADIO_LINKED_TRANSMITTING);
@@ -331,6 +337,7 @@ void updateRadioState()
331337
}
332338

333339
packetsLost = 0; //Reset, used for linkLost testing
340+
updateRSSI(); //Adjust LEDs to RSSI level
334341
frequencyCorrection += radio.getFrequencyError() / 1000000.0;
335342
sendAckPacket(); //Transmit ACK
336343
changeState(RADIO_LINKED_TRANSMITTING);
@@ -351,6 +358,7 @@ void updateRadioState()
351358
}
352359

353360
packetsLost = 0; //Reset, used for linkLost testing
361+
updateRSSI(); //Adjust LEDs to RSSI level
354362
frequencyCorrection += radio.getFrequencyError() / 1000000.0;
355363
sendCommandAckPacket(); //Transmit ACK
356364
changeState(RADIO_LINKED_TRANSMITTING);
@@ -363,6 +371,7 @@ void updateRadioState()
363371
Serial.write(lastPacket[x]);
364372

365373
packetsLost = 0; //Reset, used for linkLost testing
374+
updateRSSI(); //Adjust LEDs to RSSI level
366375
frequencyCorrection += radio.getFrequencyError() / 1000000.0;
367376
sendCommandResponseAckPacket(); //Transmit ACK
368377
changeState(RADIO_LINKED_TRANSMITTING);
@@ -378,8 +387,7 @@ void updateRadioState()
378387
generateHopTable(); //Generate freq with new settings
379388
configureRadio(); //Apply any new settings
380389

381-
digitalWrite(pin_linkLED, LOW);
382-
digitalWrite(pin_activityLED, LOW);
390+
setRSSI(0); //Turn off RSSI LEDs
383391
if (settings.pointToPoint == true)
384392
changeState(RADIO_NO_LINK_RECEIVING_STANDBY);
385393
else
@@ -388,6 +396,7 @@ void updateRadioState()
388396
else //It was just an ACK
389397
{
390398
packetsLost = 0; //Reset, used for linkLost testing
399+
updateRSSI(); //Adjust LEDs to RSSI level
391400
frequencyCorrection += radio.getFrequencyError() / 1000000.0;
392401
returnToReceiving();
393402
changeState(RADIO_LINKED_RECEIVING_STANDBY);
@@ -440,11 +449,15 @@ void updateRadioState()
440449
if (millis() - lastLinkBlink > 500) //Blink at 2Hz
441450
{
442451
lastLinkBlink = millis();
443-
digitalWrite(pin_linkLED, !digitalRead(pin_linkLED)); //Toggle LED
452+
//Toggle all RSSI LEDs
453+
if (digitalRead(pin_rssi1LED) == HIGH)
454+
setRSSI(0);
455+
else
456+
setRSSI(0b1111); //All on
444457
}
445458
}
446459
else
447-
digitalWrite(pin_linkLED, LOW); //No link
460+
setRSSI(0); //No link
448461
}
449462
break;
450463

@@ -455,7 +468,7 @@ void updateRadioState()
455468
transactionComplete = false; //Reset ISR flag
456469
returnToReceiving();
457470
changeState(RADIO_BROADCASTING_RECEIVING_STANDBY); //No ack response when in broadcasting mode
458-
digitalWrite(pin_activityLED, LOW);
471+
setRSSI(0); //Turn off RSSI LEDs
459472
}
460473

461474
else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
@@ -518,14 +531,15 @@ void updateRadioState()
518531
}
519532
break;
520533

534+
//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
535+
521536
case RADIO_TRAINING_TRANSMITTING:
522537
{
523538
if (transactionComplete == true) //If dio0ISR has fired, we are done transmitting
524539
{
525540
transactionComplete = false; //Reset ISR flag
526541
returnToReceiving();
527542
changeState(RADIO_TRAINING_ACK_WAIT);
528-
digitalWrite(pin_activityLED, LOW);
529543
}
530544
}
531545
break;
@@ -556,6 +570,21 @@ void updateRadioState()
556570
transactionComplete = false; //Reset ISR flag
557571
changeState(RADIO_TRAINING_RECEIVED_PACKET);
558572
}
573+
else if ( (millis() - lastTrainBlink) > 75) //Blink while unit waits in training state
574+
{
575+
lastTrainBlink = millis();
576+
577+
//Cylon the RSSI LEDs
578+
setRSSI(trainCylonNumber);
579+
580+
if (trainCylonNumber == 0b1000 || trainCylonNumber == 0b0001)
581+
trainCylonDirection *= -1; //Change direction
582+
583+
if(trainCylonDirection > 0)
584+
trainCylonNumber <<= 1;
585+
else
586+
trainCylonNumber >>= 1;
587+
}
559588
}
560589
break;
561590

0 commit comments

Comments
 (0)