diff --git a/.gitignore b/.gitignore
index e110aaf1..e57e1b2a 100644
--- a/.gitignore
+++ b/.gitignore
@@ -7,6 +7,9 @@ ehthumbs.db
*.b#?
*.l#?
*.lck
+.vscode/*
+/Firmware/LoRaSerial_Firmware/.vscode/*
+/Firmware/build/*
# Folder config file
Desktop.ini
@@ -27,16 +30,29 @@ $RECYCLE.BIN/
# OSX
# =========================
-.DS_Store
-.AppleDouble
-.LSOverride
-
-# Icon must ends with two \r.
-Icon
-
-# Thumbnails
-._*
-
-# Files that might appear on external disk
-.Spotlight-V100
-.Trashes
+.DS_Store
+.AppleDouble
+.LSOverride
+
+# Icon must ends with two \r.
+Icon
+
+
+# Thumbnails
+._*
+
+# Files that might appear on external disk
+.Spotlight-V100
+.Trashes
+
+# Linux
+# =========================
+
+# Object files
+*.o
+
+# Archives (Libraries)
+*.a
+
+# Executables
+Firmware/Tools/VcServerTest
diff --git a/Binaries/Programming_Tools/SparkFun_LoRaSerial_RC-Feb_09_2023_with_bootloader.bin b/Binaries/Programming_Tools/SparkFun_LoRaSerial_RC-Feb_09_2023_with_bootloader.bin
new file mode 100644
index 00000000..541be2bb
Binary files /dev/null and b/Binaries/Programming_Tools/SparkFun_LoRaSerial_RC-Feb_09_2023_with_bootloader.bin differ
diff --git a/Binaries/Programming_Tools/atprogram.exe b/Binaries/Programming_Tools/atprogram.exe
new file mode 100644
index 00000000..401cbcdc
Binary files /dev/null and b/Binaries/Programming_Tools/atprogram.exe differ
diff --git a/Binaries/Programming_Tools/batch_program.bat b/Binaries/Programming_Tools/batch_program.bat
new file mode 100644
index 00000000..84a89de0
--- /dev/null
+++ b/Binaries/Programming_Tools/batch_program.bat
@@ -0,0 +1,26 @@
+@echo off
+if [%1]==[] goto usage
+
+@echo Programming for SparkFun LoRaSerial
+@pause
+:loop
+
+@echo -
+@echo Programming binary: %1
+
+@echo Unlock bootloader
+atprogram.exe -t samice -i swd -cl 20mhz -d atsamd21g18a write --fuses --offset 0x804000 --values 0xFFC7E0D8
+
+@echo Programming firmware
+atprogram.exe -t samice -i swd -cl 20mhz -d atsamd21g18a chiperase program -f %1 --verify
+
+@echo Lock bootloader
+atprogram.exe -t samice -i swd -cl 20mhz -d atsamd21g18a write --fuses --offset 0x804000 --values 0xFAC7E0D8
+
+@echo Done programming! Ready for next board.
+@pause
+
+goto loop
+
+:usage
+@echo Missing the hex file. Ex: batch_program.bat LoRaSerial_Firmware_v10_Combined.hex
\ No newline at end of file
diff --git a/Binaries/Programming_Tools/read.bat b/Binaries/Programming_Tools/read.bat
new file mode 100644
index 00000000..7b2c9f7b
--- /dev/null
+++ b/Binaries/Programming_Tools/read.bat
@@ -0,0 +1 @@
+atprogram.exe -t atmelice -i swd -cl 10mhz -d atsamd21g18a read --file production.hex --size 244000
diff --git a/Binaries/SparkFun_LoRaSerial_RC-Feb_09_2023_with_bootloader.bin b/Binaries/SparkFun_LoRaSerial_RC-Feb_09_2023_with_bootloader.bin
new file mode 100644
index 00000000..541be2bb
Binary files /dev/null and b/Binaries/SparkFun_LoRaSerial_RC-Feb_09_2023_with_bootloader.bin differ
diff --git a/Documents/LoRaSerial Airspeed Spreadsheet.jpg b/Documents/LoRaSerial Airspeed Spreadsheet.jpg
new file mode 100644
index 00000000..94e1c992
Binary files /dev/null and b/Documents/LoRaSerial Airspeed Spreadsheet.jpg differ
diff --git a/Documents/Readme.md b/Documents/Readme.md
new file mode 100644
index 00000000..85f681ef
--- /dev/null
+++ b/Documents/Readme.md
@@ -0,0 +1,28 @@
+LoRaSerial Documents and Airspeed Calculations
+========================================
+
+[](https://docs.google.com/spreadsheets/d/1qyJa3ldE-KDUHwHNSctBMccPTVRwKbmAsodkdvOc3-8/edit?usp=sharing)
+
+The available airspeeds (40 to 38400) used in LoRaSerial were picked to, as closely as possible, mimic modem baud rates. Other spread factors, bandwidths, and coding rates can be used if desired.
+
+[This spreadsheet](https://docs.google.com/spreadsheets/d/1qyJa3ldE-KDUHwHNSctBMccPTVRwKbmAsodkdvOc3-8/edit?usp=sharing) can be used to inspect the airtime formulas.
+
+Additionally, this folder contains the various datasheets for the SX1276 IC, common to all LoRaSerial modules, as well as the individual datasheets for the different module types (915, 868, 433, etc).
+
+[Atmel SAM D21G Datasheet](https://cdn.sparkfun.com/datasheets/Dev/Arduino/Boards/Atmel-42181-SAM-D21_Datasheet.pdf)
+
+## Modes of Operation
+
+The LoRaSerial radio operates in one of three modes:
+* Point-to-Point (default)
+* Multipoint
+* Virtual Circuit
+* Training
+
+Point-to-Point mode provides guaranteed message delivery or the link breaks. The radio performs data retransmission if either the data frame was lost or its acknowledgement was lost. This can continue indefinitely if MaxResends equals zero (default) or for a limited number of retries in the range of (1 - 255).
+
+Multipoint mode provides a datagram service. The LoRaSerial radios will send the data frame without a guarantee that the frame will be received by the remote radio. Lost frames are lost, the radio does no perform retransmission. If the application is not able to tolerate the lost frames then another protocol layer needs to be implemented on the host computer between the radio and the application that provides the necessary services to the application.
+
+Virtual circuit mode enables a group of radios to communicate with each other. The radio links provide guaranteed message delivery or the link is broken. One radio in the group is designated as the server and provides the channel timer synchronization for the client radios, think of a star configuration with the server at the center. Data communications with the virtual circuit mode is all point-to-point. Communications between the radio and the host CPU use a special virtual circuit header to identify where to send the host to radio data, or where to deliver the radio to host data. More information is available [here](https://github.com/sparkfun/SparkFun_LoRaSerial/blob/release_candidate/Documents/Virtual_Circuits.md).
+
+Training is a temporary mode of operation to initialize a set of radios for one of the other modes of operation. There are one or more clients and a single server during training. The mode specific parameters for the other mode of operation are passed from the server to each of the clients. Upon completion all of the radios in the set will be able to communicate with one another. More information on training is available [here](https://github.com/sparkfun/SparkFun_LoRaSerial/blob/release_candidate/Documents/Training.md).
diff --git a/Documents/Training.md b/Documents/Training.md
new file mode 100644
index 00000000..89aeb26a
--- /dev/null
+++ b/Documents/Training.md
@@ -0,0 +1,299 @@
+LoRaSerial Training
+===================
+
+# Goals
+
+There are two goals for LoRaSerial training:
+
+1 Establish a common set of communication parameters between a set of LoRaSerial radios.
+2 Make it easy to test an initial pair of LoRaSerial radios through the use of the training button.
+
+# Methods of Training
+
+There are two methods of initiating training:
+
+* Pressing the training button on the top of the LoRaSerial module
+* Entering the ATT command
+
+Training is performed by a server radio sending parameters to the client radio. Upon reception the client radio saves the parameters in non-volatile memory and then reboots with the new parameters.
+
+## Training Button Behavior
+
+Pressing and releasing the training button for different lengths of time initiates the following behaviors:
+
+* 2 Seconds:
+ * Enter training as a client, cylon pattern appears on the green LEDs
+ * Exit training (client or server) without saving parameter changes, cylon pattern stops and previous LED pattern returns
+* 5 Seconds - Enter training as a server, yellow LED flashes 3 times when 5 seconds of press time is detected, cylon pattern appears on the green LEDs when the button is released
+* 15 Seconds - Reset LoRaSerial to factory settings and erase NVM, blue LED flashes 3 times when 15 seconds of press time is detected
+
+# Temporary Training Server
+
+It is possible to use temporary training servers for multipoint and virtual circuit modes. The only difference with a temporary server and a regular server is that the parameters are not saved to the non-volatile storage using the ATW command before exiting command mode.
+
+# Point-To-Point Training
+
+To get a known set of parameters on the client radio, use command mode to initialize the parameters on the server. Using the training buttons on both radios only changes
+the network ID and encryption key values, it does not change any of the other parameters such as AirSpeed.
+
+Point-to-Point Training Examples:
+
+Server:
+* Enter command mode using +++
+* Optional, start from factory defaults by issuing the ATF command
+* Set the desired parameters
+* Set Server=1
+* Enter training mode using ATT command
+* After the client is trained
+* Saves new parameters for netID and encryptionKey
+* Reboots
+
+Server (no clients):
+* Enter command mode with +++
+* Set any of the desired parameters
+* Enter training mode with ATT command
+* No client to be trained
+* Exit command mode with ATO or ATZ
+
+Assuming the radios are already able to communicate, use the training button to select a random NetID and EncryptionKey value.
+
+Server:
+* 2 second training button press
+* Does not receive training from a server
+* After 3 seconds, generates new netID and encryption key and automatically switches to server mode
+* Wait for client to be trained
+* Saves new parameters for netID and encryptionKey
+* Reboots
+
+Server:
+* 5 second training button press
+* Generates new netID and encryption key
+* Wait for client to be trained
+* Saves new parameters for netID and encryptionKey
+* Reboots
+
+Client:
+* 2 second training button press
+* Receives training parameters from server
+* Saves new parameters
+* Reboots
+
+Client:
+* Enter command mode using +++
+* Enter training using the ATT command
+* Receives training parameters from server
+* Saves new parameters
+* Reboots
+
+Point-To-Point Timeout Examples:
+
+Client:
+* 2 second training button press
+* Before three seconds
+* 2 second training button press, exits training without receiving any new parameters
+
+Server:
+* 2 second training button press
+* Does not receive training from a server
+* After 3 seconds, generates new netID and encryption key and automatically switches to server mode
+* 2 second training button press, exits training and does not save new netID or encryption key
+
+Server:
+* 5 second training button press
+* Generates new netID and encryption key
+* 2 second training button press, exits training and does not save new netID or encryption key
+
+# Multi-Point Training
+
+It is recommend to use a command script to initialize the server radio when performing multipoint traning. The client radios can either use command mode or the training button to enter training mode.
+
+Temporary Server (Doesn't save settings):
+* If not already at factory reset, hold the training button down for 15 seconds
+* Connect to the LoRaSerial radio via USB or the serial port
+* Enter command mode with +++
+* Start from factory defaults by issuing the ATF command
+* Issue the following commands:
+ * AT-OperatingMode=0
+ * AT-Server=1
+ * AT-SelectLedUse=1
+ * ATG
+* Set any of the other parameters
+* Enter training mode with ATT command
+* Wait for clients to be trained
+* Exit command mode with ATO command or reboot with ATZ command
+
+Server (Saves settings):
+* If not already at factory reset, hold the training button down for 15 seconds
+* Connect to the LoRaSerial radio via USB or the serial port
+* Enter command mode with +++
+* Start from factory defaults by issuing the ATF command
+* Issue the following commands:
+ * AT-OperatingMode=0
+ * AT-Server=1
+ * AT-SelectLedUse=1
+ * ATG
+* Set any of the other parameters
+* Enter training mode with ATT command
+* Wait for clients to be trained
+* Save parameters with ATW command
+* Always reboot with ATZ command
+
+Client:
+* 2 second training button press
+* Receives training parameters from server
+* Saves new parameters
+* Reboots
+
+Client:
+* Connect to the LoRaSerial radio via USB or the serial port
+* Enter command mode using +++
+* Enter training using the ATT command
+* Receives training parameters from server
+* Saves new parameters
+* Reboots
+
+# Virtual Circuit Training
+
+It is recommend to use a command script to initialize the server radio when performing virtual-circuit traning. The client radios can either use command mode or the training button to enter training mode.
+
+Temporary Server (Doesn't save settings):
+* If not already at factory reset, hold the training button down for 15 seconds
+* Connect to the LoRaSerial radio via USB or the serial port
+* Enter command mode with +++
+* Start from factory defaults by issuing the ATF command
+* Issue the following commands:
+ * AT-OperatingMode=2
+ * AT-Server=1
+ * AT-SelectLedUse=2
+ * ATG
+* Set any of the other parameters
+* Enter training mode with ATT command
+* Wait for clients to be trained
+* Exit command mode with ATO command or reboot with ATZ command
+
+Server (Saves settings):
+* If not already at factory reset, hold the training button down for 15 seconds
+* Connect to the LoRaSerial radio via USB or the serial port
+* Enter command mode with +++
+* Start from factory defaults by issuing the ATF command
+* Issue the following commands:
+ * AT-OperatingMode=2
+ * AT-Server=1
+ * AT-SelectLedUse=2
+ * ATG
+* Set any of the other parameters
+* Enter training mode with ATT command
+* Wait for clients to be trained
+* Save parameters with ATW command
+* Always reboot with ATZ command
+
+Client:
+* 2 second training button press
+* Receives training parameters from server
+* Saves new parameters
+* Reboots
+
+Client:
+* Connect to the LoRaSerial radio via USB or the serial port
+* Enter command mode using +++
+* Enter training using the ATT command
+* Receives training parameters from server
+* Saves new parameters
+* Reboots
+
+# Training Parameters
+
+The training parameters for radio communication fall into two groups:
+
+* Radio parameters
+* Radio protocol parameters
+
+Other optional sets of training parameters may be communicated between the radios when the corresponding copyXxxx parameter is set to true (1). The optional parameter sets are:
+
+* Serial parameters
+* Debug parameters
+* Trigger parameters
+
+The following sections describe the communication parameters.
+
+## Radio Parameters
+
+The following parameters describe the radio transmit operation:
+
+* AutoTuneFrequency - Adjust the frequency based upon the last received frame's frequency error.
+
+* FrequencyHop - Enable or disable frequency hopping. Legal operation in the United States requires that this value be set to true (1) which is the default. This parameter specifies whether the radio will change frequencies to a new channel every MaxDwellTime milliseconds.
+
+* FrequencyMax - Maximum frequency the radio will use specified in MegaHertz. The default value is 928.0 MHz.
+
+* FrequencyMin - Minimum frequency the radio will use specified in MegaHertz. The default value is 902.0 MHz.
+
+* MaxDwellTime - Number of milliseconds that the LoRaSerial radio uses a specific frequency (channel). After this time, the radio switches (hops) to another frequency. For operation within the United States this value must not be greater than 400 milliseconds which is the default.
+
+* NumberOfChannels - Specify the number of unique frequencies that will be used by the LoRaSerial radio. For operation within the United States this value needs to be a minimum of 50 which is the default value.
+
+* RadioBroadcastPower_dbm - Transmit power level for the LoRaSerial radio. The valid range for this parameter is from 14 (25 milliWatts) to 30 dBm (1 Watt). The default value is 30 dBm.
+
+### Frame Synchronization Parameters
+
+The following parameters specify data that the radios use for data synchronization and frame reception:
+
+* RadioPreambleLength - Number of symbols to transmit at the beginning of the frame to notify the receiving radios of the incoming frame. The range of values are 6 to 65535 with the default being 8. The preamble is used to synchronize the PLLs in the radio to properly detect the symbol boundaries. NOTE: Different lengths does *not* guarantee a remote radio privacy. 8 to 11 works. 8 to 15 drops some. 8 to 20 is silent.
+
+* RadioSyncWord - The sync word following the preamble indicates the destination set of radios. Note that different sync words do *not* guarantee a remote radio will not receive a rogue frame.
+
+### AirSpeed
+
+The parameter AirSpeed is a simplification that selects values for the following parameters to approximate the baud rate implied by the AirSpeed.
+
+* HeartbeatTimeout
+* RadioBandwidth
+* RadioCodingRate
+* RadioSpreadFactor
+* TxToRxUsec
+
+Valid values for AirSpeed are (40, 150, 400, 1200, 2400, 4800, 9600, 19200, 28800 and 38400) and the default is 4800. After AirSpeed is set, it is possible to modify any of the parameters above. Note that AirSpeed is just an easy way to set the parameters above to known value. AirSpeed is not an actual parameter that is used for training, only the parameters listed above are used during training. More detail for these parameters is provided below:
+
+* HeartbeatTimeout - Heartbeats are transmitted on a regular basis by the server and in point-to-point and virtual circuit modes by the clients. This parameter specifies the time in milliseconds during which a HEARTBEAT frame should be transmitted. If a HEARTBEAT frame is not received within three (3) times this interval then the point-to-point or virtual circuit link is broken. The default heartbeatTimeout is 5000 milliseconds (5 seconds).
+
+* RadioBandwidth - Bandwidth of the spread spectrum signal specified in kiloHertz. The default is 500.0 kHz and other supported values are: 10.4, 15.6, 20.8, 31.25, 41.7, 62.5, 125 and 250 kHz.
+
+* RadioCodingRate - Number of bits to send 4 data bits of information. This is used for forward error correction, allowing the receiver to correct the incoming bit stream. Valid values are 5 through 8 where higher coding rates ensure less frames are dropped. The default value is 8.
+
+* RadioSpreadFactor - Number of bits in a symbol. Valid values are 6 to 12 with the default value of 9. Larger values enable longer range while reducing the data rate.
+
+* TxToRxUsec - Transition time from end of transmission to the end of reception on the remote radio specified in microseconds.
+
+## Radio protocol parameters
+
+The following parameters describe the contents of the data frame sent between the LoRaSerial radios:
+
+* DataScrambling - Enable (1) or disable (0) the use of IBM's Data Whitening algorithm to reduce DC bias
+
+* EnableCRC16 - Enable (1) or disable (0) adding a software generated CRC-16 to the end of the data frame.
+
+* EncryptData - Enable (1) or disable (0) the use of AES encryption for each data frame
+
+* EncryptionKey - The 16 byte encryption key specified in hexadecimal. While SparkFun provides a default value, it is strongly recomended to change this value for your own networks.
+
+* FramesToYield - When requested by the remote radio, suppress transmission for this number of max packet frames. The valid range is 0 to 255 with a default value of 3.
+
+* MaxResends - Number of retransmission attempt to make for a each frame when an ACK is not received from the destination radio. The valid range is 0 to 255. The default of zero represents infinite and retries will continue as long as the two radios are receiving HEARTBEAT frames from each other. The transmission will fail only when the link breaks due to not receiving HEARTBEAT frames.
+
+* NetID - A unique value denoting the network of LoRaSerial radios. All radios in the network must share the same ID value. This value is in addition to the radioSyncWord.
+
+* OperatingMode - The following modes of operation are supported by the LoRaSerial radios:
+
+ * MODE_MULTIPOINT (0) - A single server with multiple clients, all radios are sending datagram frames which are not guarranteed to be received by the other radios. This mode is great when real-time transmission is necessary and the application is able to tolerate some loss of data.
+
+ * MODE_POINT_TO_POINT (1, default) - Communications between only two LoRaSerial radios with guarranteed delivery of frames or the link breaks.
+
+ * MODE_VIRTUAL_CIRCUIT - A single server with multiple clients that supports multipoint communications with guarranteed delivery or the link breaks. This mode uses a special protocol over the serial link to be able to specify the destination radio for transmission and the receive radio for reception. More information is available [here](https://github.com/sparkfun/SparkFun_LoRaSerial/blob/release_candidate/Documents/Virtual_Circuits.md).
+
+* OverheadTime - The number of milliseconds to add to ACK and datagram times before ACK timeout occurs. The default is 10 milliseconds.
+
+* SelectLedUse - Select how to display information on the LEDs
+
+* Server - Enable (1) or disable (0) the server mode for training and for multipoint or virtual circuit operation. The default is client mode (0).
+
+* VerifyRxNetID - Enable (1) or disable (0) the verification of the netID value during reception. The default is enabled (1).
diff --git a/Documents/Virtual_Circuits.md b/Documents/Virtual_Circuits.md
new file mode 100644
index 00000000..00b45cc5
--- /dev/null
+++ b/Documents/Virtual_Circuits.md
@@ -0,0 +1,269 @@
+Virtual Circuit Mode
+====================
+
+Multiple radios can communicate to each other in Virtual Circuit mode. This mode provides guaranteed message delivery or the link breaks. Virtual circuit mode supports:
+* Up to 32 radios
+* Virtual circuit serial interface
+* Local command support
+* Remote command support
+* [Header file](https://github.com/sparkfun/SparkFun_LoRaSerial/blob/release_candidate/Firmware/LoRaSerial_Firmware/Virtual_Circuit_Protocol.h) for C and C++
+
+## Virtual Circuit Network Configuration
+
+A LoRaSerial virtual circuit network consists of a single server radio and up to 31 client radios. The server transmits HEARTBEAT frames that provide the synchronization signal for the channel hop timer. Each time the timer fires, the radio switches to a new center frequency (channel).
+
+Clients wait to receive a HEARTBEAT frame from the server on channel 0. If the selectLedUse is set to LED_VC (2) then the blue LED will flash upon when the server's HEARTBEAT frame is received. After receiving the server's HEARTBEAT frame the client synchronizes its hop timer and starts hopping channels. If the selectLedUse is set to LED_VC (2) then each hop is indicated by a flash of the yellow LED.
+
+The virtual circuit server assigns virtual circuit ID numbers to all of the client radios. This may be done during radio training or during the first time the radio is connected to the network. After receiving a HEARTBEAT frame from the server, the client sends a HEARTBEAT frame with the source VC address of VC_UNASSIGNED and the radio's 16-byte unique ID. The server echos this HEARTBEAT replacing the source VC with the assigned VC number. While the client is using VC_UNASSIGNED as it's VC number, the client radio compares the unique ID in the HEARTBEAT frame to the local radio's unique ID value. If the values match then the client replaces its VC number with the assigned VC number.
+
+For consistent processing, the server records the client unique ID values in the non-volatile memory. These values are read and loaded into the virtual circuit table when the system boots again.
+
+### Radio Parameters
+
+Select a LoRaSerial radio for the virtual circuit server. Set the following parameters on the server radio.
+
+The following parameters should be set to enable virtual circuit mode:
+* AT=OperatingMode=2 - Select virtual circuit mode
+* AT-NetID=n - Choose a unique value (n) for your network
+* AT-VerifyNetID=1 - Eliminate communications from other radios which are not using the NetID value
+* AT-EnableCRC16=? - Enable software CRC-16 by setting the value to 1, otherwise set the value to zero to disable software CRC
+* AT-EncryptionKey=? - Choose a unique encryption key for the network
+* AT-SelectLedUse=2 - The use of LEDS_VC (2) flashes the blue LED when server HEARTBEAT frames are received by the clients, providing a visual indication that the radio is synchronizing with the server
+* AT-Server=1 - Define this radio as the virtual circuit server
+* ATW - Write the parameters to the non-volatile memory (NVM).
+
+Now enter training mode with the ATT command. The training enables the server to pass these parameters (except for server) to the client radios. On the client radios, with power applied, press the button at the top of the client radio to enter training mode. The radio will obtain the parameters from the server, write them to NVM and then reboot using the new parameters.
+
+After all of the client radios are trained, the ATZ command may be entered on the server radio to cause it to reboot.
+
+#### Example Virtual Circuit Initialization Script for Training
+
+ +++
+ AT=OperatingMode=2
+ AT-NetID=3
+ AT-VerifyNetID=1
+ AT-EnableCRC16=1
+ AT-EncryptionKey=54637374546373745463737454637374
+ AT-SelectLedUse=2
+ AT-Server=1
+ ATW
+ ATT
+
+## Virtual Circuit Communications
+
+Communication is possible between the server and client or between clients. A three-way handshake must be performed prior to normal data communications to synchronize the ACK numbers. By default, the three-way handshake is not performed. The user or application initiates the handshake using the AT-CmdVc=n to select the client or server radio (n) for communications. Next the ATC command initiates the three-way handshake between the local radio and the remote radio (n).
+
+After the three-way handshake communications between the two radios is possible in virtual circuit mode.
+
+## Virtual Circuit Number
+
+The virtual circuit number of the local radio is obtained by issuing the ATI11 command to the local radio. The response returns a number in the range of zero (0) to MAX_VC. The value VC_UNASSIGNED is returned between reset until the server assigns a virtual circuit number to the local radio.
+
+## Virtual Circuit Serial Interface
+
+In virtual circuit mode all communications over the serial port must be proceeded by a VC_SERIAL_MESSAGE_HEADER. Data not proceeded by a VC_SERIAL_MESSAGE_HEADER data structure is discarded! The VC_SERIAL_MESSAGE_HEADER is defined in the [Virtual_Circuit_Protocol.h](https://github.com/sparkfun/SparkFun_LoRaSerial/blob/release_candidate/Firmware/LoRaSerial_Firmware/Virtual_Circuit_Protocol.h) header file. This data structure is four (4) bytes long starting with the value START_OF_VC_SERIAL (2). The next byte specifies the length of the binary data following the VC_SERIAL_MESSAGE_HEADER plus the size of VC_RADIO_MESSAGE_HEADER (3). The other two bytes are virtual circuit numbers for the destination and source virtual circuits.
+
+The server radio is identified by VC_SERVER (0) and client radios have VC numbers between 1 and MAX_VC. A data message sent from the server to client 3 would have the source VC set to VC_SERVER (0) and the destination VC set to 3. Example:
+
+ START_OF_VC_SERIAL
+ +-----+-----+-----+-----+-----+-----+-----+-----+-----+
+ | 2 | 8 | 3 | 0 | H | e | l | l | o |
+ +-----+-----+-----+-----+-----+-----+-----+-----+-----+
+ Length Dest Src Data
+
+### Radio Responses
+
+The LoRaSerial radio will return the following responses:
+
+* Data response
+* Local command response
+* Remote command response
+* VC state response
+* Reconnect serial response
+
+#### Data Response
+
+When sending a data message, the radio returns a VC_DATA_ACK_NACK_MESSAGE. The response is sent to PC_DATA_ACK (0xe2) when the data is acknowledged by the remote radio. A response of PC_DATA_NACK (0xe3) is returned when the link is broken.
+
+ START_OF_VC_SERIAL
+ +-----+-----+-----+-----+-----+-----+-----+-----+-----+
+ | 2 | 8 | B | A | H | e | l | l | o |
+ +-----+-----+-----+-----+-----+-----+-----+-----+-----+
+ Length Dest Src Data
+
+ Host A Radio A Radio B Host B
+ Data Message --->
+ Data Message --->
+ <--- ACK
+ Data Message --->
+ <--- VC_DATA_ACK_NACK_MESSAGE
+
+ START_OF_VC_SERIAL
+ +-----+-----+--------+-----+
+ | 2 | 3 | 0xe2 | B |
+ +-----+-----+--------+-----+
+ Length Dest Src
+
+#### Local Command Response
+When sending a local command, the radio responds with VC_COMMAND_COMPLETE_MESSAGE sent to PC_COMMAND_COMPLETE (0xe5) with the status VC_CMD_SUCCESS (0) or VC_CMD_ERROR (1).
+
+One pair of virtual circuit numbers allows the local host to communicate with the command interface on the local radio. The data portion of the message contains the command to be executed.
+
+* VC_COMMAND (0xfe): Destination VC used by the host computer to send a command to the local radio to be executed immediately
+
+* PC_COMMAND (0xe0): Source VC for the local command message
+
+
+ START_OF_VC_SERIAL
+ +-----+-----+------+------+-----+-----+-----+-----+-----+------+------+
+ | 2 | 8 | 0xe5 | 0xe0 | A | T | I | 1 | 1 | 0x0d | 0x0a |
+ +-----+-----+------+------+-----+-----+-----+-----+-----+------+------+
+ Length Dest Src Command
+
+ Host A Radio A
+ Command Message --->
+ <--- Command response (ASCII text)
+ +------+------+---+---+---+---+---+---+...+------+------+---+---+------+------+
+ | 0x0d | 0x0a | m | y | V | c | : | | A | 0x0d | 0x0a | O | K | 0x0d | 0x0a |
+ +------+------+---+---+---+---+---+---+...+...+--+------+---+---+------+------+
+ <--- VC_COMMAND_COMPLETE_MESSAGE
+
+ START_OF_VC_SERIAL
+ +-----+-----+--------+-----+-----+
+ | 2 | 4 | 0xe2 | A | 0 |
+ +-----+-----+--------+-----+-----+
+ Length Dest Src VC_CMD_SUCCESS
+
+#### Remote Command Response
+
+A command sent to a remote radio is acknowledged with a VC_DATA_ACK_NACK_MESSAGE sent to the PC_DATA_ACK (0xe2) or PC_DATA_NACK (0xe3) destination port. The actual command response is sent to the local radio's VC ored with PC_REMOTE_RESPONSE (0xc0). After the command response text is delivered, the command status is returned to the destination VC of PC_COMMAND_COMPLETE (0xe5) with the status of VC_CMD_SUCCESS (0) or VC_CMD_ERROR (1).
+
+The VC number range from 32 to 63 is reserved for remote command execution. The VC number equals the target radio number (0 - 31) or-ed with PC_REMOTE_COMMAND (0x20). This VC number is placed in the destination VC field and the local radio VC number is placed in the source VC field.
+
+The following example sends an ATI11 command from radio A to radio B to get radio
+B's VC number:
+
+ START_OF_VC_SERIAL
+ +-----+------+----------+-----+-----+-----+-----+-----+-----+------+------+
+ | 2 | 10 | 0x20 + B | A | A | T | I | 1 | 1 | 0x0d | 0x0a |
+ +-----+------+----------+-----+-----+-----+-----+-----+-----+------+------+
+ Length Dest Src Command
+
+ Host A Radio A Radio B
+ Command Message --->
+ Remote Command --->
+ <--- ACK
+ <--- VC_DATA_ACK_NACK_MESSAGE
+
+ START_OF_VC_SERIAL
+ +-----+-----+--------+-----+
+ | 2 | 3 | 0xe2 | B |
+ +-----+-----+--------+-----+
+ Length Dest Src
+
+ <--- Remote Command Response
+ <--- Remove Command Response
+ +---+----+----------+---+------+------+---+---+---+---+---+---+...+------+------+---+---+------+------+
+ | 2 | 18 | 0xc0 + A | B | 0x0d | 0x0a | m | y | V | c | : | | B | 0x0d | 0x0a | O | K | 0x0d | 0x0a |
+ +---+----+----------+---+------+------+---+---+---+---+---+---+...+...+--+------+---+---+------+------+
+
+ <--- VC_COMMAND_COMPLETE_MESSAGE
+ <--- VC_COMMAND_COMPLETE_MESSAGE
+
+ START_OF_VC_SERIAL
+ +-----+-----+--------+-----+-----+
+ | 2 | 4 | 0xe5 | B | 0 |
+ +-----+-----+--------+-----+-----+
+ Length Dest Src VC_CMD_SUCCESS
+
+#### VC State Response
+
+As VC links change states, the host is notified of the state changes with a VC_STATE_MESSAGE sent to PC_LINK_STATUS (0xe1). An example where radio A detects the initial HEARTBEAT frame from radio B and notifies host A of the VC link change:
+
+ Host A Radio A Radio B
+
+ <--- HEARTBEAT
+ <--- VC_STATE_MESSAGE
+
+ START_OF_VC_SERIAL
+ +-----+-----+--------+-----+----------+
+ | 2 | 4 | 0xe1 | B | Status |
+ +-----+-----+--------+-----+----------+
+ Length Dest Src VC_CMD_SUCCESS
+
+The status values are:
+
+* VC_STATE_LINK_DOWN (0): HEARTBEATs not received
+* VC_STATE_LINK_ALIVE (1): Receiving HEARTBEATs, waiting for UNKNOWN_ACKS
+* VC_STATE_SEND_UNKNOWN_ACKS (2): ATC command received, sending UNKNOWN_ACKS
+* VC_STATE_WAIT_SYNC_ACKS (3): UNKNOWN_ACKS sent, waiting for SYNC_ACKS
+* VC_STATE_WAIT_ZERO_ACKS (4): SYNC_ACKS sent, waiting for ZERO_ACKS
+* VC_STATE_CONNECTED (5): ZERO_ACKS received, ACKs cleared, ready to send data
+
+#### Reconnect Serial Response
+
+The ATZ command causes the system to reboot. Prior to the reboot, the radio responds with a message sent to PC_SERIAL_RECONNECT (0xe4). The local radio takes a couple of seconds to reset and causes the USB serial device to go off-line. The timing is critical here, the application must close the serial connection before the LoRaSerial USB device goes off-line. If the host is still holding the USB serial connection open when the LoRaSerial USB serial port goes off-line then the host may not be able to release it in time before the LoRaSerial attempts to connect its USB serial port. In this case, the LoRaSerial serial port may show up as a new device on the host system and
+further communications with the radio would no longer be possible using the previous device path.
+
+An example is below:
+
+ START_OF_VC_SERIAL
+ +-----+-----+------+------+-----+-----+-----+------+------+
+ | 2 | 8 | 0xe5 | 0xe0 | A | T | Z | 0x0d | 0x0a |
+ +-----+-----+------+------+-----+-----+-----+------+------+
+ Length Dest Src Command
+
+ Host A Radio A
+ Command Message --->
+ <--- Command response (ASCII text)
+
+ +---+---+------+------+
+ | O | K | 0x0d | 0x0a |
+ +---+---+------+------+
+
+ <--- Reconnect message
+
+ START_OF_VC_SERIAL
+ +-----+-----+--------+-----+
+ | 2 | 3 | 0xe4 | A |
+ +-----+-----+--------+-----+
+ Length Dest Src
+
+ <--- VC_COMMAND_COMPLETE_MESSAGE
+
+ START_OF_VC_SERIAL
+ +-----+-----+--------+-----+-----+
+ | 2 | 4 | 0xe2 | A | 0 |
+ +-----+-----+--------+-----+-----+
+ Length Dest Src VC_CMD_SUCCESS
+
+## Example Program
+
+The [VcServerTest.c](https://github.com/sparkfun/SparkFun_LoRaSerial/blob/release_candidate/Firmware/Tools/VcServerTest.c) is an example C program that communicates with the VC server using the virtual circuit serial interface. The first parameter is the device path to the local LoRaSerial radio. The second parameter specifies the destination VC number to send commands or data.
+
+The example program has the following features:
+
+* --reset command line option
+* --break command line option
+* Gets the local radio's virtual circuit number
+* Opens a virtual circuit to the target VC
+* Passes entered serial data to the target VC
+* Displays responses from the target VC
+
+### Debug Defines
+
+There are some useful defines that may be set to one (1) to display the host's interaction with the radio. These defines are:
+
+* DEBUG_PC_TO_RADIO
+* DEBUG_RADIO_TO_PC
+* DUMP_RADIO_TO_PC
+
+Setting these defines will display the radio communications in hexadecimal and ASCII.
+
+### --reset
+
+The reset command line option is not used very often, but sends an ATZ command to the local radio.
+
+### --break
+
+The break command line option sends an ATB command to the local radio causing it to delay for 5 times the heartbeatTimeout interval. This delay is sufficient to break all links with any remote virtual circuits. Following the delay, the radio returns to the RADIO_RESET state and brings up links to the other radios.
diff --git a/Firmware/LoRaSerial_Firmware/Arch_ESP32.h b/Firmware/LoRaSerial/Arch_ESP32.h
similarity index 76%
rename from Firmware/LoRaSerial_Firmware/Arch_ESP32.h
rename to Firmware/LoRaSerial/Arch_ESP32.h
index d0cfcf09..c81b8dcc 100644
--- a/Firmware/LoRaSerial_Firmware/Arch_ESP32.h
+++ b/Firmware/LoRaSerial/Arch_ESP32.h
@@ -4,6 +4,9 @@
#include
#define EEPROM_SIZE 1024 //ESP32 emulates EEPROM in non-volatile storage (external flash IC). Max is 508k.
+#define NVM_ERASE_VALUE 0xff
+#define NVM_UNIQUE_ID_OFFSET (EEPROM_SIZE - (MAX_VC * UNIQUE_ID_BYTES))
+
/*
Data flow
+--------+
@@ -23,6 +26,7 @@
+--------+
*/
+//Initialize the LoRaSerial board
void esp32BeginBoard()
{
//Lower power boards
@@ -42,25 +46,27 @@ void esp32BeginBoard()
strcpy(platformPrefix, "ESP32 100mW");
}
+//Initialize the USB serial port
void esp32BeginSerial(uint16_t serialSpeed)
{
-#if !defined(ENABLE_DEVELOPER)
if (settings.usbSerialWait)
-#endif //ENABLE_DEVELOPER
//Wait for serial to come online for debug printing
delay(500);
}
+//Initialize the watch dog timer
void esp32BeginWDT()
{
- petTimeoutHalf = 1000 / 2;
+ petTimeout = 1000 / 2;
}
+//Initilaize the EEPROM controller or simulation
void esp32EepromBegin()
{
EEPROM.begin(EEPROM_SIZE);
}
+//Write any remaining data to EEPROM
void esp32EepromCommit()
{
EEPROM.commit();
@@ -72,50 +78,50 @@ void esp32PetWDT()
delay(1);
}
+//Initialize the radio module
Module * esp32Radio()
{
return new Module(pin_cs, pin_dio0, pin_rst, pin_dio1);
}
+//Determine if serial input data is available
bool esp32SerialAvailable()
{
return Serial.available();
}
+//Ensure that all serial output data has been sent over USB
void esp32SerialFlush()
{
Serial.flush();
}
-void esp32SerialPrint(const char * value)
-{
- Serial.print(value);
-}
-
+//Read in the serial input data
uint8_t esp32SerialRead()
{
return (Serial.read());
}
+//Provide the serial output data to the USB layer or the UART TX FIFO
void esp32SerialWrite(uint8_t value)
{
Serial.write(value);
}
+//Reset the CPU
void esp32SystemReset()
{
ESP.restart();
}
-void esp32UniqueID(uint32_t * unique128_BitID)
+//Get the CPU's unique ID value
+void esp32UniqueID(uint8_t * unique128_BitID)
{
- unique128_BitID[0] = 0;
- unique128_BitID[1] = 0;
- unique128_BitID[2] = 0;
- unique128_BitID[3] = 0;
- esp_read_mac((uint8_t *)unique128_BitID, ESP_MAC_WIFI_STA);
+ memset(unique128_BitID, 0, UNIQUE_ID_BYTES);
+ esp_read_mac(unique128_BitID, ESP_MAC_WIFI_STA);
}
+//Provide the hardware abstraction layer (HAL) interface
const ARCH_TABLE arch = {
esp32BeginBoard, //beginBoard
esp32BeginSerial, //beginSerial
@@ -126,7 +132,6 @@ const ARCH_TABLE arch = {
esp32Radio, //radio
esp32SerialAvailable, //serialAvailable
esp32SerialFlush, //serialFlush
- esp32SerialPrint, //serialPrint
esp32SerialRead, //serialRead
esp32SerialWrite, //serialWrite
esp32SystemReset, //systemReset
diff --git a/Firmware/LoRaSerial_Firmware/Arch_SAMD.h b/Firmware/LoRaSerial/Arch_SAMD.h
similarity index 71%
rename from Firmware/LoRaSerial_Firmware/Arch_SAMD.h
rename to Firmware/LoRaSerial/Arch_SAMD.h
index 579ccfc8..b391b4e6 100644
--- a/Firmware/LoRaSerial_Firmware/Arch_SAMD.h
+++ b/Firmware/LoRaSerial/Arch_SAMD.h
@@ -1,10 +1,13 @@
#if defined(ARDUINO_ARCH_SAMD)
#ifndef __SAMD_H__
-#include //Click here to get the library: http://librarymanager/All#FlashStorage_SAMD21 v1.2.1 by Khoi Hoang
+#include //Click here to get the library: http://librarymanager/All#FlashStorage_SAMD21 v1.3.2 by Khoi Hoang
#include //https://github.com/javos65/WDTZero
WDTZero myWatchDog;
+#define NVM_ERASE_VALUE 0xff
+#define NVM_UNIQUE_ID_OFFSET (EEPROM_EMULATION_SIZE - (MAX_VC * UNIQUE_ID_BYTES))
+
/*
Data flow
+--------------+
@@ -60,6 +63,7 @@ WDTZero myWatchDog;
+--------------+
*/
+//Initialize the LoRaSerial board
void samdBeginBoard()
{
//Use ADC to check resistor divider
@@ -73,37 +77,38 @@ void samdBeginBoard()
pin_rst = 6;
pin_cts = 30;
pin_rts = 38;
- pin_txLED = 31;
- pin_rxLED = A5;
- pin_rssi1LED = A3;
- pin_rssi2LED = A4;
- pin_rssi3LED = 8;
- pin_rssi4LED = 9;
+ pin_blue_LED = 31;
+ pin_yellow_LED = A5;
+ pin_green_1_LED = A3;
+ pin_green_2_LED = A4;
+ pin_green_3_LED = 8;
+ pin_green_4_LED = 9;
pin_trainButton = 4;
pin_trigger = A0;
+ pin_hop_timer = A1;
//Flow control
pinMode(pin_rts, OUTPUT);
- digitalWrite(pin_rts, HIGH);
+ updateRTS(false); //Disable serial input until the radio starts
pinMode(pin_cts, INPUT_PULLUP);
//LEDs
- pinMode(pin_rssi1LED, OUTPUT);
- digitalWrite(pin_rssi1LED, LOW);
- pinMode(pin_rssi2LED, OUTPUT);
- digitalWrite(pin_rssi2LED, LOW);
- pinMode(pin_rssi3LED, OUTPUT);
- digitalWrite(pin_rssi3LED, LOW);
- pinMode(pin_rssi4LED, OUTPUT);
- digitalWrite(pin_rssi4LED, LOW);
-
- pinMode(pin_txLED, OUTPUT);
- digitalWrite(pin_txLED, LOW);
- pinMode(pin_rxLED, OUTPUT);
- digitalWrite(pin_rxLED, LOW);
+ pinMode(pin_green_1_LED, OUTPUT);
+ digitalWrite(pin_green_1_LED, LOW);
+ pinMode(pin_green_2_LED, OUTPUT);
+ digitalWrite(pin_green_2_LED, LOW);
+ pinMode(pin_green_3_LED, OUTPUT);
+ digitalWrite(pin_green_3_LED, LOW);
+ pinMode(pin_green_4_LED, OUTPUT);
+ digitalWrite(pin_green_4_LED, LOW);
+
+ pinMode(pin_blue_LED, OUTPUT);
+ digitalWrite(pin_blue_LED, LOW);
+ pinMode(pin_yellow_LED, OUTPUT);
+ digitalWrite(pin_yellow_LED, LOW);
//Train button input
pinMode(pin_trainButton, INPUT_PULLUP);
@@ -111,6 +116,8 @@ void samdBeginBoard()
//Debug
pinMode(pin_trigger, OUTPUT);
digitalWrite(pin_trigger, HIGH);
+ pinMode(pin_hop_timer, OUTPUT);
+ digitalWrite(pin_hop_timer, LOW);
//Get average of board ID voltage divider
int val = 0;
@@ -122,37 +129,50 @@ void samdBeginBoard()
float boardID = 3.3 * val / 1024;
//Use ADC to check board ID resistor divider
- if (boardID > 1.64 * 0.9 && boardID < 1.64 * 1.1)
+ if (boardID > 1.64 * 0.95 && boardID < 1.64 * 1.05)
{
+ radioBand = 915;
strcpy(platformPrefix, "SAMD21 1W 915MHz");
}
+ else if (boardID > 2.20 * 0.95 && boardID < 2.20 * 1.05)
+ {
+ radioBand = 433;
+ strcpy(platformPrefix, "SAMD21 1W 433MHz");
+ }
+ else if (boardID > 2.48 * 0.95 && boardID < 2.48 * 1.05)
+ {
+ radioBand = 868;
+ strcpy(platformPrefix, "SAMD21 1W 868MHz");
+ }
else
{
strcpy(platformPrefix, "SAMD21 1W");
}
}
+//Initialize the USB serial port and the UART
void samdBeginSerial(uint16_t serialSpeed)
{
-#if !defined(ENABLE_DEVELOPER)
if (settings.usbSerialWait)
-#endif //ENABLE_DEVELOPER
//Wait for serial to come online for debug printing
while (!Serial);
Serial1.begin(serialSpeed);
}
+//Initialize the watch dog timer
void samdBeginWDT()
{
- myWatchDog.setup(WDT_HARDCYCLE250m); // Initialize WDT with 250ms timeout
- petTimeoutHalf = 250 / 2;
+ myWatchDog.setup(WDT_HARDCYCLE2S); // Initialize WDT with 2s timeout
+ petTimeout = 1800;
}
+//Initilaize the EEPROM controller or simulation
void samdEepromBegin()
{
}
+//Write any remaining data to EEPROM
void samdEepromCommit()
{
EEPROM.commit();
@@ -165,28 +185,26 @@ void samdPetWDT()
myWatchDog.clear();
}
+//Initialize the radio module
Module * samdRadio()
{
return new Module(pin_cs, pin_dio0, pin_rst, pin_dio1);
}
+//Determine if serial input data is available
bool samdSerialAvailable()
{
return (Serial.available() || Serial1.available());
}
+//Ensure that all serial output data has been sent over USB and via the UART
void samdSerialFlush()
{
Serial.flush();
Serial1.flush();
}
-void samdSerialPrint(const char * value)
-{
- Serial.print(value);
- Serial1.print(value);
-}
-
+//Read in the serial input data
uint8_t samdSerialRead()
{
byte incoming = 0;
@@ -197,26 +215,34 @@ uint8_t samdSerialRead()
return (incoming);
}
+//Provide the serial output data to the USB layer or the UART TX FIFO
void samdSerialWrite(uint8_t value)
{
Serial.write(value);
Serial1.write(value);
}
+//Reset the CPU
void samdSystemReset()
{
NVIC_SystemReset();
}
-void samdUniqueID(uint32_t * unique128_BitID)
+//Get the CPU's unique ID value
+void samdUniqueID(uint8_t * unique128_BitID)
{
+ uint32_t id[UNIQUE_ID_BYTES / 4];
+
//Read the CPU's unique ID value
- unique128_BitID[0] = *(uint32_t *)0x0080a00c;
- unique128_BitID[1] = *(uint32_t *)0x0080a040;
- unique128_BitID[2] = *(uint32_t *)0x0080a044;
- unique128_BitID[3] = *(uint32_t *)0x0080a048;
+ id[0] = *(uint32_t *)0x0080a00c;
+ id[1] = *(uint32_t *)0x0080a040;
+ id[2] = *(uint32_t *)0x0080a044;
+ id[3] = *(uint32_t *)0x0080a048;
+
+ memcpy(unique128_BitID, id, UNIQUE_ID_BYTES);
}
+//Provide the hardware abstraction layer (HAL) interface
const ARCH_TABLE arch = {
samdBeginBoard, //beginBoard
samdBeginSerial, //beginSerial
@@ -227,7 +253,6 @@ const ARCH_TABLE arch = {
samdRadio, //radio
samdSerialAvailable, //serialAvailable
samdSerialFlush, //serialFlush
- samdSerialPrint, //serialPrint
samdSerialRead, //serialRead
samdSerialWrite, //serialWrite
samdSystemReset, //systemReset
diff --git a/Firmware/LoRaSerial/Begin.ino b/Firmware/LoRaSerial/Begin.ino
new file mode 100644
index 00000000..afab0f2c
--- /dev/null
+++ b/Firmware/LoRaSerial/Begin.ino
@@ -0,0 +1,112 @@
+//Blink LEDs to indicate the completion of system setup
+void blinkStartup()
+{
+ for (int x = 0 ; x < 3 ; x++)
+ {
+ digitalWrite(pin_green_1_LED, HIGH);
+ digitalWrite(pin_green_2_LED, HIGH);
+ digitalWrite(pin_green_3_LED, HIGH);
+ digitalWrite(pin_green_4_LED, HIGH);
+ digitalWrite(pin_blue_LED, HIGH);
+ digitalWrite(pin_yellow_LED, HIGH);
+ delay(50);
+
+ digitalWrite(pin_green_1_LED, LOW);
+ digitalWrite(pin_green_2_LED, LOW);
+ digitalWrite(pin_green_3_LED, LOW);
+ digitalWrite(pin_green_4_LED, LOW);
+ digitalWrite(pin_blue_LED, LOW);
+ digitalWrite(pin_yellow_LED, LOW);
+ delay(50);
+ }
+}
+
+//Initialize the radio layer
+void beginLoRa()
+{
+ radio = arch.radio();
+
+ float centerFreq = (settings.frequencyMax - settings.frequencyMin) / 2;
+ centerFreq += settings.frequencyMin;
+
+ int state = radio.begin(centerFreq); //Doesn't matter what freq we start at
+ if (state != RADIOLIB_ERR_NONE)
+ {
+ systemPrint("Radio init failed with code: ");
+ systemPrintln(state);
+ waitForever("Radio init failed!");
+ }
+
+ changeState(RADIO_RESET);
+}
+
+//Initialize the button driver
+void beginButton()
+{
+ if (pin_trainButton != PIN_UNDEFINED)
+ {
+ trainBtn = new Button(pin_trainButton); //Create the button
+ trainBtn->begin();
+ }
+}
+
+//Delay with pets of WDT when needed
+void delayWDT(uint16_t delayAmount)
+{
+ unsigned long startTime = millis();
+ while (millis() - startTime < delayAmount)
+ {
+ delay(1);
+ petWDT();
+ }
+}
+
+//Initialize the serial drivers
+void beginSerial(uint16_t serialSpeed)
+{
+ Serial.begin(serialSpeed);
+ arch.beginSerial(serialSpeed);
+}
+
+//Ensure the watch dog timer does not fire which would cause a CPU hardware reset
+void petWDT()
+{
+ //Petting the dog takes a long time (~4.5ms on SAMD21) so it's only done after we've passed the timeout
+ if (millis() - lastPet > petTimeout)
+ {
+ lastPet = millis();
+ arch.petWDT();
+ }
+}
+
+//Start the timer measuring the dwell interval and indicating that it is time to
+//hop channels
+void beginChannelTimer()
+{
+ if (channelTimer.attachInterruptInterval_MS(settings.maxDwellTime, channelTimerHandler) == false)
+ systemPrintln("Error starting ChannelTimer!");
+
+ stopChannelTimer(); //Start timer in state machine - beginChannelTimer
+}
+
+//ISR that fires when channel timer expires
+void channelTimerHandler()
+{
+ channelTimerStart = millis(); //Record when this ISR happened. Used for calculating clock sync.
+ radioCallHistory[RADIO_CALL_channelTimerHandler] = channelTimerStart;
+
+ //If the last timer was used to sync clocks, restore full timer interval
+ if (reloadChannelTimer == true)
+ {
+ reloadChannelTimer = false;
+ channelTimer.setInterval_MS(settings.maxDwellTime, channelTimerHandler);
+ channelTimerMsec = settings.maxDwellTime; //ISR update
+ }
+
+ if (settings.frequencyHop)
+ {
+ digitalWrite(pin_hop_timer, ((channelNumber + 1) % settings.numberOfChannels) & 1);
+ triggerEvent(TRIGGER_CHANNEL_TIMER_ISR);
+ timeToHop = true;
+ }
+}
diff --git a/Firmware/LoRaSerial/Commands.ino b/Firmware/LoRaSerial/Commands.ino
new file mode 100644
index 00000000..d94fc3ff
--- /dev/null
+++ b/Firmware/LoRaSerial/Commands.ino
@@ -0,0 +1,1415 @@
+//To add a new ATSxx command:
+//Add an entry to the "commands" table below
+
+//To add a new commnd prefix such as AT or RT
+//Add an entry to the "prefix" table below
+
+//----------------------------------------
+// Data structures
+//----------------------------------------
+
+enum {
+ TYPE_BOOL = 0,
+ TYPE_FLOAT,
+ TYPE_KEY,
+ TYPE_SPEED_AIR,
+ TYPE_SPEED_SERIAL,
+ TYPE_U8,
+ TYPE_U16,
+ TYPE_U32,
+};
+
+typedef bool (* COMMAND_ROUTINE)(const char * commandString);
+typedef struct
+{
+ const char * prefix;
+ bool supportedInVcMode;
+ COMMAND_ROUTINE processCommand;
+} COMMAND_PREFIX;
+
+//----------------------------------------
+// Command prefix routines
+//----------------------------------------
+
+//Process the AT commands
+bool commandAT(const char * commandString)
+{
+ uint32_t delayMillis;
+ long deltaMillis;
+ uint8_t id[UNIQUE_ID_BYTES];
+ const char * string;
+ unsigned long timer;
+ VIRTUAL_CIRCUIT * vc = &virtualCircuitList[cmdVc];
+ uint8_t vcIndex;
+
+ //'AT'
+ if (commandLength == 2)
+ return true;
+
+ //AT?, ATA, ATB, ATC, ATG, ATI, ATO, ATZ commands
+ if (commandLength == 3)
+ {
+ switch (commandString[2])
+ {
+ default:
+ return false;
+
+ case ('?'): //Display the command help
+ systemPrintln("Command summary:");
+ systemPrintln(" AT? - Print the command summary");
+ systemPrintln(" ATA - Get the current VC status");
+ systemPrintln(" ATB - Break the link");
+ systemPrintln(" ATC - Establish VC connection for data");
+ systemPrintln(" ATD - Display the debug settings");
+ systemPrintln(" ATF - Restore factory settings");
+ systemPrintln(" ATG - Generate new netID and encryption key");
+ systemPrintln(" ATI - Display the radio version");
+ systemPrintln(" ATI? - Display the information commands");
+ systemPrintln(" ATIn - Display system information");
+ systemPrintln(" ATO - Exit command mode");
+ systemPrintln(" ATP - Display probe trigger settings");
+ systemPrintln(" ATR - Display radio settings");
+ systemPrintln(" ATS - Display the serial settings");
+ systemPrintln(" ATT - Enter training mode");
+ systemPrintln(" ATV - Display virtual circuit settings");
+ systemPrintln(" ATW - Save current settings to NVM");
+ systemPrintln(" ATZ - Reboot the radio");
+ systemPrintln(" AT-Param=xxx - Set parameter's value to xxx by name (Param)");
+ systemPrintln(" AT-Param? - Print parameter's current value by name (Param)");
+ systemPrintln(" AT-? - Display the setting values");
+ return true;
+
+ case ('A'): //ATA - Get the current VC status
+ for (int index = 0; index < MAX_VC; index++)
+ vcSendPcStateMessage(index, virtualCircuitList[index].vcState);
+ return true;
+
+ case ('B'): //ATB - Break the link
+
+ //Compute the time delay
+ delayMillis = (VC_LINK_BREAK_MULTIPLIER + 2) * settings.heartbeatTimeout;
+
+ //Warn the user of the delay
+ systemPrint("Delaying ");
+ systemPrint(delayMillis / 1000);
+ systemPrintln(" seconds to break the link");
+ outputSerialData(true);
+
+ //Flag the links as broken
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ for (int i = 0; i < MAX_VC; i++)
+ if ((virtualCircuitList[i].vcState != VC_STATE_LINK_DOWN) && (i != myVc))
+ vcBreakLink(i);
+ }
+ else if (settings.operatingMode == MODE_POINT_TO_POINT)
+ {
+ breakLink();
+ outputSerialData(true);
+ }
+
+ //Idle the system to break the link
+ //This is required on the server system which does not request an VC number assignment
+ timer = millis();
+ while ((millis() - timer) < ((VC_LINK_BREAK_MULTIPLIER + 2) * settings.heartbeatTimeout))
+ petWDT();
+ changeState(RADIO_RESET);
+
+ //Display the end of the delay
+ systemPrintln("Delay done");
+ return true;
+
+ case ('C'): //ATC - Establish VC connection for data
+ if ((settings.operatingMode != MODE_VIRTUAL_CIRCUIT)
+ || (vc->vcState != VC_STATE_LINK_ALIVE))
+ return false;
+ if (cmdVc == myVc)
+ vcChangeState(cmdVc, VC_STATE_CONNECTED);
+ else
+ vcChangeState(cmdVc, VC_STATE_SEND_UNKNOWN_ACKS);
+ return true;
+
+ case ('F'): //ATF - Restore default parameters
+ settings = defaultSettings; //Overwrite all system settings with defaults
+
+ validateSettings(); //Modify defaults for each radio type (915, 868, 433, etc)
+
+ tempSettings = settings; //Overwrite all temp settings with defaults
+ forceRadioReset = true;
+
+ recordSystemSettings();
+
+ //Clear the unique ID table
+ for (vcIndex = 0; vcIndex < MAX_VC; vcIndex++)
+ nvmEraseUniqueId(vcIndex);
+ return true;
+
+ case ('G'): //ATG - Generate a new netID and encryption key
+ generateRandomKeysID(&tempSettings);
+ return true;
+
+ case ('I'): //ATI
+ //Shows the radio version
+ systemPrint("SparkFun LoRaSerial ");
+ systemPrint(platformPrefix);
+ systemPrint(" v");
+ systemPrint(FIRMWARE_VERSION_MAJOR);
+ systemPrint(".");
+ systemPrintln(FIRMWARE_VERSION_MINOR);
+ return true;
+
+ case ('O'): //ATO - Exit command mode
+ if (printerEndpoint == PRINT_TO_RF)
+ //If we are pointed at the RF link, send ok and wait for response ACK before applying settings
+ return true;
+
+ inCommandMode = false; //Return to printing normal RF serial data
+
+ settings = tempSettings; //Apply user's modifications
+
+ if (writeOnCommandExit)
+ {
+ writeOnCommandExit = false;
+ recordSystemSettings();
+ }
+
+ //If a setting was applied that requires radio reset, do so
+ if (forceRadioReset)
+ {
+ forceRadioReset = false;
+ changeState(RADIO_RESET);
+ }
+
+ return true;
+
+ case ('T'): //ATT - Enter training mode
+ trainingSettings = tempSettings; //Apply user's modifications
+ selectTraining();
+ return true;
+
+ case ('W'): //ATW - Write parameters to the flash memory
+ writeOnCommandExit = true;
+ return true;
+
+ case ('Z'): //ATZ - Reboots the system
+ if (writeOnCommandExit)
+ {
+ settings = tempSettings; //Apply user's modifications
+ recordSystemSettings();
+ }
+
+ reportOK();
+ commandReset();
+ return true;
+ }
+ }
+
+ //ATIx commands
+ if (commandString[2] == 'I' && commandLength == 4)
+ {
+ switch (commandString[3])
+ {
+ default:
+ return false;
+
+ case ('?'): //ATI? - Display the information commands
+ systemPrintln(" ATI0 - Show user settable parameters");
+ systemPrintln(" ATI1 - Show board variant");
+ systemPrintln(" ATI2 - Show firmware version");
+ systemPrintln(" ATI3 - Display RSSI value");
+ systemPrintln(" ATI4 - Get random byte from RSSI");
+ systemPrintln(" ATI5 - Show max possible bytes per second");
+ systemPrintln(" ATI6 - Display AES key");
+ systemPrintln(" ATI7 - Show current FHSS channel");
+ systemPrintln(" ATI8 - Display system unique ID");
+ systemPrintln(" ATI9 - Display the maximum datagram size");
+ systemPrintln(" ATI10 - Display radio metrics");
+ systemPrintln(" ATI11 - Return myVc value");
+ systemPrintln(" ATI12 - Display the VC details");
+ systemPrintln(" ATI13 - Display the SX1276 registers");
+ systemPrintln(" ATI14 - Dump the radioTxBuffer");
+ systemPrintln(" ATI15 - Dump the NVM unique ID table");
+ return true;
+
+ case ('0'): //ATI0 - Show user settable parameters
+ displayParameters(0, true);
+ return true;
+
+ case ('1'): //ATI1 - Show board variant
+ systemPrint("SparkFun LoRaSerial ");
+ systemPrint(platformPrefix);
+ systemPrint("\r\n");
+ return true;
+
+ case ('2'): //ATI2 - Show firmware version
+ systemPrint(FIRMWARE_VERSION_MAJOR);
+ systemPrint(".");
+ systemPrintln(FIRMWARE_VERSION_MINOR);
+ return true;
+
+ case ('3'): //ATI3 - Display latest RSSI
+ systemPrintln(radio.getRSSI());
+ return true;
+
+ case ('4'): //ATI4 - Get random byte from RSSI
+ systemPrintln(radio.randomByte());
+ return true;
+
+ case ('5'): //ATI5 - Show max possible bytes per second
+ systemPrintln(calcMaxThroughput());
+ return true;
+
+ case ('6'): //ATI6 - Display currentState
+ displayState(radioState);
+ return true;
+
+ case ('7'): //ATI7 - Show current FHSS channel
+ systemPrintln(channelNumber);
+ return true;
+
+ case ('8'): //ATI8 - Display the system's unique ID
+ systemPrintUniqueID(myUniqueId);
+ systemPrintln();
+ return true;
+
+ case ('9'): //ATI9 - Display the maximum datagram size
+ systemPrint("Maximum datagram size: ");
+ systemPrintln(maxDatagramSize);
+ return true;
+ }
+ }
+ if ((commandString[2] == 'I') && (commandString[3] == '1') && (commandLength == 5))
+ {
+ switch (commandString[4])
+ {
+ default:
+ return false;
+
+ case ('0'): //ATI10 - Display radio metrics
+ systemPrint("Radio Metrics @ ");
+ systemPrintTimestamp(millis() + timestampOffset);
+ systemPrintln();
+ if (settings.operatingMode == MODE_POINT_TO_POINT)
+ {
+ systemPrint(" Link Status: ");
+ systemPrintln((radioState >= RADIO_P2P_LINK_UP) ? "Up" : "Down");
+ systemPrint(" Last RX: ");
+ systemPrintTimestamp(lastRxDatagram + timestampOffset);
+ systemPrintln();
+ systemPrint(" First RX: ");
+ systemPrintTimestamp(lastLinkUpTime + timestampOffset);
+ systemPrintln();
+ delayMillis = lastRxDatagram - lastLinkUpTime;
+ if (((int)delayMillis) >= 0)
+ {
+ systemPrint(" Up Time: ");
+ systemPrintTimestamp(delayMillis);
+ systemPrintln();
+ }
+ outputSerialData(true);
+ petWDT();
+ }
+
+ //Transmitter metrics
+ systemPrintln(" Sent");
+ systemPrint(" Datagrams: ");
+ systemPrintln(datagramsSent);
+ systemPrint(" Frames: ");
+ systemPrintln(framesSent);
+ systemPrint(" Lost Frames: ");
+ systemPrintln(lostFrames);
+ outputSerialData(true);
+ petWDT();
+
+ //Receiver metrics
+ systemPrintln(" Received");
+ systemPrint(" Frames: ");
+ systemPrintln(framesReceived);
+ systemPrint(" Datagrams: ");
+ systemPrintln(datagramsReceived);
+ systemPrint(" Bad CRC: ");
+ systemPrintln(badCrc);
+ systemPrint(" Bad Frames: ");
+ systemPrintln(badFrames);
+ systemPrint(" Duplicate Frames: ");
+ systemPrintln(duplicateFrames);
+ systemPrint(" Insufficient Space: ");
+ systemPrintln(insufficientSpace);
+ systemPrint(" Net ID Mismatch: ");
+ systemPrintln(netIdMismatch);
+ systemPrint(" Link failures: ");
+ systemPrintln(linkFailures);
+ outputSerialData(true);
+ petWDT();
+
+ //ACK management metrics
+ if (settings.operatingMode == MODE_POINT_TO_POINT)
+ {
+ vc = &virtualCircuitList[0];
+ systemPrintln(" ACK Management");
+ systemPrint(" Last RX ACK number: ");
+ systemPrintln(vc->rxAckNumber);
+ systemPrint(" Next RX ACK number: ");
+ systemPrintln(vc->rmtTxAckNumber);
+ systemPrint(" Last TX ACK number: ");
+ systemPrintln(vc->txAckNumber);
+ systemPrint(" ackTimer: ");
+ if (ackTimer)
+ systemPrintTimestamp(ackTimer + timestampOffset);
+ else
+ systemPrint("Not Running");
+ systemPrintln();
+ }
+ else if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ systemPrintln(" ACK Management");
+ systemPrint(" ackTimer: ");
+ if (ackTimer)
+ {
+ systemPrint("VC ");
+ systemPrint(txDestVc);
+ systemPrint(", ");
+ systemPrintTimestamp(ackTimer + timestampOffset);
+ systemPrintln();
+ }
+ else
+ systemPrintln("Not Running");
+ systemPrint(" vcConnecting: ");
+ systemPrint((int)vcConnecting, HEX);
+ if (vcConnecting)
+ {
+ systemPrintln();
+ for (int index = 0; index < MAX_VC; index++)
+ {
+ if (vcConnecting & (1 << index))
+ {
+ systemPrint(" VC ");
+ if (index < 10)
+ systemWrite(' ');
+ systemPrint(index);
+ systemPrint(" State: ");
+ systemPrintln(vcStateNames[virtualCircuitList[index].vcState]);
+ }
+ }
+ }
+ else
+ systemPrintln("None");
+ }
+ outputSerialData(true);
+ petWDT();
+
+ //Clock synchronization
+ systemPrintln(" Clock Synchronization");
+ systemPrint(" ACK Time: ");
+ systemPrint(txDataAckUsec);
+ systemPrintln(" uSec");
+ systemPrint(" FIND_PARTNER Time: ");
+ systemPrint(txFindPartnerUsec);
+ systemPrintln(" uSec");
+ systemPrint(" HEARTBEAT Time: ");
+ systemPrint(txHeartbeatUsec);
+ systemPrintln(" uSec");
+ systemPrint(" SYNC_CLOCKS Time: ");
+ systemPrint(txSyncClocksUsec);
+ systemPrintln(" uSec");
+ systemPrint(" Uptime: ");
+ deltaMillis = millis();
+ systemPrintTimestamp(deltaMillis);
+ systemPrintln();
+ systemPrint(" TimeStampOffset: ");
+ if (timestampOffset < 0)
+ {
+ systemPrint("-");
+ systemPrintTimestamp(-timestampOffset);
+ }
+ else
+ systemPrintTimestamp(timestampOffset);
+ systemPrintln();
+ systemPrint(" Adjusted Time: ");
+ systemPrintTimestamp(deltaMillis + timestampOffset);
+ systemPrintln();
+ outputSerialData(true);
+ petWDT();
+
+ //Circular buffer metrics
+ systemPrintln(" Circular Buffers");
+ systemPrint(" serialReceiveBuffer: rxHead: ");
+ systemPrint(rxHead);
+ systemPrint(", rxTail: ");
+ systemPrint(rxTail);
+ systemPrint(", ");
+ systemPrint(availableRXBytes());
+ systemPrintln(" bytes");
+ systemPrint(" serialTransmitBuffer: txHead: ");
+ systemPrint(txHead);
+ systemPrint(", txTail: ");
+ systemPrint(txTail);
+ systemPrint(", ");
+ systemPrint(availableTXBytes());
+ systemPrintln(" bytes");
+ systemPrint(" radioTxBuffer: radioTxHead: ");
+ systemPrint(radioTxHead);
+ systemPrint(", radioTxTail: ");
+ systemPrint(radioTxTail);
+ systemPrint(", ");
+ systemPrint(availableRadioTXBytes());
+ systemPrintln(" bytes");
+ systemPrint(" inCommandMode: ");
+ systemPrintln(inCommandMode ? "True" : "False");
+ systemPrint(" commandRXBuffer: commandRXHead: ");
+ systemPrint(commandRXHead);
+ systemPrint(", commandRXTail: ");
+ systemPrint(commandRXTail);
+ systemPrint(", ");
+ systemPrint(availableRXCommandBytes());
+ systemPrintln(" bytes");
+ systemPrint(" commandTXBuffer: commandTXHead: ");
+ systemPrint(commandTXHead);
+ systemPrint(", commandTXTail: ");
+ systemPrint(commandTXTail);
+ systemPrint(", ");
+ systemPrint(availableTXCommandBytes());
+ systemPrintln(" bytes");
+ outputSerialData(true);
+ petWDT();
+
+ //Radio metrics
+ systemPrintln(" Radio");
+ systemPrint(" Channel: ");
+ systemPrintln(channelNumber);
+ systemPrint(" Frequency: ");
+ systemPrint(radioFrequency, 3);
+ systemPrint(" MHz");
+ if (radioFrequency != channels[channelNumber])
+ {
+ systemPrint(" = ");
+ systemPrint(channels[channelNumber], 3);
+ systemPrint(" MHz + ");
+ systemPrint((radioFrequency - channels[channelNumber]) * 1000, 0);
+ systemPrint(" KHz");
+ }
+ systemPrintln();
+ systemPrint(" maxDwellTime: ");
+ systemPrint(settings.maxDwellTime);
+ systemPrintln(" mSec");
+ if (channelNumber)
+ {
+ systemPrint(" Next Ch 0 time: ");
+ systemPrintTimestamp(millis() + mSecToChannelZero() + timestampOffset);
+ int hopCount = settings.numberOfChannels - channelNumber;
+ systemPrint(", in ");
+ systemPrint(hopCount);
+ systemPrintln(" hops");
+ }
+ systemPrint(" Last Successful Transmit: ");
+ if (txSuccessMillis)
+ {
+ systemPrintTimestamp(txSuccessMillis + timestampOffset);
+ systemPrintln();
+ }
+ else
+ systemPrintln("None");
+ systemPrint(" Last Transmit Failure: ");
+ if (txFailureMillis)
+ {
+ systemPrintTimestamp(txFailureMillis + timestampOffset);
+ systemPrint(", Status: ");
+ systemPrint(txFailureState);
+ string = getRadioStatusCode(txFailureState);
+ if (string)
+ {
+ systemPrint(", ");
+ systemPrint(string);
+ }
+ systemPrintln();
+ }
+ else
+ systemPrintln("None");
+ systemPrint(" Last Successful Receive: ");
+ if (rxSuccessMillis)
+ {
+ systemPrintTimestamp(rxSuccessMillis + timestampOffset);
+ systemPrintln();
+ }
+ else
+ systemPrintln("None");
+ systemPrint(" Last Receive Failure: ");
+ if (rxFailureMillis)
+ {
+ systemPrintTimestamp(rxFailureMillis + timestampOffset);
+ systemPrint(", Status: ");
+ systemPrint(rxFailureState);
+ string = getRadioStatusCode(rxFailureState);
+ if (string)
+ {
+ systemPrint(", ");
+ systemPrint(string);
+ }
+ systemPrintln();
+ }
+ else
+ systemPrintln("None");
+ systemPrint(" radio.startReceive Failure: ");
+ if (startReceiveFailureMillis)
+ {
+ systemPrintTimestamp(startReceiveFailureMillis + timestampOffset);
+ systemPrintln();
+ systemPrint(" radio.startReceive Status: ");
+ systemPrintln(startReceiveFailureState);
+ }
+ else
+ systemPrintln("None");
+ systemPrint(" transactionComplete: ");
+ systemPrintln(transactionComplete ? "True" : "False");
+ systemPrint(" lastReceiveInProcessTrue @ ");
+ systemPrintTimestamp(lastReceiveInProcessTrue + timestampOffset);
+ systemPrintln();
+ systemPrint(" lastModemStatus: ");
+ systemPrint(lastModemStatus, HEX);
+ systemPrintln();
+ systemPrint(" irqFlags: 0x");
+ systemPrint(irqFlags, HEX);
+ systemPrintln();
+ if (irqFlags & 0x80)
+ systemPrintln(" RX Timeout");
+ if (irqFlags & 0x40)
+ systemPrintln(" RX Done");
+ if (irqFlags & 0x20)
+ systemPrintln(" Payload CRC Error");
+ if (irqFlags & 0x10)
+ systemPrintln(" Valid Header");
+ if (irqFlags & 8)
+ systemPrintln(" TX Done");
+ if (irqFlags & 4)
+ systemPrintln(" CAD Done");
+ if (irqFlags & 2)
+ systemPrintln(" FHSS Change Channel");
+ if (irqFlags & 1)
+ systemPrintln(" CAD Detected");
+ systemPrint(" receiveInProcess: ");
+ systemPrintln(receiveInProcess() ? "True" : "False");
+ outputSerialData(true);
+ petWDT();
+
+ //Call history
+ systemPrintln(" Call History");
+ displayRadioCallHistory();
+ outputSerialData(true);
+ petWDT();
+
+ //State history
+ systemPrintln(" State History");
+ displayRadioStateHistory();
+ return true;
+
+ case ('1'): //ATI11 - Return myVc value
+ systemPrintln();
+ systemPrint("myVc: ");
+ systemPrintln(myVc);
+ return true;
+
+ case ('2'): //ATI12 - Display the VC details
+ systemPrintTimestamp();
+ systemPrint("VC ");
+ systemPrint(cmdVc);
+ systemPrint(": ");
+ if (!vc->flags.valid)
+ systemPrintln("Down, Not valid");
+ else
+ {
+ systemPrintln(vcStateNames[vc->vcState]);
+ systemPrintTimestamp();
+ systemPrint(" ID: ");
+ systemPrintUniqueID(vc->uniqueId);
+ systemPrintln(vc->flags.valid ? " (Valid)" : " (Invalid)");
+
+ //Heartbeat metrics
+ systemPrintTimestamp();
+ systemPrintln(" Heartbeats");
+ if (cmdVc == myVc)
+ {
+ systemPrintTimestamp();
+ systemPrint(" Next TX: ");
+ systemPrintTimestamp(heartbeatTimer + heartbeatRandomTime + timestampOffset);
+ systemPrintln();
+ }
+ systemPrintTimestamp();
+ systemPrint(" Last: ");
+ systemPrintTimestamp(vc->lastTrafficMillis + timestampOffset);
+ systemPrintln();
+ systemPrintTimestamp();
+ systemPrint(" First: ");
+ systemPrintTimestamp(vc->firstHeartbeatMillis + timestampOffset);
+ systemPrintln();
+ systemPrintTimestamp();
+ systemPrint(" Up Time: ");
+ deltaMillis = vc->lastTrafficMillis - vc->firstHeartbeatMillis;
+ if (deltaMillis < 0)
+ deltaMillis = -deltaMillis;
+ systemPrintTimestamp(deltaMillis);
+ systemPrintln();
+ outputSerialData(true);
+ petWDT();
+
+ //Transmitter metrics
+ systemPrintTimestamp();
+ systemPrintln(" Sent");
+ systemPrintTimestamp();
+ systemPrint(" Frames: ");
+ systemPrintln(vc->framesSent);
+ systemPrintTimestamp();
+ systemPrint(" Messages: ");
+ systemPrintln(vc->messagesSent);
+ outputSerialData(true);
+ petWDT();
+
+ //Receiver metrics
+ systemPrintTimestamp();
+ systemPrintln(" Received");
+ systemPrintTimestamp();
+ systemPrint(" Frames: ");
+ systemPrintln(vc->framesReceived);
+ systemPrintTimestamp();
+ systemPrint(" Messages: ");
+ systemPrintln(vc->messagesReceived);
+ systemPrintTimestamp();
+ systemPrint(" Bad Lengths: ");
+ systemPrintln(vc->badLength);
+ systemPrintTimestamp();
+ systemPrint(" Link Failures: ");
+ systemPrintln(linkFailures);
+ outputSerialData(true);
+ petWDT();
+
+ //ACK Management metrics
+ systemPrintTimestamp();
+ systemPrintln(" ACK Management");
+ systemPrintTimestamp();
+ systemPrint(" Last RX ACK number: ");
+ systemPrintln(vc->rxAckNumber);
+ systemPrintTimestamp();
+ systemPrint(" Next RX ACK number: ");
+ systemPrintln(vc->rmtTxAckNumber);
+ systemPrintTimestamp();
+ systemPrint(" Last TX ACK number: ");
+ systemPrintln(vc->txAckNumber);
+ if (txDestVc == cmdVc)
+ {
+ systemPrintTimestamp();
+ systemPrint(" ackTimer: ");
+ if (ackTimer)
+ systemPrintTimestamp(ackTimer + timestampOffset);
+ else
+ systemPrint("Not Running");
+ systemPrintln();
+ }
+ }
+ return true;
+
+ case ('3'): //ATI13 - Display the SX1276 registers
+ printSX1276Registers();
+ return true;
+
+ case ('4'): //ATI14 - Dump the radioTxBuffer
+ systemPrintln("radioTxBuffer:");
+ dumpCircularBuffer(radioTxBuffer, radioTxTail, sizeof(radioTxBuffer), availableRadioTXBytes());
+ return true;
+
+ case ('5'): //ATI15 - Dump the NVM unique ID table
+ systemPrintln("NVM Unique ID Table");
+ for (vcIndex = 0; vcIndex < MAX_VC; vcIndex++)
+ {
+ systemPrint(" ");
+ if (vcIndex < 10)
+ systemWrite(' ');
+ systemPrint(vcIndex);
+ systemPrint(": ");
+ if (nvmIsVcUniqueIdSet(vcIndex))
+ {
+ nvmGetUniqueId(vcIndex, id);
+ systemPrintUniqueID(id);
+ systemPrintln();
+ }
+ else
+ systemPrintln("Empty");
+ }
+ return true;
+ }
+ }
+
+ //Invalid command
+ return false;
+}
+
+//Send the AT command over RF link
+bool sendRemoteCommand(const char * commandString)
+{
+ //We cannot send a command if not linked
+ if (isLinked() == false)
+ return false;
+
+ //Move this command into the transmit buffer
+ for (int x = 0 ; x < commandLength ; x++)
+ {
+ commandTXBuffer[commandTXHead++] = commandString[x];
+ commandTXHead %= sizeof(commandTXBuffer);
+ }
+ remoteCommandResponse = false;
+ return true;
+}
+
+//----------------------------------------
+// Command prefix table
+//----------------------------------------
+
+const COMMAND_PREFIX prefixTable[] = {
+ {"ATD", 1, commandDisplayDebug},
+ {"ATP", 1, commandDisplayProbe},
+ {"ATR", 1, commandDisplayRadio},
+ {"ATS", 1, commandDisplaySerial},
+ {"ATV", 1, commandDisplayVirtualCircuit},
+ {"AT-?", 1, commandDisplayAll},
+ {"AT-", 1, commandSetByName},
+ {"AT", 1, commandAT},
+ {"RT", 0, sendRemoteCommand},
+};
+
+const int prefixCount = sizeof(prefixTable) / sizeof(prefixTable[0]);
+
+//----------------------------------------
+// Command processing routine
+//----------------------------------------
+
+//Check to see if a valid command has been received
+void checkCommand()
+{
+ char * commandString;
+ int index;
+ int prefixLength;
+ bool success;
+
+ //Verify the command length
+ success = false;
+ commandString = trimCommand(); //Remove any leading or trailing whitespace
+
+ //Upper case the command
+ for (index = 0; index < commandLength; index++)
+ commandString[index] = toupper(commandString[index]);
+
+ //Echo the command
+ systemPrintln(commandString);
+
+ //Verify the command length
+ if (commandLength >= 2)
+ {
+ //Locate the correct processing routine for the command prefix
+ for (index = 0; index < prefixCount; index++)
+ {
+ //Skip command types not supported in current mode
+ if ((!prefixTable[index].supportedInVcMode) && (settings.operatingMode != MODE_POINT_TO_POINT))
+ continue;
+
+ //Locate the prefix
+ prefixLength = strlen(prefixTable[index].prefix);
+ if (strncmp(commandString, prefixTable[index].prefix, prefixLength) != 0)
+ continue;
+
+ //Process the command
+ success = prefixTable[index].processCommand(commandString);
+ break;
+ }
+ }
+
+ //Print the command failure
+ petWDT();
+ if (success)
+ reportOK();
+ else
+ {
+ systemPrintln("ERROR");
+ commandComplete(false);
+ }
+ outputSerialData(true);
+ petWDT();
+
+ commandLength = 0; //Get ready for next command
+}
+
+//Indicate successful command completion
+void reportOK()
+{
+ systemPrintln("OK");
+ commandComplete(true);
+}
+
+//Notify the host that the command is complete
+void commandComplete(bool success)
+{
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ //Output the serial message header
+ systemWrite(START_OF_VC_SERIAL);
+ systemWrite(sizeof(VC_RADIO_MESSAGE_HEADER) + sizeof(VC_COMMAND_COMPLETE_MESSAGE));
+ systemWrite(PC_COMMAND_COMPLETE);
+ systemWrite(myVc);
+
+ //Output the command complete message
+ systemWrite(success ? VC_CMD_SUCCESS : VC_CMD_ERROR);
+ }
+}
+
+//Notify the host of the reset then reboot the system
+void commandReset()
+{
+ if (serialOperatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ //Notify the PC of the serial port failure
+ serialOutputByte(START_OF_VC_SERIAL);
+ serialOutputByte(3);
+ serialOutputByte(PC_SERIAL_RECONNECT);
+ serialOutputByte(myVc);
+ }
+ outputSerialData(true);
+ systemFlush();
+ systemReset();
+}
+
+//Remove any preceeding or following whitespace chars
+char * trimCommand()
+{
+ char * commandString = commandBuffer;
+
+ //Remove the leading white space
+ while (isspace(*commandString))
+ {
+ commandString++;
+ --commandLength;
+ }
+
+ //Zero terminate the string
+ commandString[commandLength] = 0;
+
+ //Remove the trailing white space
+ while (commandLength && isspace(commandString[commandLength - 1]))
+ commandString[--commandLength] = 0;
+
+ //Return the remainder as the command
+ return commandString;
+}
+
+//Display all of the commands
+bool commandDisplayAll(const char * commandString)
+{
+ displayParameters(0, false);
+ return true;
+}
+
+//Display only the debugging commands
+bool commandDisplayDebug(const char * commandString)
+{
+ displayParameters('D', false);
+ return true;
+}
+
+//Display only the trigger probe commands
+bool commandDisplayProbe(const char * commandString)
+{
+ displayParameters('P', false);
+ return true;
+}
+
+//Display only the radio commands
+bool commandDisplayRadio(const char * commandString)
+{
+ displayParameters('R', false);
+ return true;
+}
+
+//Display only the serial commands
+bool commandDisplaySerial(const char * commandString)
+{
+ displayParameters('S', false);
+ return true;
+}
+
+//Display only the virtual circuit commands
+bool commandDisplayVirtualCircuit(const char * commandString)
+{
+ displayParameters('V', false);
+ return true;
+}
+
+//----------------------------------------
+// Data validation routines
+//----------------------------------------
+
+//Validate a bandwidth value
+bool valBandwidth (void * value, uint32_t valMin, uint32_t valMax)
+{
+ double doubleSettingValue = *(double *)value;
+
+ UNUSED(valMin);
+ UNUSED(valMax);
+
+ //Some doubles get rounded incorrectly
+ return (((doubleSettingValue * 100) == 1040)
+ || (doubleSettingValue == 15.6)
+ || ((doubleSettingValue * 100) == 2080)
+ || (doubleSettingValue == 31.25)
+ || (doubleSettingValue == 41.7)
+ || (doubleSettingValue == 62.5)
+ || (doubleSettingValue == 125.0)
+ || (doubleSettingValue == 250.0)
+ || (doubleSettingValue == 500.0));
+}
+
+//Validate a maximum frequency value
+bool valFreqMax (void * value, uint32_t valMin, uint32_t valMax)
+{
+ double doubleSettingValue = *(double *)value;
+
+ UNUSED(valMin);
+
+ return ((doubleSettingValue >= settings.frequencyMin) && (doubleSettingValue <= (double)valMax));
+}
+
+//Validate a minimum frequency value
+bool valFreqMin (void * value, uint32_t valMin, uint32_t valMax)
+{
+ double doubleSettingValue = *(double *)value;
+
+ UNUSED(valMax);
+
+ return ((doubleSettingValue >= (double)valMin) && (doubleSettingValue <= settings.frequencyMax));
+}
+
+//Validate an integer value
+bool valInt (void * value, uint32_t valMin, uint32_t valMax)
+{
+ uint32_t settingValue = *(uint32_t *)value;
+
+ return ((settingValue >= valMin) && (settingValue <= valMax));
+}
+
+//Validate an encryption key value
+bool valKey (void * value, uint32_t valMin, uint32_t valMax)
+{
+ unsigned int length;
+ char * str = (char *)value;
+ char * strEnd;
+
+ UNUSED(valMin);
+ UNUSED(valMax);
+
+ //Validate the length of the encryption key
+ length = strlen(str);
+ if (length != (2 * sizeof(settings.encryptionKey)))
+ return false;
+
+ //Validate the characters in the encryption key
+ strEnd = &str[length];
+ if (strlen(str) == length)
+ {
+ while (str < strEnd)
+ {
+ if (charToHex(*str) < 0)
+ break;
+ str++;
+ }
+ if (str >= strEnd)
+ return true;
+ }
+ return false;
+}
+
+//Validate the server value
+bool valServer (void * value, uint32_t valMin, uint32_t valMax)
+{
+ uint32_t settingValue = *(uint32_t *)value;
+ bool valid;
+ int8_t vcIndex;
+
+ //Validate the value
+ valid = valInt(value, valMin, valMax);
+
+ //Check for a change from client to server
+ if (valid && (!settings.server) && settingValue)
+ {
+ //Clear the unique ID table in NVM
+ for (vcIndex = 1; vcIndex < MAX_VC; vcIndex++)
+ if (nvmIsVcUniqueIdSet(vcIndex))
+ nvmEraseUniqueId(vcIndex);
+
+ //Set our address as the server address
+ nvmSaveUniqueId(VC_SERVER, myUniqueId);
+ }
+ return valid;
+}
+
+//Validate the AirSpeed value
+bool valSpeedAir (void * value, uint32_t valMin, uint32_t valMax)
+{
+ bool valid;
+ uint32_t settingValue = *(uint32_t *)value;
+
+ UNUSED(valMin);
+ UNUSED(valMax);
+
+ valid = ((settingValue == 40)
+ || (settingValue == 150)
+ || (settingValue == 400)
+ || (settingValue == 1200)
+ || (settingValue == 2400)
+ || (settingValue == 4800)
+ || (settingValue == 9600)
+ || (settingValue == 19200)
+ || (settingValue == 28800)
+ || (settingValue == 38400));
+ if (valid)
+ {
+ //Adjust the settings to match the requested airSpeed
+ convertAirSpeedToSettings(&tempSettings, settingValue);
+ airSpeed = 0;
+ systemPrintln("Warning: AirSpeed overrides bandwidth, coding rate, spread factor,");
+ systemPrintln("heartbeatTimeout, and txToRxUsec");
+ }
+ return valid;
+}
+
+//Validate the SerialSpeed value
+bool valSpeedSerial (void * value, uint32_t valMin, uint32_t valMax)
+{
+ uint32_t settingValue = *(uint32_t *)value;
+
+ UNUSED(valMin);
+ UNUSED(valMax);
+
+ return ((settingValue == 2400)
+ || (settingValue == 4800)
+ || (settingValue == 9600)
+ || (settingValue == 14400)
+ || (settingValue == 19200)
+ || (settingValue == 38400)
+ || (settingValue == 57600)
+ || (settingValue == 115200));
+}
+
+//----------------------------------------
+// Command table
+//----------------------------------------
+
+const COMMAND_ENTRY commands[] =
+{
+ /*Debug parameters
+ Ltr, All, reset, min, max, digits, type, validation, name, setting addr, */
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "CopyDebug", &tempSettings.copyDebug},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "Debug", &tempSettings.debug},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugDatagrams", &tempSettings.debugDatagrams},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugHeartbeat", &tempSettings.debugHeartbeat},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugNvm", &tempSettings.debugNvm},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugRadio", &tempSettings.debugRadio},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugReceive", &tempSettings.debugReceive},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugSerial", &tempSettings.debugSerial},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugStates", &tempSettings.debugStates},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugSync", &tempSettings.debugSync},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugTraining", &tempSettings.debugTraining},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DebugTransmit", &tempSettings.debugTransmit},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "DisplayRealMillis", &tempSettings.displayRealMillis},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintAckNumbers", &tempSettings.printAckNumbers},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintChannel", &tempSettings.printChannel},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintFrequency", &tempSettings.printFrequency},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintLinkUpDown", &tempSettings.printLinkUpDown},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintPacketQuality", &tempSettings.printPacketQuality},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintPktData", &tempSettings.printPktData},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintRfData", &tempSettings.printRfData},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintTimestamp", &tempSettings.printTimestamp},
+ {'D', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "PrintTxErrors", &tempSettings.printTxErrors},
+
+ /*Radio parameters
+ Ltr, All, reset, min, max, digits, type, validation, name, setting addr */
+ {'R', 0, 1, 0, 0, 0, TYPE_SPEED_AIR, valSpeedAir, "AirSpeed", &airSpeed},
+ {'R', 0, 1, 0, 1, 0, TYPE_BOOL, valInt, "AutoTune", &tempSettings.autoTuneFrequency},
+ {'R', 0, 1, 0, 0, 2, TYPE_FLOAT, valBandwidth, "Bandwidth", &tempSettings.radioBandwidth},
+ {'R', 0, 1, 5, 8, 0, TYPE_U8, valInt, "CodingRate", &tempSettings.radioCodingRate},
+ {'R', 0, 1, 0, 1, 0, TYPE_BOOL, valInt, "FrequencyHop", &tempSettings.frequencyHop},
+ {'R', 0, 1, 0, 931, 3, TYPE_FLOAT, valFreqMax, "FrequencyMax", &tempSettings.frequencyMax},
+ {'R', 0, 1, 900, 0, 3, TYPE_FLOAT, valFreqMin, "FrequencyMin", &tempSettings.frequencyMin},
+ {'R', 0, 1, 10, 65535, 0, TYPE_U16, valInt, "MaxDwellTime", &tempSettings.maxDwellTime},
+ {'R', 0, 1, 1, 255, 0, TYPE_U8, valInt, "NumberOfChannels", &tempSettings.numberOfChannels},
+ {'R', 0, 1, 6, 65535, 0, TYPE_U16, valInt, "PreambleLength", &tempSettings.radioPreambleLength},
+ {'R', 0, 1, 6, 12, 0, TYPE_U8, valInt, "SpreadFactor", &tempSettings.radioSpreadFactor},
+ {'R', 0, 1, 0, 255, 0, TYPE_U8, valInt, "SyncWord", &tempSettings.radioSyncWord},
+ {'R', 0, 1, 14, 30, 0, TYPE_U8, valInt, "TxPower", &tempSettings.radioBroadcastPower_dbm},
+ {'R', 0, 1, 0, 999999, 0, TYPE_U32, valInt, "TxToRxUsec", &tempSettings.txToRxUsec},
+
+ /*Radio protocol parameters
+ Ltr, All, reset, min, max, digits, type, validation, name, setting addr */
+ {'R', 0, 1, 0, 1, 0, TYPE_BOOL, valInt, "DataScrambling", &tempSettings.dataScrambling},
+ {'R', 0, 1, 0, 1, 0, TYPE_BOOL, valInt, "EnableCRC16", &tempSettings.enableCRC16},
+ {'R', 0, 1, 0, 1, 0, TYPE_BOOL, valInt, "EncryptData", &tempSettings.encryptData},
+ {'R', 0, 1, 0, 0, 0, TYPE_KEY, valKey, "EncryptionKey", &tempSettings.encryptionKey},
+ {'R', 0, 0, 0, 255, 0, TYPE_U8, valInt, "FramesToYield", &tempSettings.framesToYield},
+ {'R', 0, 0, 250, 65535, 0, TYPE_U16, valInt, "HeartBeatTimeout", &tempSettings.heartbeatTimeout},
+ {'R', 0, 0, 0, 255, 0, TYPE_U8, valInt, "MaxResends", &tempSettings.maxResends},
+ {'R', 0, 1, 0, 255, 0, TYPE_U8, valInt, "NetID", &tempSettings.netID},
+ {'R', 0, 1, 0, 2, 0, TYPE_U8, valInt, "OperatingMode", &tempSettings.operatingMode},
+ {'R', 0, 1, 0, 1000, 0, TYPE_U16, valInt, "OverHeadtime", &tempSettings.overheadTime},
+ {'R', 1, 0, 0, 255, 0, TYPE_U8, valInt, "SelectLedUse", &tempSettings.selectLedUse},
+ {'R', 0, 0, 0, 1, 0, TYPE_BOOL, valServer, "Server", &tempSettings.server},
+ {'R', 0, 1, 0, 1, 0, TYPE_BOOL, valInt, "VerifyRxNetID", &tempSettings.verifyRxNetID},
+
+ /*Serial parameters
+ Ltr, All, reset, min, max, digits, type, validation, name, setting addr */
+ {'S', 0, 0, 0, 1, 0, TYPE_BOOL, valInt, "CopySerial", &tempSettings.copySerial},
+ {'S', 0, 0, 0, 1, 0, TYPE_BOOL, valInt, "Echo", &tempSettings.echo},
+ {'S', 0, 0, 0, 1, 0, TYPE_BOOL, valInt, "FlowControl", &tempSettings.flowControl},
+ {'S', 0, 0, 0, 1, 0, TYPE_BOOL, valInt, "InvertCts", &tempSettings.invertCts},
+ {'S', 0, 0, 0, 1, 0, TYPE_BOOL, valInt, "InvertRts", &tempSettings.invertRts},
+ {'S', 0, 0, 10, 2000, 0, TYPE_U16, valInt, "SerialDelay", &tempSettings.serialTimeoutBeforeSendingFrame_ms},
+ {'S', 0, 0, 0, 0, 0, TYPE_SPEED_SERIAL, valSpeedSerial, "SerialSpeed", &tempSettings.serialSpeed},
+ {'S', 0, 0, 0, 1, 0, TYPE_BOOL, valInt, "UsbSerialWait", &tempSettings.usbSerialWait},
+
+ /*Training parameters
+ Ltr, All, reset, min, max, digits, type, validation, name, setting addr */
+ {'R', 0, 1, 1, 255, 0, TYPE_U8, valInt, "ClientFindPartnerRetryInterval", &tempSettings.clientFindPartnerRetryInterval},
+ {'R', 0, 0, 0, 0, 0, TYPE_KEY, valKey, "TrainingKey", &tempSettings.trainingKey},
+ {'R', 0, 0, 1, 255, 0, TYPE_U8, valInt, "TrainingTimeout", &tempSettings.trainingTimeout},
+
+ /*Trigger parameters
+ Ltr, All, reset, min, max, digits, type, validation, name, setting addr */
+ {'P', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "CopyTriggers", &tempSettings.copyTriggers},
+ {'P', 1, 0, 0, 0xffffffff, 0, TYPE_U32, valInt, "TriggerEnable_31-0", &tempSettings.triggerEnable},
+ {'P', 1, 0, 0, 0xffffffff, 0, TYPE_U32, valInt, "TriggerEnable_63-32", &tempSettings.triggerEnable2},
+ {'P', 1, 0, 1, 255, 0, TYPE_U8, valInt, "TriggerWidth", &tempSettings.triggerWidth},
+ {'P', 1, 0, 0, 1, 0, TYPE_BOOL, valInt, "TriggerWidthIsMultiplier", &tempSettings.triggerWidthIsMultiplier},
+
+ /*Virtual circuit parameters
+ Ltr, All, reset, min, max, digits, type, validation, name, setting addr */
+ {'V', 0, 0, 0, MAX_VC - 1, 0, TYPE_U8, valInt, "CmdVC", &cmdVc},
+};
+
+const int commandCount = sizeof(commands) / sizeof(commands[0]);
+
+//----------------------------------------
+// ATSxx routines
+//----------------------------------------
+
+//Display a command
+void commandDisplay(const COMMAND_ENTRY * command)
+{
+ //Print the setting value
+ switch (command->type)
+ {
+ case TYPE_BOOL:
+ systemPrint((uint8_t)(*(bool *)(command->setting)));
+ break;
+ case TYPE_FLOAT:
+ systemPrint(*((float *)(command->setting)), command->digits);
+ break;
+ case TYPE_KEY:
+ displayEncryptionKey((uint8_t *)(command->setting));
+ break;
+ case TYPE_U8:
+ systemPrint(*(uint8_t *)(command->setting));
+ break;
+ case TYPE_U16:
+ systemPrint(*(uint16_t *)(command->setting));
+ break;
+ case TYPE_SPEED_AIR:
+ case TYPE_SPEED_SERIAL:
+ case TYPE_U32:
+ systemPrint(*(uint32_t *)(command->setting));
+ break;
+ }
+ systemPrintln();
+}
+
+//Set or display the parameter by name
+bool commandSetByName(const char * commandString)
+{
+ const char * buffer;
+ const COMMAND_ENTRY * command;
+ int index;
+ int nameLength;
+ int number;
+ const char * param;
+ int paramLength;
+ int table;
+
+ //Determine the parameter name length
+ param = &commandString[3];
+ buffer = param;
+ paramLength = 0;
+ while (*buffer && (*buffer != '=') && (*buffer != '?'))
+ {
+ buffer++;
+ paramLength += 1;
+ }
+
+ command = NULL;
+ for (index = 0; index < commandCount; index++)
+ {
+ nameLength = strlen(commands[index].name);
+ if (nameLength == paramLength)
+ {
+ //Compare the parameter names
+ if (strnicmp(param, commands[index].name, nameLength) == 0)
+ {
+ command = &commands[index];
+ break;
+ }
+ }
+ }
+
+ //Verify that the parameter was found
+ if (!command)
+ //Report the error
+ return false;
+
+ //Process this command
+ return commandSetOrDisplayValue(command, buffer);
+}
+
+//Set or display the command
+bool commandSetOrDisplayValue(const COMMAND_ENTRY * command, const char * buffer)
+{
+ const char * digit;
+ double doubleSettingValue;
+ uint32_t settingValue;
+ bool valid;
+
+ do {
+ //Is this a display request
+ if ((*buffer == 0) || (strcmp(buffer, "?") == 0))
+ {
+ commandDisplay(command);
+ return true;
+ }
+
+ //Make sure the command has the proper syntax
+ if (*buffer++ != '=')
+ break;
+
+ //Verify the input value
+ for (digit = buffer; *digit != 0; digit++)
+ if ((*digit < '0') || (*digit > '9'))
+ {
+ //Floating point values may contain a decimal point
+ if ((command->type == TYPE_FLOAT) && (*digit == '.'))
+ continue;
+
+ //Hexadecimal values may contain A through F
+ if ((toupper(*digit) >= 'A') && (toupper(*digit) <= 'F')
+ && (command->type == TYPE_KEY))
+ continue;
+ break;
+ }
+ if (*digit)
+ break;
+
+ //Get the value
+ doubleSettingValue = strtod(buffer, NULL);
+ settingValue = doubleSettingValue;
+
+ //Validate and set the value
+ valid = false;
+ switch (command->type)
+ {
+ case TYPE_BOOL:
+ valid = command->validate((void *)&settingValue, command->minValue, command->maxValue);
+ if (valid)
+ *(bool *)(command->setting) = (bool)settingValue;
+ break;
+ case TYPE_FLOAT:
+ valid = command->validate((void *)&doubleSettingValue, command->minValue, command->maxValue);
+ if (valid)
+ *((float *)(command->setting)) = doubleSettingValue;
+ break;
+ case TYPE_KEY:
+ valid = command->validate((void *)buffer, command->minValue, command->maxValue);
+ if (valid)
+ for (uint32_t x = 0; x < (2 * AES_KEY_BYTES); x += 2)
+ ((uint8_t *)command->setting)[x / 2] = charHexToDec(buffer[x], buffer[x + 1]);
+ break;
+ case TYPE_SPEED_AIR:
+ case TYPE_SPEED_SERIAL:
+ case TYPE_U32:
+ valid = command->validate((void *)&settingValue, command->minValue, command->maxValue);
+ if (valid)
+ *(uint32_t *)(command->setting) = settingValue;
+ break;
+ case TYPE_U8:
+ valid = command->validate((void *)&settingValue, command->minValue, command->maxValue);
+ if (valid)
+ *(uint8_t *)(command->setting) = (uint8_t)settingValue;
+ break;
+ case TYPE_U16:
+ valid = command->validate((void *)&settingValue, command->minValue, command->maxValue);
+ if (valid)
+ *(uint16_t *)(command->setting) = (uint16_t)settingValue;
+ break;
+ }
+ if (valid == false)
+ break;
+
+ //See if this command requires a radio reset to be apply
+ if (valid && command->forceRadioReset)
+ forceRadioReset = true;
+
+ //The parameter was successfully set
+ return true;
+ } while (0);
+
+ //Report the error
+ return false;
+}
+
+//Display the encryption key
+void displayEncryptionKey(uint8_t * key)
+{
+ for (uint8_t index = 0 ; index < sizeof(settings.encryptionKey) ; index++)
+ systemPrint(key[index], HEX);
+}
+
+//Show current settings in user friendly way
+void displayParameters(char letter, bool displayAll)
+{
+ int index;
+ uint8_t sortOrder[commandCount];
+ uint8_t temp;
+ int x;
+
+ //Set the default sort order
+ for (index = 0; index < commandCount; index++)
+ sortOrder[index] = index;
+
+ //Perform a bubble sort if requested
+ for (index = 0; index < commandCount; index++)
+ for (x = index + 1; x < commandCount; x++)
+ if (stricmp(commands[sortOrder[index]].name, commands[sortOrder[x]].name) > 0)
+ {
+ temp = sortOrder[index];
+ sortOrder[index] = sortOrder[x];
+ sortOrder[x] = temp;
+ }
+
+ //Print the parameters
+ for (index = 0; index < commandCount; index++)
+ {
+ if (displayAll || (letter == commands[sortOrder[index]].letter)
+ || ((letter == 0) && (!commands[sortOrder[index]].requireAll)))
+ {
+ petWDT(); //Printing may take longer than WDT at 9600, so pet the WDT.
+
+ if (inCommandMode && (printerEndpoint == PRINT_TO_RF))
+ systemPrint("R"); //If someone is asking for our settings over RF, respond with 'R' style settings
+ else
+ systemPrint("A");
+
+ systemPrint("T-");
+ systemPrint(commands[sortOrder[index]].name);
+ systemPrint("=");
+ commandDisplay(&commands[sortOrder[index]]);
+ }
+ }
+}
diff --git a/Firmware/LoRaSerial/LoRaSerial.ino b/Firmware/LoRaSerial/LoRaSerial.ino
new file mode 100644
index 00000000..f907dc65
--- /dev/null
+++ b/Firmware/LoRaSerial/LoRaSerial.ino
@@ -0,0 +1,667 @@
+/*
+ December 15th, 2021
+ SparkFun Electronics
+ Nathan Seidle
+
+ This firmware runs the core of the SparkFun LoRaSerial Radio product.
+ Primarily designed to run on a ATSAMD21G18A with the ebyte 1W LoRa Radio based on the SX1276.
+
+ This radio is designed to operate at the physical layer of LoRa sending data directly to an end point
+ as opposed to something like LoRaWAN that operates on the data and network layers. For this reason
+ LoRaSerial is not intended to operate on LoRaWAN.
+
+ The system requests an ACK for certain packet types.
+
+ Each packet contains data plus a NetID (byte) and Control byte.
+ For transmissions at SpreadFactor 6 the packet length is set to 250 bytes and an additional byte is
+ transmitted before NetID that repsents the actual data length within the packet.
+
+ The max packet size for the SX127x is 255 bytes. With the NetID and control bytes removed, we have
+ 253 bytes available for data (252 when spread factor is 6).
+
+ The AT command structure is based on the SiK Ardupilot radio.
+
+ For a graphical view of the system state machine see: https://lucid.app/lucidchart/7293b4a6-690a-493e-a3f6-92bf47025fb1/edit?invitationId=inv_9476a070-5ba9-40e6-b89f-9c0d22af9855
+
+ Build notes:
+ RadioLib should have RADIOLIB_FIX_ERRATA_SX127X turned on (uncommented)
+
+ Processors supported:
+ SAMD21
+ ESP32
+
+ For other processors the following unique features must be considered:
+ Interrupt capable pins for DIO0/1
+ Processor reset (command ATZ)
+ EEPROM read/write/commit
+ ~14k RAM for serial RX/TX and radio buffers
+
+ Compiled with Arduino v1.8.15
+*/
+
+const int FIRMWARE_VERSION_MAJOR = 2;
+const int FIRMWARE_VERSION_MINOR = 0;
+
+#define RADIOLIB_LOW_LEVEL //Enable access to the module functions
+//#define ENABLE_DEVELOPER true //Uncomment this line to enable special developer modes
+
+#define UNUSED(x) (void)(x)
+
+//Define the LoRaSerial board identifier:
+// This is an int which is unique to this variant of the LoRaSerial hardware which allows us
+// to make sure that the settings in EEPROM are correct for this version of the LoRaSerial
+// (sizeOfSettings is not necessarily unique and we want to avoid problems when swapping from one variant to another)
+// It is the sum of:
+// the major firmware version * 0x10
+// the minor firmware version
+#define LRS_IDENTIFIER (FIRMWARE_VERSION_MAJOR * 0x10 + FIRMWARE_VERSION_MINOR)
+
+#define CHANNEL_TIMER_BYTES sizeof(uint16_t) //Number of bytes used within in control header for clock sync (uint16_t msToNextHop)
+#define CLOCK_MILLIS_BYTES sizeof(unsigned long) //Number of bytes used within in various packets for system timestamps sync (unsigned long currentMillis)
+#define MAX_PACKET_SIZE 255 //Limited by SX127x
+#define AES_IV_BYTES 12 //Number of bytes for AESiv
+#define AES_KEY_BYTES 16 //Number of bytes in the encryption key
+#define UNIQUE_ID_BYTES 16 //Number of bytes in the unique ID
+
+//Frame lengths
+#define MP_HEARTBEAT_BYTES 1 //Number of data bytes in the MP_HEARTBEAT frame
+#define P2P_FIND_PARTNER_BYTES sizeof(unsigned long) //Number of data bytes in the FIND_PARTNER frame
+#define P2P_SYNC_CLOCKS_BYTES (sizeof(uint8_t) + sizeof(unsigned long)) //Number of data bytes in the SYNC_CLOCKS frame
+#define P2P_ZERO_ACKS_BYTES sizeof(unsigned long) //Number of data bytes in the ZERO_ACKS frame
+#define P2P_HEARTBEAT_BYTES sizeof(unsigned long) //Number of data bytes in the HEARTBEAT frame
+#define P2P_ACK_BYTES sizeof(unsigned long) //Number of data bytes in the ACK frame
+#define VC_HEARTBEAT_BYTES 1 + 1 + 1 + 16 + 4 //Number of data bytes in the VC_HEARTBEAT frame
+
+//Bit 0: Signal Detected indicates that a valid LoRa preamble has been detected
+//Bit 1: Signal Synchronized indicates that the end of Preamble has been detected, the modem is in lock
+//Bit 3: Header Info Valid toggles high when a valid Header (with correct CRC) is detected
+#define RECEIVE_IN_PROCESS_MASK 0b1011
+
+//Always define ENABLE_DEVELOPER to enable its use in conditional statements
+#ifndef ENABLE_DEVELOPER
+#define ENABLE_DEVELOPER false
+#endif //ENABLE_DEVELOPER
+
+#include "settings.h"
+
+//Hardware connections
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//These pins are set in beginBoard()
+#define PIN_UNDEFINED 255
+
+uint8_t pin_rst = PIN_UNDEFINED;
+uint8_t pin_cs = PIN_UNDEFINED;
+uint8_t pin_txen = PIN_UNDEFINED;
+uint8_t pin_rxen = PIN_UNDEFINED;
+uint8_t pin_dio0 = PIN_UNDEFINED;
+uint8_t pin_dio1 = PIN_UNDEFINED;
+uint8_t pin_rts = PIN_UNDEFINED;
+uint8_t pin_cts = PIN_UNDEFINED;
+uint8_t pin_blue_LED = PIN_UNDEFINED;
+uint8_t pin_yellow_LED = PIN_UNDEFINED;
+uint8_t pin_trainButton = PIN_UNDEFINED;
+uint8_t pin_green_1_LED = PIN_UNDEFINED;
+uint8_t pin_green_2_LED = PIN_UNDEFINED;
+uint8_t pin_green_3_LED = PIN_UNDEFINED;
+uint8_t pin_green_4_LED = PIN_UNDEFINED;
+uint8_t pin_boardID = PIN_UNDEFINED;
+
+uint8_t pin_trigger = PIN_UNDEFINED;
+uint8_t pin_hop_timer = PIN_UNDEFINED;
+
+/*
+ Antenna Qwiic
+ +---------------------------+
+ | |
+ | G4 G3 G2 G1 |
+ | |
+ | |
+ | Red |
+ | |
+ | |
+ | Blue Yellow |
+ | |
+ +---------------------------+
+ USB Serial
+*/
+
+#define GREEN_LED_1 pin_green_1_LED //Top right
+#define GREEN_LED_2 pin_green_2_LED
+#define GREEN_LED_3 pin_green_3_LED
+#define GREEN_LED_4 pin_green_4_LED //Top left
+#define BLUE_LED pin_blue_LED
+#define YELLOW_LED pin_yellow_LED //Bottom right
+
+#define RADIO_USE_BLINK_MILLIS 15
+
+#define LED_ON HIGH
+#define LED_OFF LOW
+
+#define LED_MAX_PULSE_WIDTH 24 //mSec
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Radio Library
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+#include //Click here to get the library: http://librarymanager/All#RadioLib v5.6.0
+SX1276 radio = NULL; //We can't instantiate here because we don't yet know what pin numbers to use
+
+float *channels;
+uint8_t channelNumber = 0;
+uint32_t airSpeed;
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Encryption
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+#include //From: https://github.com/rweather/arduinolibs
+#include
+#include
+GCM gcm;
+
+uint8_t AESiv[AES_IV_BYTES] = {0}; //Set during hop table generation
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Buttons - Interrupt driven and debounce
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+#include // http://librarymanager/All#JC_Button //v2.1.2
+Button *trainBtn = NULL; //We can't instantiate the button here because we don't yet know what pin number to use
+
+const int trainButtonClientTime = 4 * 1000; //ms press and hold before entering client training
+const int trainButtonServerTime = 8 * 1000; //ms press and hold before entering server training
+const int trainButtonFactoryResetTime = 16 * 1000; //ms press and hold before reset
+
+bool inTraining; //True if training is in process
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Hardware Timers
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+#include "SAMDTimerInterrupt.h" //http://librarymanager/All#SAMD_TimerInterrupt v1.10.1 by Koi Hang
+SAMDTimer channelTimer(TIMER_TCC); //Available: TC3, TC4, TC5, TCC, TCC1 or TCC2
+volatile uint16_t channelTimerMsec; //Last value programmed into the channel timer
+volatile unsigned long channelTimerStart = 0; //Tracks how long our timer has been running since last hop
+volatile bool timeToHop = false; //Set by channelTimerHandler to indicate that hopChannel needs to be called
+volatile bool reloadChannelTimer = false; //When set channel timer interval needs to be reloaded with settings.maxDwellTime
+
+uint16_t petTimeout = 0; //A reduced amount of time before WDT triggers. Helps reduce amount of time spent petting.
+unsigned long lastPet = 0; //Remebers time of last WDT pet.
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Global variables - Serial
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+const uint8_t escapeCharacter = '+';
+const uint8_t maxEscapeCharacters = 3; //Number of characters needed to enter command mode
+const uint8_t responseDelayDivisor = 4; //Add on to max response time after packet has been sent. Factor of 2. 8 is ok. 4 is good. A smaller number increases the delay.
+
+//Buffer to receive serial data from the USB or serial ports
+uint16_t rxHead = 0;
+uint16_t rxTail = 0;
+uint8_t serialReceiveBuffer[1024];
+
+//Buffer to store bytes for transmission via the long range radio
+uint16_t radioTxHead = 0;
+uint16_t radioTxTail = 0;
+uint8_t radioTxBuffer[1024 * 3];
+
+//Buffer to store bytes to be sent to the USB or serial ports
+uint16_t txHead = 0;
+uint16_t txTail = 0;
+uint8_t serialTransmitBuffer[1024 * 4]; //Bytes received from RF waiting to be printed out UART. Buffer up to 1s of bytes at 4k
+
+unsigned long lastByteReceived_ms = 0; //Track when last transmission was. Send partial buffer once time has expired.
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Global variables - Command Processing
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+char commandBuffer[100]; //Received serial gets stored into buffer until \r or \n is received
+uint8_t commandRXBuffer[100]; //Bytes received from remote, waiting for printing or AT parsing
+uint8_t commandTXBuffer[1024 * 4]; //Bytes waiting to be transmitted to the remote unit
+uint16_t commandTXHead = 0;
+uint16_t commandTXTail = 0;
+uint16_t commandRXHead = 0;
+uint16_t commandRXTail = 0;
+
+uint8_t escapeCharsReceived = 0; //Used to enter command mode
+unsigned long lastEscapeReceived_ms = 0; //Tracks end of serial traffic
+const long minEscapeTime_ms = 2000; //Serial traffic must stop this amount before an escape char is recognized
+
+bool inCommandMode = false; //Normal data is prevented from entering serial output when in command mode
+uint8_t commandLength = 0;
+bool remoteCommandResponse;
+
+bool rtsAsserted; //When RTS is asserted, host says it's ok to send data
+bool forceRadioReset = false; //Goes true when a setting requires a link/radio reset to work
+bool writeOnCommandExit = false; //Goes true if user specifies ATW command
+
+/* Data Flow - Point-to-Point and Multi-Point
+
+ USB or UART
+ |
+ | Flow control: RTS for UART
+ | Off: Buffer full
+ | On: Buffer drops below half full
+ | updateSerial
+ V
+ serialReceiveBuffer
+ |
+ | processSerialInput
+ |
+ | inCommandMode or local VC command?
+ |
+ true V false
+ .-------------+--------------------------.
+ | |
+ V v
+ commandBuffer radioTxBuffer
+ | |
+ | Remote Command? v
+ | outgoingPacket
+ false V true |
+ .-------------+-------------. V
+ | | Send to remote system
+ | V |
+ | outgoingPacket V
+ | | incomingBuffer
+ | V |
+ | Send to remote system |
+ | | |
+ | V |
+ | incomingBuffer |
+ | | |
+ | V |
+ | commandRXBuffer |
+ | | |
+ | V VC Remote Cmd V
+ | commandBuffer <------------------+
+ | | |
+ | V |
+ | Command processing |
+ | checkCommand | Data or
+ | | | VC Data or
+ | V | VC Rmt Cmd Resp
+ | commandTXBuffer |
+ | | |
+ | V |
+ | outgoingPacket |
+ | | |
+ | V |
+ | Send back to local system |
+ | | |
+ | V |
+ | incomingBuffer |
+ | | |
+ | V |
+ `-------------------------->+<-------------------------'
+ |
+ |
+ V
+ serialTransmitBuffer
+ |
+ |
+ V
+ USB or UART
+
+*/
+
+/* Data Flow - Virtual Circuit
+
+ USB or UART
+ |
+ | Flow control: RTS for UART
+ | Off: Buffer full
+ | On: Buffer drops below half full
+ | updateSerial
+ V
+ serialReceiveBuffer
+ |
+ | vcProcessSerialInput
+ |
+ | Destination VC?
+ V Other
+ .-------------+--------------->+---------------->+------> Discard
+ VC_COMMAND | myVc | >= 0 |
+ | | VC_BROADCAST |
+ | | |
+ V | v
+ commandBuffer | radioTxBuffer
+ | | |
+ | Remote Command? | v
+ | | outgoingPacket
+ false V true | |
+ .-------------+-------------. | V
+ | | | Send to remote system
+ | V | |
+ | outgoingPacket | V
+ | | | incomingBuffer
+ | V | |
+ | Send to remote system | |
+ | | | |
+ | V | |
+ | incomingBuffer | |
+ | | | |
+ | V | |
+ | commandRXBuffer | |
+ | | | |
+ | V | |
+ | Command processing | |
+ | checkCommand | |
+ | | | |
+ | V | |
+ | commandTXBuffer | |
+ | | | |
+ | V | |
+ | outgoingPacket | |
+ | | | |
+ | V | |
+ | Send back to local system | |
+ | | | |
+ | V | |
+ | incomingBuffer | |
+ | | | |
+ | V V |
+ `-------------------------->+<---------------+<----------------'
+ |
+ V
+ serialTransmitBuffer
+ |
+ | Flow control: CTS for UART
+ |
+ V
+ USB or UART
+
+*/
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Global variables - LEDs
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+uint8_t cylonLedPattern = 0b0001;
+bool cylonPatternGoingLeft;
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Global variables - Radio (General)
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+uint16_t radioBand = 0; //In MHz. Detected radio module type. Sets the upper/lower frequency bounds.
+uint8_t outgoingPacket[MAX_PACKET_SIZE]; //Contains the current data in route to receiver
+uint32_t frameAirTimeUsec; //Recalc'd with each new packet transmission
+uint8_t frameSentCount = 0; //Increases each time a frame is sent
+
+unsigned long lastPacketReceived = 0; //Controls link LED in broadcast mode
+unsigned long lastLinkBlink = 0; //Controls link LED in broadcast mode
+
+volatile uint16_t irqFlags; //IRQ Flags register value
+volatile bool transactionComplete = false; //Used in dio0ISR
+uint8_t sf6ExpectedSize = MAX_PACKET_SIZE; //Used during SF6 operation to reduce packet size when needed
+
+float radioFrequency; //Current radio frequency
+float frequencyCorrection = 0; //Adjust receive freq based on the last packet received freqError
+
+volatile bool hop = true; //Clear the DIO1 hop ISR when possible
+
+int rssi; //Average signal level, measured during reception of a packet
+
+//Link quality metrics
+uint32_t datagramsSent; //Total number of datagrams sent
+uint32_t datagramsReceived; //Total number of datagrams received
+uint32_t framesSent; //Total number of frames sent
+uint32_t framesReceived; //Total number of frames received
+uint32_t badFrames; //Total number of bad frames received
+uint32_t duplicateFrames; //Total number of duplicate frames received
+uint32_t lostFrames; //Total number of lost TX frames
+uint32_t linkFailures; //Total number of link failures
+uint32_t insufficientSpace; //Total number of times the buffer did not have enough space
+uint32_t badCrc; //Total number of bad CRC frames
+uint32_t netIdMismatch; //Total number of mismatched Net ID frames
+
+unsigned long lastLinkUpTime = 0; //Mark when link was first established
+unsigned long lastRxDatagram; //Remember last valid receive
+
+//Receiver and Transmitter status
+unsigned long rxSuccessMillis;
+unsigned long rxFailureMillis;
+int rxFailureState;
+
+//Receive failures
+unsigned long startReceiveFailureMillis;
+int startReceiveFailureState;
+unsigned long lastReceiveInProcessTrue;
+uint8_t lastModemStatus;
+
+unsigned long txSuccessMillis;
+unsigned long txFailureMillis;
+int txFailureState;
+
+//History
+unsigned long radioCallHistory[RADIO_CALL_MAX];
+unsigned long radioStateHistory[RADIO_MAX_STATE];
+
+uint8_t packetLength = 0; //Total bytes received, used for calculating clock sync times in multi-point mode
+int16_t msToNextHopRemote; //Can become negative
+uint8_t clockSyncIndex;
+CLOCK_SYNC_DATA clockSyncData[16];
+
+bool requestYield = false; //Datagram sender can tell this radio to stop transmitting to enable two-way comm
+unsigned long yieldTimerStart = 0;
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Global variables - Radio Protocol
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Frame size values
+uint8_t headerBytes;
+uint8_t trailerBytes;
+uint8_t txDatagramSize;
+
+//Point-to-Point
+unsigned long datagramTimer;
+uint16_t randomTime;
+uint16_t heartbeatRandomTime;
+
+//Receive control
+uint8_t incomingBuffer[MAX_PACKET_SIZE];
+uint8_t minDatagramSize;
+uint8_t maxDatagramSize;
+uint8_t * rxData;
+uint8_t rxDataBytes;
+unsigned long heartbeatTimer;
+unsigned long linkDownTimer;
+
+//Clock synchronization
+unsigned long rcvTimeMillis;
+unsigned long xmitTimeMillis;
+long timestampOffset;
+
+//Transmit control
+uint8_t * endOfTxData;
+CONTROL_U8 txControl;
+unsigned long ackTimer;
+
+//Retransmit support
+uint8_t rmtCmdVc;
+uint8_t rexmtBuffer[MAX_PACKET_SIZE];
+CONTROL_U8 rexmtControl;
+uint8_t rexmtLength;
+uint8_t rexmtFrameSentCount;
+uint8_t rexmtTxDestVc;
+
+//Multi-point Training
+bool trainingServerRunning; //Training server is running
+bool trainingPreviousRxInProgress = false; //Previous RX status
+float originalChannel; //Original channel from HOP table while training is in progress
+uint8_t trainingPartnerID[UNIQUE_ID_BYTES]; //Unique ID of the training partner
+uint8_t myUniqueId[UNIQUE_ID_BYTES]; // Unique ID of this system
+
+//Virtual-Circuit
+int8_t cmdVc; //VC index for ATI commands only
+int8_t myVc;
+int8_t rxDestVc;
+int8_t rxSrcVc;
+uint8_t *rxVcData;
+int8_t txDestVc;
+VIRTUAL_CIRCUIT virtualCircuitList[MAX_VC];
+uint8_t serialOperatingMode;
+uint32_t vcConnecting;
+
+unsigned int multipointChannelLoops = 0; //Count the number of times Multipoint scanning has traversed the table
+
+unsigned long retransmitTimeout = 0; //Throttle back re-transmits
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Global variables
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+const Settings defaultSettings;
+Settings settings; //Active settings used by the radio
+Settings tempSettings; //Temporary settings used for command processing
+Settings trainingSettings; //Settings used for training other radios
+
+char platformPrefix[25]; //Used for printing platform specific device name, ie "SAMD21 1W 915MHz"
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+/*
+ Clock Sync Transmitter Clock Sync Receiver
+
+ HEARTBEAT send needed
+ call xmitDatagramP2PHeartbeat
+ .-------------------- Get millis()
+ | Add millis to HEARTBEAT frame
+ | * USB Interrupt
+ | * hopChannel if necessary
+ | Software CRC
+ | txTimeUsec Data encryption
+ | Data whitening
+ | Move data to radio via SPI
+ | xmitTimeMillis = millis()
+ | * Radio arbitrary delay
+ | TX HEARTBEAT - - > Detect RX in process
+ | ... ...
+ | TX done RX HEARTBEAT
+ | * Radio arbitrary delay Radio arbitrary delay *
+ '--- Transaction complete detected USB Interrupt *
+ .------- DIO0 Interrupt
+ | Delay - finish previous loop
+ rxTimeUsec | Transaction complete detected
+ | call receiveDatagram
+ | USB Interrupt
+ +------- Get millis()
+ Move data from radio using SPI
+ Data whitening
+ Data decryption
+ Software CRC
+ Start processing HEARTBEAT datagram
+ Get millis();
+
+ CPU Clock drift
+
+ timeStampOffset = TX millis + txTimeUsec + rxTimeUsec
+
+ RX uSec RX Var TX uSec Hop uSec
+ None 1379 216 1970 22
+ Encryption 1957 155 2540 13
+ CRC 1387 178 1986 5
+ CRC + Encryption 1960 223 2557 15
+ Whitening 1393 231 1993 28
+ Whitening + Encryption 1963 263 2562 22
+ Whitening + CRC 1415 249 2014 13
+ Whitening + CRC + Encryption 1987 220 2584 27
+
+ Options RX TX
+ CRC: 8 16 uSec
+ Encryption: 578 570 uSec
+ CRC + Encr: 581 587 uSec
+ Whitening 14 15 uSec
+ White + Enc: 584 592 uSec
+ White + CRC: 36 44 uSec
+ Wh + CRC + En: 608 614 uSec
+
+*/
+
+//Clock synchronization
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+bool clockSyncReceiver; //Receives and processes the clock synchronization
+bool startChannelTimerPending; //When true, call startChannelTimer in transactionCompleteISR
+
+//TX time measurements
+uint32_t txSetChannelTimerMicros; //Timestamp when millis is read in TX routine to set channel timer value
+uint32_t transactionCompleteMicros; //Timestamp at the beginning of the transactionCompleteIsr routine
+uint32_t txDataAckUsec; //Time in microseconds to transmit the DATA_ACK frame
+uint32_t txFindPartnerUsec; //Time in microseconds to transmit the FIND_PARTNER frame
+uint32_t txHeartbeatUsec; //Time in microseconds to transmit the HEARTBEAT frame
+uint32_t txSyncClocksUsec; //Time in microseconds to transmit the SYNC_CLOCKS frame
+uint32_t txDatagramMicros; //Timestamp at the beginning of the transmitDatagram routine
+uint32_t maxFrameAirTimeMsec; //Air time of the maximum sized message
+unsigned long remoteSystemMillis; //Millis value contained in the received message
+
+#define VC_DELAY_HEARTBEAT_MSEC 5
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Architecture variables
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+void updateRTS(bool assertRTS);
+
+#include "Arch_ESP32.h"
+#include "Arch_SAMD.h"
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Initial entrypoint following any runtime library initialization
+void setup()
+{
+ int index;
+
+ beginSerial(57600); //Default for debug messages before board begins
+
+ arch.beginBoard(); //Initialize the board specific hardware, and ID platform type
+
+ loadSettings(); //Load settings from EEPROM
+ serialOperatingMode = settings.operatingMode;
+
+ beginSerial(settings.serialSpeed);
+
+ verifyTables(); //Verify that the enum counts match the name table lengths
+
+ //Load the unique IDs for the virtual circuits
+ //Always hand out the same VC number for a given unique ID
+ if (settings.server)
+ {
+ for (index = 0; index < MAX_VC; index++)
+ nvmLoadVcUniqueId(index);
+ }
+
+ arch.uniqueID(myUniqueId); //Get the unique ID
+
+ beginLoRa(); //Start radio
+
+ beginButton(); //Start watching the train button
+
+ beginChannelTimer(); //Setup (but do not start) hardware timer for channel hopping
+
+ arch.beginWDT(); //Start watchdog timer
+
+ updateRTS(true); //Enable serial input
+
+ systemPrintTimestamp();
+ systemPrintln("LRS");
+ outputSerialData(true);
+
+ triggerEvent(TRIGGER_RADIO_RESET);
+
+ blinkStartup(); //Blink LEDs to indicate the completion of system setup
+}
+
+//Idle loop for the CPU
+void loop()
+{
+ petWDT();
+
+ updateButton(); //Check if train button is pressed
+
+ updateSerial(); //Store incoming and print outgoing
+
+ updateRadioState(); //Send packets as needed for handshake, data, remote commands
+
+ updateLeds(); //Update the LEDs on the board
+
+ updateHopISR(); //Clear hop ISR as needed
+}
diff --git a/Firmware/LoRaSerial/NVM.ino b/Firmware/LoRaSerial/NVM.ino
new file mode 100644
index 00000000..5eb7e703
--- /dev/null
+++ b/Firmware/LoRaSerial/NVM.ino
@@ -0,0 +1,226 @@
+//Read the settings from NVM into the settings structure
+void loadSettings()
+{
+ arch.eepromBegin();
+
+ //Check to see if EEPROM is blank
+ uint32_t testRead = 0;
+ if (EEPROM.get(0, testRead) == 0xFFFFFFFF)
+ {
+ if (settings.debugNvm)
+ {
+ systemPrintln("EEPROM is blank.");
+ outputSerialData(true);
+ }
+ recordSystemSettings(); //Record default settings to EEPROM. At power on, settings are in default state
+ }
+
+ //Check that the current settings struct size matches what is stored in EEPROM
+ //Misalignment happens when we add a new feature or setting
+ uint16_t tempSize = 0;
+ EEPROM.get(0, tempSize); //Load the sizeOfSettings
+ if (tempSize != sizeof(Settings))
+ {
+ if (settings.debugNvm)
+ {
+ systemPrintln("Settings wrong size.");
+ outputSerialData(true);
+ }
+ recordSystemSettings(); //Record default settings to EEPROM. At power on, settings are in default state
+ }
+
+ //Check that the strIdentifier is correct
+ uint16_t tempIdentifier = 0;
+ EEPROM.get(sizeof(tempSize), tempIdentifier); //Load the identifier from the EEPROM location after sizeOfSettings (int)
+ if (tempIdentifier != LRS_IDENTIFIER)
+ {
+ if (settings.debugNvm)
+ {
+ systemPrint("Settings are not valid for this variant of LoRaSerial.");
+ outputSerialData(true);
+ }
+ recordSystemSettings(); //Record default settings to EEPROM. At power on, settings are in default state
+ }
+
+ //Read current settings
+ if (settings.debugNvm)
+ {
+ systemPrintln("Reading the settings from EEPROM");
+ outputSerialData(true);
+ }
+ EEPROM.get(0, settings);
+
+ validateSettings(); //Confirm these settings are within regulatory bounds
+
+ recordSystemSettings();
+}
+
+//Modify defaults for each radio type (915, 868, 433, etc)
+//Confirm various settings are within regulatory bounds
+void validateSettings()
+{
+ if (radioBand == 915)
+ {
+ //Radio limits are 900-931MHz
+ //USA ISM bounds are 902-928MHz
+ if (settings.frequencyMin < 900.0 || settings.frequencyMin > 931.0) settings.frequencyMin = 902.0;
+ if (settings.frequencyMax > 931.0 || settings.frequencyMax < 900.0) settings.frequencyMax = 928.0;
+ }
+ else if (radioBand == 868)
+ {
+ //Radio limits are 862-893MHz
+ //EU ESTI limits are 862-893MHz
+ if (settings.frequencyMin < 862.0 || settings.frequencyMin > 893.0) settings.frequencyMin = 862.0;
+ if (settings.frequencyMax > 893.0 || settings.frequencyMax < 862.0) settings.frequencyMax = 893.0;
+ }
+ else if (radioBand == 433)
+ {
+ //Radio limits are 410-510MHz
+ //USA amateur radio limits are 420-450MHz
+ if (settings.frequencyMin < 410.0 || settings.frequencyMin > 510.0) settings.frequencyMin = 420.0;
+ if (settings.frequencyMax > 510.0 || settings.frequencyMax < 410.0) settings.frequencyMax = 450.0;
+ }
+ else
+ {
+ systemPrintln("Error: Unknown radioBand");
+ }
+}
+
+//Record the current settings struct to EEPROM
+void recordSystemSettings()
+{
+ if (settings.debugNvm)
+ {
+ systemPrintln("Writing settings to EEPROM");
+ outputSerialData(true);
+ }
+ settings.sizeOfSettings = sizeof(Settings);
+ EEPROM.put(0, settings);
+
+ arch.eepromCommit();
+}
+
+int nvmVcOffset(int8_t vc)
+{
+ return NVM_UNIQUE_ID_OFFSET + (vc * UNIQUE_ID_BYTES);
+}
+
+//Erase the specified unique ID
+void nvmEraseUniqueId(int8_t vc)
+{
+ uint8_t id[UNIQUE_ID_BYTES];
+ int index;
+
+ //Set the erase value
+ for (index = 0; index < sizeof(id); index++)
+ id[index] = NVM_ERASE_VALUE;
+
+ //Erase this portion of the NVM
+ nvmSaveUniqueId(vc, id);
+
+ //Invalidate the VC structure
+ memcpy(virtualCircuitList[vc].uniqueId, id, sizeof(id));
+ virtualCircuitList[vc].flags.valid = false;
+}
+
+//Get the unique ID for the VC from NVM
+void nvmGetUniqueId(int8_t vc, uint8_t * uniqueId)
+{
+ uint8_t id[UNIQUE_ID_BYTES];
+
+ //Read the unique ID from the flash
+ EEPROM.get(nvmVcOffset(vc), id);
+ memcpy(uniqueId, id, UNIQUE_ID_BYTES);
+}
+
+//Determine if the unique ID is set
+bool nvmIsVcUniqueIdSet(int8_t vc)
+{
+ uint8_t id[UNIQUE_ID_BYTES];
+ int index;
+
+ //Read the ID from the flash
+ nvmGetUniqueId(vc, id);
+
+ //Determine if a unique ID is set in the flash
+ for (index = 0; index < sizeof(id); index++)
+ if (id[index] != NVM_ERASE_VALUE)
+ return true;
+ return false;
+}
+
+//Copy the unique ID for the VC from NVM into the virtualCircuitList entry
+void nvmLoadVcUniqueId(int8_t vc)
+{
+ uint8_t id[UNIQUE_ID_BYTES];
+ int index;
+
+ //Read the ID from the flash
+ nvmGetUniqueId(vc, id);
+
+ //Update the VC when a unique ID is in the NVM
+ if (nvmIsVcUniqueIdSet(vc))
+ {
+ //The unique ID was set, copy it into the VC structure
+ memcpy(virtualCircuitList[vc].uniqueId, id, sizeof(id));
+ virtualCircuitList[vc].flags.valid = true;
+ }
+}
+
+//Save the unique ID into the NVM
+void nvmSaveUniqueId(int8_t vc, uint8_t * uniqueId)
+{
+ uint8_t id[UNIQUE_ID_BYTES];
+ int index;
+
+ //Get the unique ID value
+ memcpy(id, uniqueId, sizeof(id));
+
+ //Write the ID into the flash
+ EEPROM.put(nvmVcOffset(vc), id);
+ arch.eepromCommit();
+
+ //Place the address in the VC structure
+ memcpy(virtualCircuitList[vc].uniqueId, id, sizeof(id));
+ virtualCircuitList[vc].flags.valid = true;
+}
+
+//Save the unique ID from the virtualCircuitList entry into the NVM
+void nvmSaveVcUniqueId(int8_t vc)
+{
+ uint8_t id[UNIQUE_ID_BYTES];
+ int index;
+
+ //Read the ID from the flash
+ nvmGetUniqueId(vc, id);
+
+ //Write the ID into the flash
+ if (memcmp(id, virtualCircuitList[vc].uniqueId, sizeof(id)) != 0)
+ nvmSaveUniqueId(vc, virtualCircuitList[vc].uniqueId);
+}
+
+//Erase the entire EEPROM
+void nvmErase()
+{
+ int address;
+ int length;
+ uint8_t value[64];
+
+ //Get the EEPROM length
+ length = EEPROM.length();
+
+ //Set the erase value
+ memset(&value, NVM_ERASE_VALUE, sizeof(value));
+
+ //Erase the EEPROM
+ address = 0;
+ while (address < length)
+ {
+ petWDT();
+ EEPROM.put(address, value);
+ address += sizeof(value);
+ }
+
+ //Finish the write
+ arch.eepromCommit();
+}
diff --git a/Firmware/LoRaSerial/Radio.ino b/Firmware/LoRaSerial/Radio.ino
new file mode 100644
index 00000000..a2da6e15
--- /dev/null
+++ b/Firmware/LoRaSerial/Radio.ino
@@ -0,0 +1,3771 @@
+//Apply settings to radio
+//Called after begin() and once user exits from command interface
+bool configureRadio()
+{
+ bool success = true;
+
+ radioCallHistory[RADIO_CALL_configureRadio] = millis();
+
+ channelNumber = 0;
+ if (!setRadioFrequency(false))
+ success = false;
+
+ //The SX1276 and RadioLib accepts a value of 2 to 17, with 20 enabling the power amplifier
+ //Measuring actual power output the radio will output 14dBm (25mW) to 27.9dBm (617mW) in constant transmission
+ //So we use a lookup to convert between the user's chosen power and the radio setting
+ int radioPowerSetting = covertdBmToSetting(settings.radioBroadcastPower_dbm);
+ if (radio.setOutputPower(radioPowerSetting) == RADIOLIB_ERR_INVALID_OUTPUT_POWER)
+ success = false;
+
+ if (radio.setBandwidth(settings.radioBandwidth) == RADIOLIB_ERR_INVALID_BANDWIDTH)
+ success = false;
+
+ if (radio.setSpreadingFactor(settings.radioSpreadFactor) == RADIOLIB_ERR_INVALID_SPREADING_FACTOR)
+ success = false;
+
+ if (radio.setCodingRate(settings.radioCodingRate) == RADIOLIB_ERR_INVALID_CODING_RATE)
+ success = false;
+
+ if (radio.setSyncWord(settings.radioSyncWord) != RADIOLIB_ERR_NONE)
+ success = false;
+
+ if (radio.setPreambleLength(settings.radioPreambleLength) == RADIOLIB_ERR_INVALID_PREAMBLE_LENGTH)
+ success = false;
+
+ if (radio.setCRC(true) == RADIOLIB_ERR_INVALID_CRC_CONFIGURATION) //Enable hardware CRC
+ success = false;
+
+ //SF6 requires an implicit header. We will transmit 255 bytes for most packets and 2 bytes for ACK packets.
+ if (settings.radioSpreadFactor == 6)
+ {
+ if (radio.implicitHeader(MAX_PACKET_SIZE) != RADIOLIB_ERR_NONE)
+ success = false;
+ }
+ else
+ {
+ if (radio.explicitHeader() != RADIOLIB_ERR_NONE)
+ success = false;
+ }
+
+ radio.setDio0Action(transactionCompleteISR); //Called when transmission is finished
+ radio.setDio1Action(hopISR); //Called after a transmission has started, so we can move to next freq
+
+ if (pin_rxen != PIN_UNDEFINED)
+ radio.setRfSwitchPins(pin_rxen, pin_txen);
+
+ // HoppingPeriod = Tsym * FreqHoppingPeriod
+ // Given defaults of spreadfactor = 9, bandwidth = 125, it follows Tsym = 4.10ms
+ // HoppingPeriod = 4.10 * x = Yms. Can be as high as 400ms to be within regulatory limits
+ uint16_t hoppingPeriod = settings.maxDwellTime / calcSymbolTimeMsec(); //Limit FHSS dwell time to 400ms max. / automatically floors number
+ if (hoppingPeriod > 255) hoppingPeriod = 255; //Limit to 8 bits.
+ if (settings.frequencyHop == false) hoppingPeriod = 0; //Disable
+ if (radio.setFHSSHoppingPeriod(hoppingPeriod) != RADIOLIB_ERR_NONE)
+ success = false;
+
+ if ((settings.debug == true) || (settings.debugRadio == true))
+ {
+ systemPrint("Freq: ");
+ systemPrintln(channels[0], 3);
+ systemPrint("radioBandwidth: ");
+ systemPrintln(settings.radioBandwidth, 3);
+ systemPrint("radioSpreadFactor: ");
+ systemPrintln(settings.radioSpreadFactor);
+ systemPrint("radioCodingRate: ");
+ systemPrintln(settings.radioCodingRate);
+ systemPrint("radioSyncWord: ");
+ systemPrintln(settings.radioSyncWord);
+ systemPrint("radioPreambleLength: ");
+ systemPrintln(settings.radioPreambleLength);
+ systemPrint("calcSymbolTimeMsec: ");
+ systemPrint(calcSymbolTimeMsec(), 3);
+ systemPrintln(" mSec");
+ systemPrint("HoppingPeriod: ");
+ systemPrintln(hoppingPeriod);
+ outputSerialData(true);
+ }
+
+ if (success == false)
+ systemPrintln("Radio init failed. Check settings.");
+ else if ((settings.debug == true) || (settings.debugRadio == true))
+ systemPrintln("Radio configured");
+ outputSerialData(true);
+ return success;
+}
+
+//Update the settings based upon the airSpeed value
+void convertAirSpeedToSettings(Settings *newSettings, uint16_t airSpeed)
+{
+ switch (airSpeed)
+ {
+ default:
+ systemPrint("Unknown airSpeed: ");
+ systemPrintln(airSpeed);
+ waitForever("ERROR - Invalid airSpeed value");
+ break;
+ case (40):
+ newSettings->radioSpreadFactor = 11;
+ newSettings->radioBandwidth = 62.5;
+ newSettings->radioCodingRate = 8;
+ //HEARTBEAT bytes worst case
+ // P2P - 13,
+ // MP - 7,
+ // VC - 30,
+ if (newSettings->operatingMode == MODE_VIRTUAL_CIRCUIT)
+ newSettings->heartbeatTimeout = 60 * 1000;
+ else
+ newSettings->heartbeatTimeout = 25 * 1000;
+ //uSec: 26018 26026 26026 26025 26020 26038 ==> ~26026
+ newSettings->txToRxUsec = 26026;
+ break;
+ case (150):
+ newSettings->radioSpreadFactor = 10;
+ newSettings->radioBandwidth = 62.5;
+ newSettings->radioCodingRate = 8;
+ if (newSettings->operatingMode == MODE_VIRTUAL_CIRCUIT)
+ newSettings->heartbeatTimeout = 15 * 1000;
+ else
+ newSettings->heartbeatTimeout = 8 * 1000;
+ //uSec: 12187 12188 12189 12190 12191 12194 ==> ~12190
+ newSettings->txToRxUsec = 12190;
+ break;
+ case (400):
+ newSettings->radioSpreadFactor = 10;
+ newSettings->radioBandwidth = 125;
+ newSettings->radioCodingRate = 8;
+ if (newSettings->operatingMode == MODE_VIRTUAL_CIRCUIT)
+ newSettings->heartbeatTimeout = 9 * 1000;
+ else
+ newSettings->heartbeatTimeout = 5 * 1000;
+ //uSec: 6072 6070 6072 6070 6069 6067 ==> ~6070
+ newSettings->txToRxUsec = 6070;
+ break;
+ case (1200):
+ newSettings->radioSpreadFactor = 9;
+ newSettings->radioBandwidth = 125;
+ newSettings->radioCodingRate = 8;
+ newSettings->heartbeatTimeout = 5 * 1000;
+ //uSec: 2770 2777 2772 2773 2771 2773 ==> ~2773
+ newSettings->txToRxUsec = 2773;
+ break;
+ case (2400):
+ newSettings->radioSpreadFactor = 10;
+ newSettings->radioBandwidth = 500;
+ newSettings->radioCodingRate = 8;
+ newSettings->heartbeatTimeout = 5 * 1000;
+ //uSec: 1495 1481 1482 1481 1482 1481 ==> ~1484
+ newSettings->txToRxUsec = 1484;
+ break;
+ case (4800):
+ newSettings->radioSpreadFactor = 9;
+ newSettings->radioBandwidth = 500;
+ newSettings->radioCodingRate = 8;
+ newSettings->heartbeatTimeout = 5 * 1000;
+ //uSec: 657 657 657 658 657 657 ==> ~657
+ newSettings->txToRxUsec = 657;
+ break;
+ case (9600):
+ newSettings->radioSpreadFactor = 8;
+ newSettings->radioBandwidth = 500;
+ newSettings->radioCodingRate = 7;
+ newSettings->heartbeatTimeout = 5 * 1000;
+ //uSec: 279 279 281 280 280 279 ==> ~280
+ newSettings->txToRxUsec = 280;
+ break;
+ case (19200):
+ newSettings->radioSpreadFactor = 7;
+ newSettings->radioBandwidth = 500;
+ newSettings->radioCodingRate = 7;
+ newSettings->heartbeatTimeout = 5 * 1000;
+ //uSec: 119 118 118 119 120 119 ==> ~119
+ newSettings->txToRxUsec = 119;
+ break;
+ case (28800):
+ newSettings->radioSpreadFactor = 6;
+ newSettings->radioBandwidth = 500;
+ newSettings->radioCodingRate = 6;
+ newSettings->heartbeatTimeout = 5 * 1000;
+ //uSec: ???
+ newSettings->txToRxUsec = 0;
+ break;
+ case (38400):
+ newSettings->radioSpreadFactor = 6;
+ newSettings->radioBandwidth = 500;
+ newSettings->radioCodingRate = 5;
+ newSettings->heartbeatTimeout = 5 * 1000;
+ //uSec: ???
+ newSettings->txToRxUsec = 0;
+ break;
+ }
+}
+
+//Set radio frequency
+bool setRadioFrequency(bool rxAdjust)
+{
+ float previousFrequency;
+ static uint8_t previousChannelNumber;
+
+ radioCallHistory[RADIO_CALL_setRadioFrequency] = millis();
+
+ //Determine the frequency to use
+ previousFrequency = radioFrequency;
+ radioFrequency = channels[channelNumber];
+ if (rxAdjust && settings.autoTuneFrequency)
+ radioFrequency -= frequencyCorrection;
+
+ //Set the new frequency
+ if (radio.setFrequency(radioFrequency) == RADIOLIB_ERR_INVALID_FREQUENCY)
+ return false;
+
+ if (settings.debugSync)
+ triggerFrequency(radioFrequency);
+ else
+ triggerEvent(TRIGGER_FREQ_CHANGE);
+
+ //Print the frequency if requested
+ if (settings.printChannel && (previousChannelNumber != channelNumber))
+ {
+ systemPrintTimestamp();
+ systemPrint("CH");
+ systemPrintln(channelNumber);
+ outputSerialData(true);
+ }
+ if (settings.printFrequency && (previousFrequency != radioFrequency))
+ {
+ systemPrintTimestamp();
+ systemPrint(channelNumber);
+ systemPrint(": ");
+ systemPrint(radioFrequency, 3);
+ systemPrint(" MHz, Ch 0 in ");
+ systemPrint(mSecToChannelZero());
+ systemPrintln(" mSec");
+ outputSerialData(true);
+ }
+ previousChannelNumber = channelNumber;
+ return true;
+}
+
+//Place the radio in receive mode
+void returnToReceiving()
+{
+ radioCallHistory[RADIO_CALL_returnToReceiving] = millis();
+
+ if (receiveInProcess() == true) return; //Do not touch the radio if it is already receiving
+
+ int state;
+ if (settings.radioSpreadFactor > 6)
+ {
+ state = radio.startReceive();
+ }
+ else
+ {
+ if (settings.operatingMode == MODE_POINT_TO_POINT)
+ {
+ radio.implicitHeader(sf6ExpectedSize);
+ state = radio.startReceive(sf6ExpectedSize); //Set the size we expect to see
+
+ if (sf6ExpectedSize < MAX_PACKET_SIZE)
+ triggerEvent(TRIGGER_RTR_SHORT_PACKET);
+ else
+ triggerEvent(TRIGGER_RTR_255BYTE);
+
+ sf6ExpectedSize = MAX_PACKET_SIZE; //Always return to expecing a full data packet
+ }
+ }
+
+ if (state != RADIOLIB_ERR_NONE) {
+ startReceiveFailureMillis = rcvTimeMillis;
+ startReceiveFailureState = state;
+ if ((settings.debug == true) || (settings.debugRadio == true))
+ {
+ systemPrint("Receive failed: ");
+ systemPrintln(state);
+ outputSerialData(true);
+ }
+ }
+}
+
+//Given spread factor, bandwidth, coding rate and number of bytes, return total Air Time in ms for packet
+//See datasheet for the nPayload formula / section 4.1.1.6
+float calcAirTimeUsec(uint8_t bytesToSend)
+{
+ radioCallHistory[RADIO_CALL_calcAirTimeUsec] = millis();
+
+ float tSymUsec = calcSymbolTimeUsec();
+
+ //See Synchronization section
+ float tPreambleUsec = (settings.radioPreambleLength + 2 + 2.25) * tSymUsec;
+
+ const uint8_t useHardwareCRC = 1; //0 to disable
+
+ //With SF = 6 selected, implicit header mode is the only mode of operation possible.
+ uint8_t explicitHeader = 0; //1 for implicit header
+ if (settings.radioSpreadFactor == 6) explicitHeader = 1;
+
+ //LowDataRateOptimize increases the robustness of the LoRa link at low effective data
+ //rates. Its use is mandated when the symbol duration exceeds 16ms.
+ //We choose to enable LDRO for airSpeed of 400 even though TSym is 8.2ms.
+ uint8_t useLowDataRateOptimization = (tSymUsec >= 8192);
+ float p1 = ((8 * bytesToSend) - (4 * settings.radioSpreadFactor) + 28
+ + (16 * useHardwareCRC) - (20 * explicitHeader))
+ / (4.0 * (settings.radioSpreadFactor - (2 * useLowDataRateOptimization)));
+ p1 = ceil(p1) * settings.radioCodingRate;
+ if (p1 < 0) p1 = 0;
+ uint16_t payloadBytes = 8 + p1;
+ float tPayloadUsec = payloadBytes * tSymUsec;
+ float tPacketUsec = tPreambleUsec + tPayloadUsec;
+ return tPacketUsec;
+}
+
+//Return the frame air time in milliseconds
+uint16_t calcAirTimeMsec(uint8_t bytesToSend)
+{
+ return ((uint16_t)ceil(calcAirTimeUsec(bytesToSend) / 1000.));
+}
+
+//Given spread factor and bandwidth, return symbol time
+float calcSymbolTimeUsec()
+{
+ //The following documentation is from https://en.wikipedia.org/wiki/LoRa
+ //
+ //Each symbol is represented by a cyclic shifted chirp over the frequency
+ //interval (f0-B/2,f0+B/2) where f0 is the center frequency and B the
+ //bandwidth of the signal (in Hertz).
+ //The spreading factor (SF) is a selectable radio parameter from 5 to 12 and
+ //represents the number of bits sent per symbol and in addition determines
+ //how much the information is spread over time.
+ //There are M=2^SF different initial frequencies of the cyclic shifted chirp
+ //(the instantaneous frequency is linearly increased and wrapped to f0-B/2
+ //when it reaches the maximum frequency f0+B/2.
+ //The symbol rate is determined by Rs=B/(2^SF.
+ //LoRa can trade off data rate for sensitivity (assuming a fixed channel
+ //bandwidth B) by selecting the SF, i.e. the amount of spread used.
+ //A lower SF corresponds to a higher data rate but a worse sensitivity, a
+ //higher SF implies a better sensitivity but a lower data rate.
+
+ //The LoRa PHY is described in https://wirelesspi.com/understanding-lora-phy-long-range-physical-layer/
+ //
+ // SF = spread factor = number of bits per symbol
+ //
+ // M = 2^SF = number of samples per symbol
+ //
+ // B = Bandwidth of the input signal
+ //
+ //From the sampling theorem:
+ //
+ // Fs >= 2 * B for real frequencies
+ // Fs >= B for complex frequencies
+ //
+ //Since this is a complex frequency and we want to use the lowest possible
+ //sampling frequency, we have
+ //
+ // Fs = B = 1 / Ts
+ //
+ // Ts = 1 / B
+ //
+ // Tm = M / B = Symbol time
+ //
+ // F1 = B / M = frequency step used within the bandwidth
+ //
+ // Fm = m * F1, m = 0 - (M-1) Frequency starting and end points
+ //
+ // u = B / Tm = Chirp rate
+ //
+ // Example: SF = 2
+ // M = 2 ^ 2 = 4
+ //
+ //Each symbol time (Tm), the signal changes frequencies from f0 - B/2 to f0 + B/2.
+ //Each symbol has a different starting (ending) frequency, but scans the entire
+ //bandwidth.
+ //
+ // ___________________________ f0 + B/2
+ // /| /| /| /|
+ // / | / | / | | /
+ // / |/ | | / | /
+ // _____/___|___|/__|/__|/_____
+ // f0 - B/2
+ // Symbol | 00 | 01 | 10 | 11 |
+ // | | | | |
+ // 0 Tm 2Tm 3Tm 4Tm
+ //
+ //The signal is e^(j* [(u*pi*t^2)+(2*pi*Fm*t)+phi])
+ //
+ //I: The real portion of the signal, cos((u*pi*t^2)+(2*pi*Fm*t)+phi)
+ //Q: The imaginary portion of the signal, j*sin((u*pi*t^2)+(2*pi*Fm*t)+phi)
+ //
+ //Decoding the signal is done by down chirping, multiplying the following
+ //phase locked signal with the broadcast signal and putting it through a low
+ //pass filter.
+ //
+ // ___________________________ f0 + B/2
+ // |\ |\ |\ |\
+ // | \ | \ | \ | \
+ // | \ | \ | \ | \
+ // _____|___\|___\|___\|___\__
+ // f0 - B/2
+ // | | | | |
+ // 0 Tm 2Tm 3Tm 4Tm
+ //
+ //The resulting signal is effectively added and offset to produce a constant
+ //frequency associated with the symbol over the symbol time.
+ //
+ // 0 Tm 2Tm 3Tm 4Tm
+ // | | | | |
+ // _____ B
+ // _____
+ // _____
+ // _____
+ // 0
+ // | | | | |
+ // 0 Tm 2Tm 3Tm 4Tm
+ //
+ // SF 11 10 9 8 7 6
+ // M 2048 1024 512 256 128 64
+ // B KHz 62.5 62.5 125 125 500 500
+ // Tm uSec 65536 32768 8192 4096 512 256
+ // Symbols 15.25 30.52 122.1 244.1 1953 3906
+ //
+ //Compute time in microseconds using bandwidth in kHz
+ float tSymUsec = (pow(2, settings.radioSpreadFactor) * 1000.) / settings.radioBandwidth;
+ return (tSymUsec);
+}
+
+//Return symbol time in milliseconds
+float calcSymbolTimeMsec()
+{
+ return calcSymbolTimeUsec() / 1000.;
+}
+
+//Given spread factor, bandwidth, coding rate and frame size, return most bytes we can push per second
+uint16_t calcMaxThroughput()
+{
+ uint8_t mostFramesPerSecond = 1000 / maxFrameAirTimeMsec;
+ uint16_t mostBytesPerSecond = maxDatagramSize * mostFramesPerSecond;
+
+ return (mostBytesPerSecond);
+}
+
+uint16_t myRandSeed;
+bool myRandBit;
+
+//Generate unique hop table based on radio settings
+void generateHopTable()
+{
+ if (channels != NULL) free(channels);
+ channels = (float *)malloc(settings.numberOfChannels * sizeof(float));
+
+ float channelSpacing = (settings.frequencyMax - settings.frequencyMin) / (float)(settings.numberOfChannels + 2);
+
+ //Keep away from edge of available spectrum
+ float operatingMinFreq = settings.frequencyMin + (channelSpacing / 2);
+
+ //Pre populate channel list
+ for (int x = 0 ; x < settings.numberOfChannels ; x++)
+ channels[x] = operatingMinFreq + (x * channelSpacing);
+
+ //Feed random number generator with our specific platform settings
+ //Use settings that must be identical to have a functioning link.
+ //For example, we do not use coding rate because two radios can communicate with different coding rate values
+ myRandSeed = (uint16_t)settings.radioBandwidth
+ + settings.radioSpreadFactor //Radio settings
+ + settings.radioCodingRate
+ + settings.txToRxUsec
+ + settings.netID
+ + settings.operatingMode
+ + settings.encryptData
+ + settings.dataScrambling
+ + (uint16_t)settings.frequencyMin
+ + (uint16_t)settings.frequencyMax
+ + settings.numberOfChannels
+ + settings.frequencyHop
+ + settings.maxDwellTime
+ + settings.verifyRxNetID
+ + settings.overheadTime
+ + settings.enableCRC16
+ + settings.clientFindPartnerRetryInterval;
+
+ if (settings.encryptData == true)
+ {
+ for (uint8_t x = 0 ; x < sizeof(settings.encryptionKey) ; x++)
+ myRandSeed += settings.encryptionKey[x];
+ }
+
+ //'Randomly' shuffle list based on our specific seed
+ shuffle(channels, settings.numberOfChannels);
+
+ //Verify the AES IV length
+ if (AES_IV_BYTES != gcm.ivSize())
+ {
+ systemPrint("ERROR - Wrong AES IV size in bytes, please set AES_IV_BYTES = ");
+ systemPrintln(gcm.ivSize());
+ waitForever("ERROR - Fix the AES_IV_BYTES value!");
+ }
+
+ //Verify the AES key length
+ if (AES_KEY_BYTES != gcm.keySize())
+ {
+ systemPrint("ERROR - Wrong AES key size in bytes, please set AES_KEY_BYTES = ");
+ systemPrintln(gcm.keySize());
+ waitForever("ERROR - Fix the AES_KEY_BYTES value!");
+ }
+
+ //Set new initial values for AES using settings based random seed
+ for (uint8_t x = 0 ; x < sizeof(AESiv) ; x++)
+ AESiv[x] = myRand();
+
+ if ((settings.debug == true) || (settings.debugRadio == true))
+ {
+ petWDT();
+ systemPrint("channelSpacing: ");
+ systemPrintln(channelSpacing, 3);
+
+ systemPrintln("Channel table:");
+ for (int x = 0 ; x < settings.numberOfChannels ; x++)
+ {
+ petWDT();
+ systemPrint(x);
+ systemPrint(": ");
+ systemPrint(channels[x], 3);
+ systemPrintln();
+ }
+
+ petWDT();
+
+ systemPrint("NetID: ");
+ systemPrintln(settings.netID);
+
+ systemPrint("AES Key: ");
+ for (uint8_t i = 0 ; i < AES_KEY_BYTES ; i++)
+ systemPrint(settings.encryptionKey[i], HEX);
+ systemPrintln();
+
+ systemPrint("AES IV: ");
+ for (uint8_t i = 0 ; i < AES_IV_BYTES ; i++)
+ systemPrint(AESiv[i], HEX);
+ systemPrintln();
+
+ outputSerialData(true);
+ }
+}
+
+//Array shuffle from http://benpfaff.org/writings/clc/shuffle.html
+void shuffle(float *array, uint8_t n)
+{
+ for (uint8_t i = 0; i < n - 1; i++)
+ {
+ uint8_t j = myRand() % n;
+ float t = array[j];
+ array[j] = array[i];
+ array[i] = t;
+ }
+}
+
+//Simple lfsr randomizer. Needed because we cannot guarantee how random()
+//will respond on different Arduino platforms. ie Uno acts diffrently from ESP32.
+//We don't need 'truly random', we need repeatable across platforms.
+uint16_t myRand()
+{
+ myRandBit = ((myRandSeed >> 0) ^ (myRandSeed >> 2) ^ (myRandSeed >> 3) ^ (myRandSeed >> 5) ) & 1;
+ return myRandSeed = (myRandSeed >> 1) | (myRandBit << 15);
+}
+
+//Move to the next channel
+//This is called when the FHSS interrupt is received
+//at the beginning and during of a transmission or reception
+void hopChannel()
+{
+ hopChannel(true, 1); //Move forward
+}
+
+//Hop to the previous channel in the frequency list
+void hopChannelReverse()
+{
+ hopChannel(false, 1); //Move backward
+}
+
+//Set the next radio frequency given the hop direction and frequency table
+void hopChannel(bool moveForwardThroughTable, uint8_t channelCount)
+{
+ radioCallHistory[RADIO_CALL_hopChannel] = millis();
+
+ timeToHop = false;
+
+ if (moveForwardThroughTable)
+ channelNumber += channelCount;
+ else
+ channelNumber += settings.numberOfChannels - channelCount;
+ channelNumber %= settings.numberOfChannels;
+
+ //Select the new frequency
+ setRadioFrequency(radioStateTable[radioState].rxState);
+ blinkChannelHopLed(true);
+}
+
+//Determine the time in milliseconds when channel zero is reached again
+unsigned long mSecToChannelZero()
+{
+ unsigned long nextChannelZeroTimeInMillis;
+ uint16_t remainingChannels;
+
+ //Compute the time remaining at the current channel
+ nextChannelZeroTimeInMillis = channelTimerMsec - (millis() - channelTimerStart);
+
+ //Compute the time associated with the additional channels
+ remainingChannels = settings.numberOfChannels - 1 - channelNumber;
+ if (remainingChannels > 0)
+ nextChannelZeroTimeInMillis += remainingChannels * settings.maxDwellTime;
+ return nextChannelZeroTimeInMillis;
+}
+
+//Returns true if the radio indicates we have an ongoing reception
+bool receiveInProcess()
+{
+ uint8_t radioStatus = radio.getModemStatus();
+ radioStatus &= 0b11011; //Get bits 0, 1, 3, and 4
+
+ //Known states where a reception is in progress
+ if (radioStatus == 0b00001)
+ return (true);
+ else if (radioStatus == 0b00011)
+ return (true);
+ else if (radioStatus == 0b01011)
+ return (true);
+
+ // switch (radioStatus)
+ // {
+ // default:
+ // Serial.print("Unknown status: 0b");
+ // Serial.println(radioStatus, BIN);
+ // break;
+ // case (0b00000):
+ // //No receive in process
+ // case (0b10000):
+ // //Modem clear. No receive in process
+ // break;
+ // }
+
+ return (false);
+}
+
+//Convert the user's requested dBm to what the radio should be set to, to hit that power level
+//3 is lowest allowed setting using SX1276+RadioLib
+uint8_t covertdBmToSetting(uint8_t userSetting)
+{
+ switch (userSetting)
+ {
+ case 14: return (2); break;
+ case 15: return (3); break;
+ case 16: return (4); break;
+ case 17: return (5); break;
+ case 18: return (6); break;
+ case 19: return (7); break;
+ case 20: return (7); break;
+ case 21: return (8); break;
+ case 22: return (9); break;
+ case 23: return (10); break;
+ case 24: return (11); break;
+ case 25: return (12); break;
+ case 26: return (13); break;
+ case 27: return (20); break;
+ case 28: return (20); break;
+ case 29: return (20); break;
+ case 30: return (20); break;
+ default: return (3); break;
+ }
+}
+
+#ifdef RADIOLIB_LOW_LEVEL
+//Read a register from the SX1276 chip
+uint8_t readSX1276Register(uint8_t reg)
+{
+ radioCallHistory[RADIO_CALL_readSX1276Register] = millis();
+
+ return radio._mod->SPIreadRegister(reg);
+}
+
+//SX1276 LoRa Register Names
+const char * const sx1276RegisterNames[] =
+{
+ NULL, "RegOpMode", NULL, NULL, // 0 - 3
+ NULL, NULL, "RegFrfMsb", "RegFrfMid", // 4 - 7
+ "RegFrfLsb", "RegPaConfig", "RegPaRamp", "RegOcp", // 8 - b
+ "RegLna", "RegFifoAddrPtr", "RegFifoTxBaseAddr", "regFifoRxBaseAddr", // c - f
+
+ "FifoRxCurrentAddr", "RegIrqFlagsMask", "RegIrqFlags", "RegRxNbBytes", //10 - 13
+ "RegRxHeaderCntValueMsb", "RegRxHeaderCntValueLsb", "RegRxPacketCntValueMsb", "RegRxPacketCntValueLsb", //14 - 17
+ "RegModemStat", "RegPktSnrValue", "RegPktRssiValue", "RegRssiValue", //18 - 1b
+ "RegHopChannel", "RegModemConfig1", "RegModemConfig2", "RegSymbTimeoutLsb", //1c - 1f
+
+ "RegPreambleMsb", "RegPreambleLsb", "RegPayloadLength", "RegMaxPayloadLength",//20 - 23
+ "RegHopPeriod", "RegFifoRxByteAddr", "RegModemConfig3", NULL, //24 - 27
+ "RegFeiMsb", "RegFeiMid", "RegFeiLsb", NULL, //28 - 2b
+ "RegRssiWideband", NULL, NULL, "RegIfFreq1", //2c - 2f
+
+ "RegIfFreq2", "ReqDetectOptimize", NULL, "ReqInvertIQ", //30 - 33
+ NULL, NULL, "RegHighBwOpimize1", "RegDetectionThreshold", //34 - 37
+ NULL, "RegSyncWord", "RegHighBwOptimize2", "RegInvertIQ2", //38 - 3b
+ NULL, NULL, NULL, NULL, //3c - 3f
+
+ "RegDioMapping1", "RegDioMapping2", "RegVersion", NULL, //40 - 43
+ NULL, NULL, NULL, NULL, //44 - 47
+ NULL, NULL, NULL, "RegTcxo", //48 - 4b
+ NULL, "RegPaDac", NULL, NULL, //4C - 4F
+
+ NULL, NULL, NULL, NULL, //50 - 53
+ NULL, NULL, NULL, NULL, //54 - 57
+ NULL, NULL, NULL, "RegFormerTemp", //58 - 5b
+ NULL, NULL, NULL, NULL, //5c - 5f
+
+ NULL, "RegAgcRef", "RegAgcThresh1", "RegAgcThresh2", //60 - 63
+ "RegAgcThresh3", NULL, NULL, NULL, //64 - 67
+ NULL, NULL, NULL, NULL, //68 - 6b
+ NULL, NULL, NULL, NULL, //6c - 6f
+
+ "RegPII", //70
+};
+
+//Print the SX1276 LoRa registers
+void printSX1276Registers()
+{
+ radioCallHistory[RADIO_CALL_printSX1276Registers] = millis();
+
+ petWDT();
+ systemPrintln("SX1276 Registers:");
+ systemPrintln(" Reg Value Name");
+ for (uint8_t i = 0; i < (sizeof(sx1276RegisterNames) / sizeof(sx1276RegisterNames[0])); i++)
+ {
+ //Only read and print the valid registers
+ if (sx1276RegisterNames[i])
+ {
+ systemPrint(" 0x");
+ systemPrint(i, HEX);
+ systemPrint(": 0x");
+ systemPrint(readSX1276Register(i), HEX);
+ systemPrint(", ");
+ systemPrintln(sx1276RegisterNames[i]);
+ outputSerialData(true);
+ petWDT();
+ }
+ }
+}
+
+#endif //RADIOLIB_LOW_LEVEL
+
+//ISR when DIO0 goes low
+//Called when transmission is complete or when RX is received
+void transactionCompleteISR(void)
+{
+ transactionCompleteMicros = micros();
+ radioCallHistory[RADIO_CALL_transactionCompleteISR] = millis();
+ triggerEvent(TRIGGER_TRANSACTION_COMPLETE);
+
+ //Start the channel timer if requested
+ if (startChannelTimerPending)
+ {
+ startChannelTimer(); //transactionCompleteISR, upon TX or RX of SYNC_CLOCKS
+ startChannelTimerPending = false; //transactionCompleteISR, upon TX or RX of SYNC_CLOCKS
+ }
+
+ //Signal the state machine that a receive or transmit has completed
+ transactionComplete = true;
+}
+
+//ISR when DIO1 goes low
+//Called when FhssChangeChannel interrupt occurs (at regular HoppingPeriods)
+//We do not use SX based channel hopping, and instead use a synchronized hardware timer
+//We use the hop ISR to measure RSSI during reception
+void hopISR(void)
+{
+ radioCallHistory[RADIO_CALL_hopISR] = millis();
+
+ hop = true;
+}
+
+//We clear the hop ISR just to make logic analyzer data cleaner
+void updateHopISR()
+{
+ if (hop) //Clear hop ISR as needed
+ {
+ hop = false;
+ radio.clearFHSSInt(); //Clear the interrupt
+ }
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Table for use in calculating the software CRC-16
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+const uint16_t crc16Table[256] =
+{
+ 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
+ 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
+ 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6,
+ 0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE,
+ 0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485,
+ 0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D,
+ 0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4,
+ 0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC,
+ 0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823,
+ 0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B,
+ 0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12,
+ 0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A,
+ 0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41,
+ 0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49,
+ 0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70,
+ 0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78,
+ 0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F,
+ 0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067,
+ 0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E,
+ 0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256,
+ 0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D,
+ 0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405,
+ 0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C,
+ 0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634,
+ 0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB,
+ 0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3,
+ 0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A,
+ 0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92,
+ 0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9,
+ 0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
+ 0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8,
+ 0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
+};
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Point-To-Point: Bring up the link
+//
+//A three way handshake is used to get both systems to agree that data can flow in both
+//directions. This handshake is also used to synchronize the HOP timer and zero the ACKs.
+/*
+ System A System B
+
+ RESET RESET
+ | |
+ Channel 0 | | Channel 0
+ V V
+ .----> P2P_NO_LINK P2P_NO_LINK
+ | | Tx FIND_PARTNER |
+ | Timeout | |
+ | V |
+ | P2P_WAIT_TX_FIND_PARTNER_DONE |
+ | | |
+ | | Tx Complete - - - - - > | Rx FIND_PARTNER
+ | | Start Rx |
+ | | MAX_PACKET_SIZE |
+ | V V
+ `---- P2P_WAIT_SYNC_CLOCKS +<----------------------------.
+ | | Tx SYNC_CLOCKS |
+ | V |
+ | P2P_WAIT_TX_SYNC_CLOCKS_DONE |
+ | | |
+ Rx SYNC_CLOCKS | < - - - - - - - - - - - | Tx Complete |
+ | | Start Rx |
+ | | MAX_PACKET_SIZE |
+ | | |
+ V V Timeout |
+ .--------------->+ P2P_WAIT_ZERO_ACKS ------------------->+
+ | | | ^
+ | | TX ZERO_ACKS | |
+ | | | |
+ | V | |
+ | P2P_WAIT_TX_ZERO_ACKS_DONE | |
+ | | Tx Complete - - - - - > | Rx ZERO_ACKS |
+ | Stop | Start HOP timer | Start HOP Timer | Stop
+ | HOP | Start Rx | Start Rx | HOP
+ | Timer | MAX_PACKET_SIZE | MAX_PACKET_SIZE | Timer
+ | | Zero ACKs | Zero ACKs |
+ | Rx | | |
+ | SYNC_CLOCKS V V Rx FIND_PARTNER |
+ `---------- P2P_LINK_UP P2P_LINK_UP -----------------------’
+ | |
+ | Rx Data | Rx Data
+ | |
+ V V
+
+ Two timers are in use:
+ datagramTimer: Set at end of transmit, measures ACK timeout
+ heartbeatTimer: Set upon entry to P2P_NO_LINK, measures time to send next FIND_PARTNER
+*/
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//First packet in the three way handshake to bring up the link
+bool xmitDatagramP2PFindPartner()
+{
+ uint8_t * startOfData;
+
+ unsigned long currentMillis = millis();
+ radioCallHistory[RADIO_CALL_xmitDatagramP2PFindPartner] = currentMillis;
+
+ startOfData = endOfTxData;
+ memcpy(endOfTxData, ¤tMillis, sizeof(currentMillis));
+ endOfTxData += sizeof(unsigned long);
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+---------+----------+
+ | Optional | | Optional | Optional | | |
+ | NET ID | Control | C-Timer | SF6 Length | Millis | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 4 bytes | n Bytes |
+ +----------+---------+----------+------------+---------+----------+
+ */
+
+ //Verify the data length
+ if ((endOfTxData - startOfData) != P2P_FIND_PARTNER_BYTES)
+ waitForever("ERROR - Fix the P2P_FIND_PARTNER_BYTES value!");
+
+ txControl.datagramType = DATAGRAM_FIND_PARTNER;
+ return (transmitDatagram());
+}
+
+//Second packet in the three way handshake to bring up the link
+//SYNC_CLOCKS packet sent by server in response the FIND_PARTNER, includes the
+//channel number. During discovery scanning, it's possible for the client to
+//get the SYNC_CLOCKS but be on an adjacent channel. The channel number
+//ensures that the client gets the next hop correct.
+bool xmitDatagramP2PSyncClocks()
+{
+ uint8_t * startOfData;
+
+ unsigned long currentMillis = millis();
+ radioCallHistory[RADIO_CALL_xmitDatagramP2PSyncClocks] = currentMillis;
+
+ startOfData = endOfTxData;
+ memcpy(endOfTxData, &channelNumber, sizeof(channelNumber));
+ endOfTxData += sizeof(channelNumber);
+
+ memcpy(endOfTxData, ¤tMillis, sizeof(currentMillis));
+ endOfTxData += sizeof(unsigned long);
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+---------+---------+----------+
+ | Optional | | Optional | Optional | Channel | | |
+ | NET ID | Control | C-Timer | SF6 Length | Number | Millis | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 1 byte | 4 bytes | n Bytes |
+ +----------+---------+----------+------------+---------+---------+----------+
+ */
+
+ //Verify the data length
+ if ((endOfTxData - startOfData) != P2P_SYNC_CLOCKS_BYTES)
+ waitForever("ERROR - Fix the P2P_SYNC_CLOCKS_BYTES value!");
+
+ txControl.datagramType = DATAGRAM_SYNC_CLOCKS;
+ return (transmitDatagram());
+}
+
+//Last packet in the three way handshake to bring up the link
+bool xmitDatagramP2PZeroAcks()
+{
+ uint8_t * startOfData;
+
+ unsigned long currentMillis = millis();
+ radioCallHistory[RADIO_CALL_xmitDatagramP2PZeroAcks] = currentMillis;
+
+ startOfData = endOfTxData;
+ memcpy(endOfTxData, ¤tMillis, sizeof(currentMillis));
+ endOfTxData += sizeof(unsigned long);
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+---------+----------+
+ | Optional | | Optional | Optional | | |
+ | NET ID | Control | C-Timer | SF6 Length | Millis | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 4 bytes | n Bytes |
+ +----------+---------+----------+------------+---------+----------+
+ */
+
+ //Verify the data length
+ if ((endOfTxData - startOfData) != P2P_ZERO_ACKS_BYTES)
+ waitForever("ERROR - Fix the P2P_ZERO_ACKS_BYTES value!");
+
+ txControl.datagramType = DATAGRAM_ZERO_ACKS;
+ return (transmitDatagram());
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+// Point-to-Point Data Exchange
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Send a command datagram to the remote system
+bool xmitDatagramP2PCommand()
+{
+ radioCallHistory[RADIO_CALL_xmitDatagramP2PCommand] = millis();
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+---------+----------+------------+-------------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_REMOTE_COMMAND;
+ return (transmitDatagram());
+}
+
+//Send a command response datagram to the remote system
+bool xmitDatagramP2PCommandResponse()
+{
+ radioCallHistory[RADIO_CALL_xmitDatagramP2PCommandResponse] = millis();
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+---------+----------+------------+-------------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_REMOTE_COMMAND_RESPONSE;
+ return (transmitDatagram());
+}
+
+//Send a data datagram to the remote system
+bool xmitDatagramP2PData()
+{
+ radioCallHistory[RADIO_CALL_xmitDatagramP2PData] = millis();
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+---------+----------+------------+-------------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_DATA;
+ return (transmitDatagram());
+}
+
+//Heartbeat packet to keep the link up
+bool xmitDatagramP2PHeartbeat()
+{
+ uint8_t * startOfData;
+
+ unsigned long currentMillis = millis();
+ radioCallHistory[RADIO_CALL_xmitDatagramP2PHeartbeat] = currentMillis;
+
+ startOfData = endOfTxData;
+ memcpy(endOfTxData, ¤tMillis, sizeof(currentMillis));
+ endOfTxData += sizeof(currentMillis);
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+---------+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Millis | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 4 bytes | n Bytes |
+ +----------+---------+----------+------------+---------+----------+
+ */
+
+ //Verify the data length
+ if ((endOfTxData - startOfData) != P2P_HEARTBEAT_BYTES)
+ waitForever("ERROR - Fix the P2P_HEARTBEAT_BYTES value!");
+
+ txControl.datagramType = DATAGRAM_HEARTBEAT;
+ return (transmitDatagram());
+}
+
+//Create short packet - do not expect ack
+bool xmitDatagramP2PAck()
+{
+ uint8_t * startOfData;
+
+ unsigned long currentMillis = millis();
+ radioCallHistory[RADIO_CALL_xmitDatagramP2PAck] = currentMillis;
+
+ startOfData = endOfTxData;
+ memcpy(endOfTxData, ¤tMillis, sizeof(currentMillis));
+ endOfTxData += sizeof(currentMillis);
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+---------+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Millis | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 4 bytes | n Bytes |
+ +----------+---------+----------+------------+---------+----------+
+ */
+
+ //Verify the data length
+ if ((endOfTxData - startOfData) != P2P_ACK_BYTES)
+ waitForever("ERROR - Fix the P2P_ACK_BYTES value!");
+
+ txControl.datagramType = DATAGRAM_DATA_ACK;
+ return (transmitDatagram());
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+// Multi-Point Data Exchange
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Send a data datagram to the remote system, including sync data
+bool xmitDatagramMpData()
+{
+ radioCallHistory[RADIO_CALL_xmitDatagramMpData] = millis();
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+---------+----------+------------+-------------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_DATA;
+ return (transmitDatagram());
+}
+
+//Heartbeat packet sent by server in Multipoint mode, includes the
+//channel number. During discovery scanning, it's possible for the client to
+//get the HeartBeat but be on an adjacent channel. The channel number
+//ensures that the client gets the next hop correct.
+bool xmitDatagramMpHeartbeat()
+{
+ uint8_t * startOfData;
+
+ unsigned long currentMillis = millis();
+ radioCallHistory[RADIO_CALL_xmitDatagramMpHeartbeat] = millis();
+
+ startOfData = endOfTxData;
+ memcpy(endOfTxData, &channelNumber, sizeof(channelNumber));
+ endOfTxData += sizeof(channelNumber);
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+---------+----------+
+ | Optional | | Optional | Optional | Channel | |
+ | NET ID | Control | C-Timer | SF6 Length | Number | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 1 byte | n Bytes |
+ +----------+---------+----------+------------+---------+----------+
+ */
+
+ //Verify the data length
+ if ((endOfTxData - startOfData) != MP_HEARTBEAT_BYTES)
+ waitForever("ERROR - Fix the MP_HEARTBEAT_BYTES value!");
+
+ txControl.datagramType = DATAGRAM_HEARTBEAT;
+ return (transmitDatagram());
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Multi-Point Client Training
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Build the FIND_PARTNER packet used for training
+bool xmitDatagramTrainingFindPartner()
+{
+ radioCallHistory[RADIO_CALL_xmitDatagramTrainingFindPartner] = millis();
+
+ //Add the source (server) ID
+ memcpy(endOfTxData, myUniqueId, UNIQUE_ID_BYTES);
+ endOfTxData += UNIQUE_ID_BYTES;
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+-----------+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Client ID | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 16 Bytes | n Bytes |
+ +----------+---------+----------+------------+-----------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_TRAINING_FIND_PARTNER;
+ return (transmitDatagram());
+}
+
+//Build the client ACK packet used for training
+bool xmitDatagramTrainingAck(uint8_t * serverID)
+{
+ radioCallHistory[RADIO_CALL_xmitDatagramTrainingAck] = millis();
+
+ //Add the destination (server) ID
+ memcpy(endOfTxData, serverID, UNIQUE_ID_BYTES);
+ endOfTxData += UNIQUE_ID_BYTES;
+
+ //Add the source (client) ID
+ memcpy(endOfTxData, myUniqueId, UNIQUE_ID_BYTES);
+ endOfTxData += UNIQUE_ID_BYTES;
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+-----------+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Client ID | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 16 Bytes | n Bytes |
+ +----------+---------+----------+------------+-----------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_TRAINING_ACK;
+ return (transmitDatagram());
+}
+
+//Copy the training parameters received from the server into the settings structure
+//that will eventually be written into the NVM
+void updateRadioParameters(uint8_t * rxData)
+{
+ Settings params;
+
+ //Get the parameters
+ memcpy(¶ms, rxData, sizeof(params));
+
+ //Update the radio parameters
+ trainingSettings.autoTuneFrequency = params.autoTuneFrequency;
+ trainingSettings.frequencyHop = params.frequencyHop;
+ trainingSettings.frequencyMax = params.frequencyMax;
+ trainingSettings.frequencyMin = params.frequencyMin;
+ trainingSettings.maxDwellTime = params.maxDwellTime;
+ trainingSettings.numberOfChannels = params.numberOfChannels;
+ trainingSettings.radioBandwidth = params.radioBandwidth;
+ trainingSettings.radioBroadcastPower_dbm = params.radioBroadcastPower_dbm;
+ trainingSettings.radioCodingRate = params.radioCodingRate;
+ trainingSettings.radioPreambleLength = params.radioPreambleLength;
+ trainingSettings.radioSpreadFactor = params.radioSpreadFactor;
+ trainingSettings.radioSyncWord = params.radioSyncWord;
+ trainingSettings.txToRxUsec = params.txToRxUsec;
+
+ //Update the radio protocol parameters
+ trainingSettings.dataScrambling = params.dataScrambling;
+ trainingSettings.enableCRC16 = params.enableCRC16;
+ trainingSettings.encryptData = params.encryptData;
+ memcpy(trainingSettings.encryptionKey, params.encryptionKey, sizeof(trainingSettings.encryptionKey));
+ trainingSettings.framesToYield = params.framesToYield;
+ trainingSettings.heartbeatTimeout = params.heartbeatTimeout;
+ trainingSettings.maxResends = params.maxResends;
+ trainingSettings.netID = params.netID;
+ trainingSettings.operatingMode = params.operatingMode;
+ trainingSettings.overheadTime = params.overheadTime;
+ trainingSettings.selectLedUse = params.selectLedUse;
+ trainingSettings.server = params.server;
+ trainingSettings.verifyRxNetID = params.verifyRxNetID;
+
+ //Update the debug parameters
+ if (params.copyDebug)
+ {
+ trainingSettings.copyDebug = params.copyDebug;
+ trainingSettings.debug = params.debug;
+ trainingSettings.debugDatagrams = params.debugDatagrams;
+ trainingSettings.debugHeartbeat = params.debugHeartbeat;
+ trainingSettings.debugNvm = params.debugNvm;
+ trainingSettings.debugRadio = params.debugRadio;
+ trainingSettings.debugReceive = params.debugReceive;
+ trainingSettings.debugSerial = params.debugSerial;
+ trainingSettings.debugStates = params.debugStates;
+ trainingSettings.debugSync = params.debugSync;
+ trainingSettings.debugTraining = params.debugTraining;
+ trainingSettings.debugTransmit = params.debugTransmit;
+ trainingSettings.displayRealMillis = params.displayRealMillis;
+ trainingSettings.printAckNumbers = params.printAckNumbers;
+ trainingSettings.printChannel = params.printChannel;
+ trainingSettings.printFrequency = params.printFrequency;
+ trainingSettings.printLinkUpDown = params.printLinkUpDown;
+ trainingSettings.printPacketQuality = params.printPacketQuality;
+ trainingSettings.printPktData = params.printPktData;
+ trainingSettings.printRfData = params.printRfData;
+ trainingSettings.printTimestamp = params.printTimestamp;
+ trainingSettings.printTxErrors = params.printTxErrors;
+ }
+
+ //Update the serial parameters
+ if (params.copySerial)
+ {
+ trainingSettings.copySerial = params.copySerial;
+ trainingSettings.echo = params.echo;
+ trainingSettings.flowControl = params.flowControl;
+ trainingSettings.invertCts = params.invertCts;
+ trainingSettings.invertRts = params.invertRts;
+ trainingSettings.serialSpeed = params.serialSpeed;
+ trainingSettings.serialTimeoutBeforeSendingFrame_ms = params.serialTimeoutBeforeSendingFrame_ms;
+ trainingSettings.usbSerialWait = params.usbSerialWait;
+ }
+
+ //Update the training values
+ trainingSettings.clientFindPartnerRetryInterval = params.clientFindPartnerRetryInterval;
+ //The trainingKey is already the same
+ trainingSettings.trainingTimeout = params.trainingTimeout;
+
+ //Update the trigger parameters
+ if (params.copyTriggers)
+ {
+ trainingSettings.copyTriggers = params.copyTriggers;
+ trainingSettings.triggerEnable = params.triggerEnable;
+ trainingSettings.triggerEnable2 = params.triggerEnable2;
+ trainingSettings.triggerWidth = params.triggerWidth;
+ trainingSettings.triggerWidthIsMultiplier = params.triggerWidthIsMultiplier;
+ }
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Server Training
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Build the server parameters packet used for training
+bool xmitDatagramTrainRadioParameters(const uint8_t * clientID)
+{
+ Settings params;
+
+ radioCallHistory[RADIO_CALL_xmitDatagramTrainRadioParameters] = millis();
+
+ //Initialize the radio parameters
+ memcpy(¶ms, &trainingSettings, sizeof(settings));
+ params.server = false;
+
+ //Add the destination (client) ID
+ memcpy(endOfTxData, clientID, UNIQUE_ID_BYTES);
+ endOfTxData += UNIQUE_ID_BYTES;
+
+ //Add the source (server) ID
+ memcpy(endOfTxData, myUniqueId, UNIQUE_ID_BYTES);
+ endOfTxData += UNIQUE_ID_BYTES;
+
+ //Add the radio parameters
+ memcpy(endOfTxData, ¶ms, sizeof(params));
+ endOfTxData += sizeof(params);
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+-----------+-----------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | | Radio | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Client ID | Server ID | Parameters | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 16 Bytes | 16 Bytes | n bytes | n Bytes |
+ +----------+---------+----------+------------+-----------+-----------+-------------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_TRAINING_PARAMS;
+ return (transmitDatagram());
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Virtual Circuit frames
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Broadcast a datagram to all of the VCs
+bool xmitVcDatagram()
+{
+ radioCallHistory[RADIO_CALL_xmitVcDatagram] = millis();
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+----------+---------+---------+----------+
+ | Optional | | Optional | Optional | | | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | DestAddr | SrcAddr | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 8 bits | 8 bits | n Bytes | n Bytes |
+ +----------+---------+----------+------------+----------+---------+---------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_DATAGRAM;
+ txControl.ackNumber = 0;
+ return (transmitDatagram());
+}
+
+//Broadcast a HEARTBEAT to all of the VCs
+bool xmitVcHeartbeat()
+{
+ return xmitVcHeartbeat(VC_IGNORE_TX, myUniqueId);
+}
+
+bool xmitVcHeartbeat(int8_t addr, uint8_t * id)
+{
+ uint32_t currentMillis = millis();
+ uint8_t * startOfData;
+ uint8_t * txData;
+
+ radioCallHistory[RADIO_CALL_xmitVcHeartbeat] = currentMillis;
+
+ startOfData = endOfTxData;
+
+ //Build the VC header
+ txData = endOfTxData;
+ *endOfTxData++ = 0; //Reserve for length
+ *endOfTxData++ = VC_BROADCAST;
+ *endOfTxData++ = addr;
+
+ //Add this radio's unique ID
+ memcpy(endOfTxData, id, UNIQUE_ID_BYTES);
+ endOfTxData += UNIQUE_ID_BYTES;
+
+ //Add the current time for timestamp synchronization
+ memcpy(endOfTxData, ¤tMillis, sizeof(currentMillis));
+ endOfTxData += sizeof(currentMillis);
+
+ //Set the length field
+ *txData = (uint8_t)(endOfTxData - txData);
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+----------+----------+---------+----------+---------+----------+
+ | Optional | | Optional | Optional | | | | | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Length | DestAddr | SrcAddr | Src ID | millis | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 8 bits | 8 bits | 8 bits | 16 Bytes | 4 Bytes | n Bytes |
+ +----------+---------+----------+------------+----------+----------+---------+----------+---------+----------+
+ */
+
+ //Verify the data length
+ if ((endOfTxData - startOfData) != VC_HEARTBEAT_BYTES)
+ waitForever("ERROR - Fix the VC_HEARTBEAT_BYTES value!");
+
+ txControl.datagramType = DATAGRAM_VC_HEARTBEAT;
+ txControl.ackNumber = 0;
+
+ //Select a random for the next heartbeat
+ setVcHeartbeatTimer();
+ return (transmitDatagram());
+}
+
+//Build the ACK frame
+bool xmitVcAckFrame(int8_t destVc)
+{
+ VC_RADIO_MESSAGE_HEADER * vcHeader;
+
+ radioCallHistory[RADIO_CALL_xmitVcAckFrame] = millis();
+
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)endOfTxData;
+ vcHeader->length = VC_RADIO_HEADER_BYTES;
+ vcHeader->destVc = destVc;
+ vcHeader->srcVc = myVc;
+ endOfTxData += VC_RADIO_HEADER_BYTES;
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+----------+---------+----------+
+ | Optional | | Optional | Optional | | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | DestAddr | SrcAddr | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 8 bits | 8 bits | n Bytes |
+ +----------+---------+----------+------------+----------+---------+----------+
+ */
+
+ //Finish building the ACK frame
+ txControl.datagramType = DATAGRAM_DATA_ACK;
+ return (transmitDatagram());
+}
+
+//Build and transmit the UNKNOWN_ACKS frame, first frame in 3-way ACKs handshake
+bool xmitVcUnknownAcks(int8_t destVc)
+{
+ VC_RADIO_MESSAGE_HEADER * vcHeader;
+
+ radioCallHistory[RADIO_CALL_xmitVcUnknownAcks] = millis();
+
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)endOfTxData;
+ vcHeader->length = VC_RADIO_HEADER_BYTES;
+ vcHeader->destVc = destVc;
+ vcHeader->srcVc = myVc;
+ endOfTxData += VC_RADIO_HEADER_BYTES;
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+----------+---------+----------+
+ | Optional | | Optional | Optional | | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | DestAddr | SrcAddr | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 8 bits | 8 bits | n Bytes |
+ +----------+---------+----------+------------+----------+---------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_VC_UNKNOWN_ACKS;
+ return (transmitDatagram());
+}
+
+//Build and transmit the SYNC_ACKS frame, second frame in 3-way ACKs handshake
+bool xmitVcSyncAcks(int8_t destVc)
+{
+ VC_RADIO_MESSAGE_HEADER * vcHeader;
+
+ radioCallHistory[RADIO_CALL_xmitVcSyncAcks] = millis();
+
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)endOfTxData;
+ vcHeader->length = VC_RADIO_HEADER_BYTES;
+ vcHeader->destVc = destVc;
+ vcHeader->srcVc = myVc;
+ endOfTxData += VC_RADIO_HEADER_BYTES;
+
+ if (settings.debugSync)
+ {
+ systemPrint(" channelNumber: ");
+ systemPrintln(channelNumber);
+ outputSerialData(true);
+ }
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+----------+---------+----------+
+ | Optional | | Optional | Optional | | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | DestAddr | SrcAddr | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 8 bits | 8 bits | n Bytes |
+ +----------+---------+----------+------------+----------+---------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_VC_SYNC_ACKS;
+ return (transmitDatagram());
+}
+
+//Build and transmit the ZERO_ACKS frame, last frame in 3-way ACKs handshake
+bool xmitVcZeroAcks(int8_t destVc)
+{
+ VC_RADIO_MESSAGE_HEADER * vcHeader;
+
+ radioCallHistory[RADIO_CALL_xmitVcZeroAcks] = millis();
+
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)endOfTxData;
+ vcHeader->length = VC_RADIO_HEADER_BYTES;
+ vcHeader->destVc = destVc;
+ vcHeader->srcVc = myVc;
+ endOfTxData += VC_RADIO_HEADER_BYTES;
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+---------+----------+------------+----------+---------+----------+
+ | Optional | | Optional | Optional | | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | DestAddr | SrcAddr | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | 8 bits | 8 bits | n Bytes |
+ +----------+---------+----------+------------+----------+---------+----------+
+ */
+
+ txControl.datagramType = DATAGRAM_VC_ZERO_ACKS;
+ return (transmitDatagram());
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Datagram reception
+//
+//Security or lack there of:
+//
+//The comments below outline the radio parameters and how they can be determined by
+//listening to the radio traffic. The required parameters are followed by one or
+//more step numbers indicating the step which determines the parameter's value. The
+//comments further describe the steps that can be taken to reduce the attack surface
+//for the LoRaSerial network.
+//
+//The following settings define the LoRaSerial radio network:
+//
+// AirSpeed - 3, 4, 5
+// AutoTune - This is receive only
+// Bandwidth - 3
+// CodingRate - 5
+// FrequencyHop - 1
+// FrequencyMax - 1
+// FrequencyMin - 1
+// MaxDwellTime - 1
+// NumberOfChannels - 1
+// PreambleLength - 4
+// SpreadFactor - 4
+// SyncWord - 4
+// TxPower
+//
+// Protocol settings:
+//
+// DataScrambling - 6
+// EnableCRC16 - 8
+// EncryptData - 7
+// EncryptionKey - 7
+// FramesToYield
+// HeartBeatTimeout - 12
+// MaxResends - 14
+// NetID - 9
+// OperatingMode - 10, 11
+// Server - 10, 11
+// VerifyRxNetID - 9
+//
+//Attempting to attack a network of LoRaSerial radios would be done with the following
+//steps:
+//
+// 1. Locate the frequencies that the network is using
+// a. Listen for traffic on a specific channel to determine if the network is using
+// that channel
+// b. Repeat across all of the channels in the available frequency band
+// 2. Once the frequencies are identified, attempt to determine the channel sequence
+// by monitoring when traffic occurs on each of the identified frequencies, this
+// allows the attacker to construct the hop table for the network
+// 3. Look at the bandwidth utilized by the radio network. The signal for each
+// symbol is a ramp that spans the bandwidth selected for use
+// 4. Using a receiver that uses the opposite ramp to generate the sub frequencies
+// within the bandwidth to decode the symbols. By monitoring the network traffic
+// it is possible to determine the spreadfactor since there are 2^SF sub frequencies
+// that will be used within the bandwidth
+// 5. Now that the spread factor is known, the next step is to determine the coding
+// rate used for forward error correction. Here 4 data bits are converted into
+// between 5 to 8 bits in the transmitted frame
+// 6. Look at the signal for multiple transmissions, does this signal have a DC offset?
+// The data scrambling setting is false if a DC offset is present, or is true when
+// no DC offset is present
+// 7. Next step is breaking the encryption key
+// 8. After the encryption key is obtained, it is possible determine if the link is
+// using software CRC by computing the CRC-16 value on the first n-2 bytes and
+// comparing that with the last 2 bytes
+// 9. Determine if the link is using a network ID value, by checking the first byte
+// in each of the transmitted frames
+// 10. Determine if the virtual circuit header is contained in the transmitted frames
+// 11. Determine which set of data frames are being transmitted
+// 12. Determine the maximum interval between HEARTBEAT frames to roughly determine
+// the HeartbeatTimeout value
+// 13. Look for HEARTBEAT frames and FIND_PARTNER frames. A FIND_PARTNER frame
+// is sent following a link failure which occurs after three HEARTBEAT timeout
+// periods.
+// 14. The MaxResends value can be estimated by the maximum number of data
+// retransmissions done prior to the link failure. A large number of link
+// failures will need to be collected from a very radio near the network.
+//
+//How do you prevent the attacks on a LoRaSerial radio network:
+//
+// 1. Don't advertize the network. Reduce the TxPower value to the minimum needed
+// to successfully operate the network
+//
+// 2. Encrypt the data on the network. Don't use the factory default encryption key.
+// Select a new encryption key and and train all of the radios in the network with
+// this key. This will prevent attacks from any groups that are not able to break
+// the encryption. However the radio network is vulnerable to well funded or
+// dedicated groups that are able to break the encryption.
+//
+// 3. Change the encryption key. When another network is using the same encryption key
+// and same network ID traffic from the other network is likely to be received.
+// Selecting another encryption key will avoid this behavior. Also the encryption
+// key may be tested by setting a radio to MODE_MULTIPOINT, disabling VerifyRxNetID
+// and disabling EnableCRC16. Both settings of DataScrambling will need to be tested.
+//
+// 4. Use a network ID. This won't prevent attacks, but it prevents the reception
+// of frames from other networks use the same encryption key.
+//
+// 5. Use software CRC-16. This won't prevent attacks but will eliminate most
+// frames from networks using the same encryption key that don't use a network
+// ID. Occasionally, when they get lucky, our network ID matches the first byte
+// of their transmitted frame. The software CRC-16 will most likely cause this
+// frame to be discarded.
+//
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Determine the type of datagram received
+PacketType rcvDatagram()
+{
+ uint8_t ackNumber;
+ PacketType datagramType;
+ uint8_t receivedNetID;
+ CONTROL_U8 rxControl;
+ VIRTUAL_CIRCUIT * vc;
+ VC_RADIO_MESSAGE_HEADER * vcHeader;
+
+ radioCallHistory[RADIO_CALL_rcvDatagram] = millis();
+
+ //Acknowledge the receive interrupt
+ transactionComplete = false;
+
+ //Save the receive time
+ rcvTimeMillis = millis();
+
+ //Get the IRQ flags
+ irqFlags = radio.getIRQFlags();
+
+ //Get the received datagram
+ framesReceived++;
+ int state = radio.readData(incomingBuffer, MAX_PACKET_SIZE);
+
+ printPacketQuality(); //Display the RSSI, SNR and frequency error values
+
+ if (state == RADIOLIB_ERR_NONE)
+ {
+ rxSuccessMillis = rcvTimeMillis;
+ triggerEvent(TRIGGER_RX_SPI_DONE);
+ rssi = radio.getRSSI();
+ }
+ else
+ {
+ rxFailureMillis = rcvTimeMillis;
+ rxFailureState = state;
+ if (state == RADIOLIB_ERR_CRC_MISMATCH)
+ {
+ if (settings.debug || settings.debugDatagrams || settings.debugReceive)
+ {
+ systemPrintln("Receive CRC error!");
+ outputSerialData(true);
+ }
+ badCrc++;
+ returnToReceiving(); //Return to listening
+ return (DATAGRAM_CRC_ERROR);
+ }
+ else
+ {
+ if (settings.debug || settings.debugDatagrams || settings.debugReceive)
+ {
+ systemPrint("Receive error: ");
+ systemPrintln(state);
+ outputSerialData(true);
+ }
+ returnToReceiving(); //Return to listening
+ badFrames++;
+ return (DATAGRAM_BAD);
+ }
+ }
+
+ rxDataBytes = radio.getPacketLength();
+ packetLength = rxDataBytes; //Total bytes received, used for calculating clock sync times in multi-point mode
+
+ returnToReceiving(); //Immediately begin listening while we process new data
+
+ rxData = incomingBuffer;
+ vc = &virtualCircuitList[0];
+ vcHeader = NULL;
+
+ /*
+ |<--------------------------- rxDataBytes --------------------------->|
+ | |
+ +----------+---------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+---------+----------+------------+-------------+----------+
+ ^
+ |
+ '---- rxData
+ */
+
+ //Display the received data bytes
+ if (settings.printRfData || settings.debugReceive)
+ {
+ systemPrintln("----------");
+ systemPrintTimestamp();
+ systemPrint("RX: ");
+ systemPrint((settings.dataScrambling || settings.encryptData) ? "Encrypted " : "Unencrypted ");
+ systemPrint("Frame ");
+ systemPrint(rxDataBytes);
+ systemPrint(" (0x");
+ systemPrint(rxDataBytes, HEX);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printRfData && rxDataBytes)
+ dumpBuffer(incomingBuffer, rxDataBytes);
+ outputSerialData(true);
+ }
+
+ if (settings.dataScrambling == true)
+ radioComputeWhitening(incomingBuffer, rxDataBytes);
+
+ if (settings.encryptData == true)
+ {
+ decryptBuffer(incomingBuffer, rxDataBytes);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ if (settings.debugReceive)
+ {
+ systemPrint("in: ");
+ dumpBufferRaw(incomingBuffer, 14); //Print only the first few bytes when debugging packets
+ }
+
+ //Display the received data bytes
+ if ((settings.dataScrambling || settings.encryptData)
+ && (settings.printRfData || settings.debugReceive))
+ {
+ systemPrintTimestamp();
+ systemPrint("RX: Unencrypted Frame ");
+ systemPrint(rxDataBytes);
+ systemPrint(" (0x");
+ systemPrint(rxDataBytes, HEX);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printRfData && rxDataBytes)
+ dumpBuffer(incomingBuffer, rxDataBytes);
+ outputSerialData(true);
+ }
+
+ //All packets must include the control header
+ if (rxDataBytes < minDatagramSize)
+ {
+ //Display the packet contents
+ if (settings.printPktData || settings.debugDatagrams || settings.debugReceive)
+ {
+ systemPrintTimestamp();
+ systemPrint("RX: Bad Frame ");
+ systemPrint(rxDataBytes);
+ systemPrint(" (0x");
+ systemPrint(rxDataBytes, HEX);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printRfData && rxDataBytes)
+ dumpBuffer(incomingBuffer, rxDataBytes);
+ outputSerialData(true);
+ }
+ badFrames++;
+ return (DATAGRAM_BAD);
+ }
+
+ /*
+ |<---------------------- rxDataBytes ---------------------->|
+ | |
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ ^
+ |
+ '---- rxData
+ */
+
+ //Verify the netID if necessary
+ if ((settings.operatingMode == MODE_POINT_TO_POINT) || settings.verifyRxNetID)
+ {
+ receivedNetID = *rxData++;
+ if (receivedNetID != settings.netID)
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("RX: NetID ");
+ systemPrint(receivedNetID);
+ systemPrint(" (0x");
+ systemPrint(receivedNetID, HEX);
+ systemPrint(")");
+ if (receivedNetID != settings.netID)
+ {
+ systemPrint(" expecting ");
+ systemPrint(settings.netID);
+ }
+ systemPrintln();
+ outputSerialData(true);
+ }
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.debugReceive && settings.printPktData && rxDataBytes)
+ dumpBuffer(incomingBuffer, rxDataBytes);
+ outputSerialData(true);
+ netIdMismatch++;
+ return (DATAGRAM_NETID_MISMATCH);
+ }
+ }
+
+ //Process the trailer
+ petWDT();
+ if (settings.enableCRC16)
+ {
+ uint16_t crc;
+ uint8_t * data;
+
+ //Compute the CRC-16 value
+ crc = 0xffff;
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ for (data = incomingBuffer; data < &incomingBuffer[rxDataBytes - 2]; data++)
+ crc = crc16Table[*data ^ (uint8_t)(crc >> (16 - 8))] ^ (crc << 8);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ if ((incomingBuffer[rxDataBytes - 2] != (crc >> 8))
+ && (incomingBuffer[rxDataBytes - 1] != (crc & 0xff)))
+ {
+ //Display the packet contents
+ if (settings.printPktData || settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("RX: Bad CRC-16, received 0x");
+ systemPrint(incomingBuffer[rxDataBytes - 2], HEX);
+ systemPrint(incomingBuffer[rxDataBytes - 1], HEX);
+ systemPrint(" expected 0x");
+ systemPrintln(crc, HEX);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printRfData && rxDataBytes)
+ dumpBuffer(incomingBuffer, rxDataBytes);
+ outputSerialData(true);
+ }
+ badCrc++;
+ return (DATAGRAM_CRC_ERROR);
+ }
+ }
+
+ /*
+ |<--------------------------- rxDataBytes ---------------------------->|
+ | |
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ ^
+ |
+ '---- rxData
+ */
+
+ //Get the control byte
+ rxControl = *((CONTROL_U8 *)rxData++);
+ datagramType = rxControl.datagramType;
+ ackNumber = rxControl.ackNumber;
+
+ if (settings.debugReceive)
+ printControl(*((uint8_t *)&rxControl));
+
+ if (datagramType >= MAX_DATAGRAM_TYPE)
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("RX: Invalid datagram type ");
+ systemPrintln(datagramType);
+ outputSerialData(true);
+ }
+ badFrames++;
+ return (DATAGRAM_BAD);
+ }
+
+ //Ignore this frame is requested
+ if (rxControl.ignoreFrame)
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("RX: Ignore this ");
+ systemPrintln(datagramType);
+ outputSerialData(true);
+ }
+ badFrames++;
+ return (DATAGRAM_BAD);
+ }
+
+ //Display the CRC
+ if (settings.enableCRC16 && settings.debugReceive)
+ {
+ systemPrintTimestamp();
+ systemPrint(" CRC-16: 0x");
+ systemPrint(incomingBuffer[rxDataBytes - 2], HEX);
+ systemPrintln(incomingBuffer[rxDataBytes - 1], HEX);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ /*
+ |<--------------------------- rxDataBytes ---------------------------->|
+ | |
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ ^
+ |
+ '---- rxData
+ */
+ //If hopping is enabled, sync data is located next within the header
+ if (settings.frequencyHop == true)
+ {
+ memcpy(&msToNextHopRemote, rxData, sizeof(msToNextHopRemote));
+ rxData += sizeof(msToNextHopRemote);
+
+ //Display the channel timer
+ if (settings.debugReceive)
+ {
+ systemPrint(" Channel Timer(ms): ");
+ systemPrintln(msToNextHopRemote);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ }
+
+ /*
+ |<--------------------------- rxDataBytes ---------------------------->|
+ | |
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ ^
+ |
+ '---- rxData
+ */
+
+ //Get the spread factor 6 length
+ if (settings.radioSpreadFactor == 6)
+ {
+ if (rxDataBytes >= (*rxData + minDatagramSize))
+ rxDataBytes = *rxData++;
+ else
+ {
+ if (settings.debugReceive)
+ {
+ systemPrintTimestamp();
+ systemPrint("Invalid SF6 length, received SF6 length ");
+ systemPrint(*rxData);
+ systemPrint(" > ");
+ systemPrint((int)rxDataBytes - minDatagramSize);
+ systemPrintln(" received bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ badFrames++;
+ return (DATAGRAM_BAD);
+ }
+ if (settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint(" SF6 Length: ");
+ systemPrintln(rxDataBytes);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ }
+ else
+ rxDataBytes -= minDatagramSize;
+
+ //Get the Virtual-Circuit header
+ rxVcData = rxData;
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ //Verify that the virtual circuit header is present
+ if (rxDataBytes < 3)
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Missing VC header bytes, received only ");
+ systemPrint(rxDataBytes);
+ systemPrintln(" bytes, expecting at least 3 bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ badFrames++;
+ return DATAGRAM_BAD;
+ }
+
+ //Parse the virtual circuit header
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)rxData;
+ rxDestVc = vcHeader->destVc;
+ rxSrcVc = vcHeader->srcVc;
+ rxVcData = &rxData[3];
+
+ //Display the virtual circuit header
+ if (settings.debugReceive)
+ {
+ systemPrintTimestamp();
+ systemPrint(" VC Length: ");
+ systemPrintln(vcHeader->length);
+ systemPrint(" DestAddr: ");
+ if (rxDestVc == VC_BROADCAST)
+ systemPrintln("Broadcast");
+ else
+ systemPrintln(rxDestVc);
+ systemPrint(" SrcAddr: ");
+ if (rxSrcVc == VC_UNASSIGNED)
+ systemPrintln("Unassigned");
+ else
+ systemPrintln(rxSrcVc);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ //Validate the source VC
+ vc = NULL;
+ if (rxSrcVc != VC_UNASSIGNED)
+ {
+ if ((uint8_t)rxSrcVc >= MAX_VC)
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Invalid source VC: ");
+ systemPrintln(rxSrcVc);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ if (settings.printRfData && rxDataBytes)
+ dumpBuffer(incomingBuffer, rxDataBytes);
+ outputSerialData(true);
+ }
+ badFrames++;
+ return DATAGRAM_BAD;
+ }
+ vc = &virtualCircuitList[rxSrcVc];
+ }
+
+ //Validate the length
+ if (vcHeader->length != rxDataBytes)
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Invalid VC length, received ");
+ systemPrint(vcHeader->length);
+ systemPrint(" expecting ");
+ systemPrintln(rxDataBytes);
+ outputSerialData(true);
+ }
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ if (vc)
+ vc->badLength++;
+ badFrames++;
+ return DATAGRAM_BAD;
+ }
+
+ //Validate the destination VC
+ if ((rxDestVc != VC_BROADCAST) && (rxDestVc != myVc))
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Not my VC: ");
+ systemPrintln(rxDestVc);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ if (settings.printPktData && rxDataBytes)
+ dumpBuffer(incomingBuffer, rxDataBytes);
+ outputSerialData(true);
+ }
+ return DATAGRAM_NOT_MINE;
+ }
+ }
+
+ //Verify the packet number last so that the expected datagram or ACK number can be updated
+ if (vc && (settings.operatingMode != MODE_MULTIPOINT))
+ {
+ switch (datagramType)
+ {
+ default:
+ break;
+
+ case DATAGRAM_DATA_ACK:
+ if (ackNumber != vc->txAckNumber)
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Invalid ACK number, received ");
+ systemPrint(ackNumber);
+ systemPrint(" expecting ");
+ systemPrintln(vc->txAckNumber);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ badFrames++;
+ return (DATAGRAM_BAD);
+ }
+
+ //Set the next TX ACK number
+ if (settings.printAckNumbers)
+ {
+ systemPrint("txAckNumber: ");
+ systemPrint(vc->txAckNumber);
+ systemPrint(" --> ");
+ }
+ vc->txAckNumber = (vc->txAckNumber + 1) & 3;
+ if (settings.printAckNumbers)
+ {
+ systemPrintln(vc->txAckNumber);
+ outputSerialData(true);
+ }
+
+ //Remember when the last datagram was received
+ lastRxDatagram = rcvTimeMillis;
+ break;
+
+ case DATAGRAM_HEARTBEAT:
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ break;
+ datagramType = validateDatagram(vc, datagramType, ackNumber, rxDataBytes);
+ if (datagramType != DATAGRAM_HEARTBEAT)
+ return datagramType;
+ lastRxDatagram = rcvTimeMillis;
+ break;
+
+ case DATAGRAM_REMOTE_COMMAND:
+ datagramType = validateDatagram(vc, datagramType, ackNumber, sizeof(commandRXBuffer)
+ - availableRXCommandBytes());
+ if (datagramType != DATAGRAM_REMOTE_COMMAND)
+ return datagramType;
+ lastRxDatagram = rcvTimeMillis;
+ break;
+
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ datagramType = validateDatagram(vc, datagramType, ackNumber, sizeof(serialTransmitBuffer)
+ - availableTXBytes());
+ if (datagramType != DATAGRAM_REMOTE_COMMAND_RESPONSE)
+ return datagramType;
+ lastRxDatagram = rcvTimeMillis;
+ break;
+
+ case DATAGRAM_DATA:
+ datagramType = validateDatagram(vc, datagramType, ackNumber, sizeof(serialTransmitBuffer)
+ - availableTXBytes());
+ if (datagramType != DATAGRAM_DATA)
+ return datagramType;
+ lastRxDatagram = rcvTimeMillis;
+ vc->messagesReceived++;
+ break;
+ }
+
+ //Account for this frame
+ vc->framesReceived++;
+ }
+
+ //If packet is good, check requestYield bit
+ //If bit is set, this radio supresses transmissions for X number of frames
+ //Datagram sender can both set and clear yield requests
+ requestYield = rxControl.requestYield;
+ if (requestYield)
+ {
+ triggerEvent(TRIGGER_RX_YIELD);
+ yieldTimerStart = millis();
+ }
+
+ /*
+ |<-- rxDataBytes -->|
+ | |
+ +----------+----------+----------+------------+------ ... ------+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------------+----------+
+ ^
+ |
+ '---- rxData
+ */
+
+ //Display the packet contents
+ if (settings.printPktData || settings.debugReceive)
+ {
+ systemPrintTimestamp();
+ systemPrint("RX: Datagram ");
+ systemPrint(rxDataBytes);
+ systemPrint(" (0x");
+ systemPrint(rxDataBytes, HEX);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printPktData && rxDataBytes)
+ dumpBuffer(rxData, rxDataBytes);
+ }
+
+ //Display the datagram type
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("RX: ");
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ systemPrint((uint8_t)((rxDestVc == VC_BROADCAST) ? rxDestVc : rxDestVc & VCAB_NUMBER_MASK));
+ systemPrint(" <-- ");
+ systemPrint((uint8_t)((rxSrcVc == VC_UNASSIGNED) ? rxSrcVc : rxSrcVc & VCAB_NUMBER_MASK));
+ systemWrite(' ');
+ }
+ systemPrint(radioDatagramType[datagramType]);
+ switch (datagramType)
+ {
+ default:
+ systemPrintln();
+ break;
+
+ case DATAGRAM_DATA:
+ case DATAGRAM_DATA_ACK:
+ case DATAGRAM_REMOTE_COMMAND:
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ case DATAGRAM_HEARTBEAT:
+ if (settings.operatingMode != MODE_MULTIPOINT)
+ {
+ systemPrint(" (");
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ systemPrint("VC ");
+ systemPrint("ACK #");
+ systemPrint(ackNumber);
+ systemPrint(")");
+
+ if (rxControl.requestYield)
+ systemPrint(" (Y)");
+ }
+ systemPrintln();
+ break;
+ }
+ outputSerialData(true);
+ }
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ //Process the packet
+ datagramsReceived++;
+ linkDownTimer = millis();
+
+ //Blink the RX LED
+ blinkRadioRxLed(true);
+ return datagramType;
+}
+
+//Determine what PacketType value should be returned to the receiving code, options are:
+// * Received datagramType
+// * DATAGRAM_DUPLICATE
+// * DATAGRAM_BAD
+PacketType validateDatagram(VIRTUAL_CIRCUIT * vc, PacketType datagramType, uint8_t ackNumber, uint16_t freeBytes)
+{
+ if (ackNumber != vc->rmtTxAckNumber)
+ {
+ //Determine if this is a duplicate datagram
+ if (ackNumber == ((vc->rmtTxAckNumber - 1) & 3))
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Duplicate datagram received, ACK ");
+ systemPrintln(ackNumber);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ linkDownTimer = millis();
+ duplicateFrames++;
+ return DATAGRAM_DUPLICATE;
+ }
+
+ //Not a duplicate
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Invalid datagram number, received ");
+ systemPrint(ackNumber);
+ systemPrint(" expecting ");
+ systemPrintln(vc->rmtTxAckNumber);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ badFrames++;
+ return DATAGRAM_BAD;
+ }
+
+ //Verify that there is sufficient space in the serialTransmitBuffer
+ if (inCommandMode || ((sizeof(serialTransmitBuffer) - availableTXBytes()) < rxDataBytes))
+ {
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrintln("Insufficient space in the serialTransmitBuffer");
+ }
+ insufficientSpace++;
+
+ //Apply back pressure to the other radio by dropping this packet and
+ //forcing the other radio to retransmit the packet.
+ badFrames++;
+ return DATAGRAM_BAD;
+ }
+
+ //Receive this data packet and set the next expected datagram number
+ if (settings.printAckNumbers)
+ {
+ systemPrint("rxAckNumber: ");
+ systemPrint(vc->rxAckNumber);
+ systemPrint(" --> ");
+ }
+ vc->rxAckNumber = vc->rmtTxAckNumber;
+ if (settings.printAckNumbers)
+ {
+ systemPrintln(vc->rxAckNumber);
+ systemPrint("rmtTxAckNumber: ");
+ systemPrint(vc->rmtTxAckNumber);
+ systemPrint(" --> ");
+ }
+ vc->rmtTxAckNumber = (vc->rmtTxAckNumber + 1) & 3;
+ if (settings.printAckNumbers)
+ {
+ systemPrintln(vc->rmtTxAckNumber);
+ outputSerialData(true);
+ }
+ return datagramType;
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Datagram transmission
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Push the outgoing packet to the air
+//Returns false if we could not start tranmission due to packet received or RX in process
+bool transmitDatagram()
+{
+ uint8_t control;
+ uint8_t * header;
+ uint8_t length;
+ int8_t srcVc;
+ uint8_t * vcData;
+ VIRTUAL_CIRCUIT * vc;
+ VC_RADIO_MESSAGE_HEADER * vcHeader;
+
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ //Remove some jitter by getting this time after the hopChannel
+ txDatagramMicros = micros();
+ radioCallHistory[RADIO_CALL_transmitDatagram] = millis();
+
+ //Parse the virtual circuit header
+ vc = &virtualCircuitList[0];
+ vcHeader = NULL;
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ vc = NULL;
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)&outgoingPacket[headerBytes];
+ txDestVc = vcHeader->destVc;
+ srcVc = vcHeader->srcVc;
+ if ((uint8_t)vcHeader->destVc <= MAX_VC)
+ {
+ vc = &virtualCircuitList[txDestVc];
+ vc->messagesSent++;
+ }
+ vcData = (uint8_t *)&vcHeader[1];
+ }
+
+ //Determine the packet size
+ datagramsSent++;
+ txDatagramSize = endOfTxData - outgoingPacket;
+ length = txDatagramSize - headerBytes;
+
+ //Select the ACK number
+ if (txControl.datagramType == DATAGRAM_DATA_ACK)
+ txControl.ackNumber = vc->rxAckNumber;
+ else
+ txControl.ackNumber = vc->txAckNumber;
+
+ //If we are ACK'ing data, and we have data to send ourselves, request that
+ //the sender yield to give us an opportunity to send our data
+ if ((txControl.datagramType == DATAGRAM_DATA_ACK) && availableRadioTXBytes())
+ {
+ triggerEvent(TRIGGER_TX_YIELD);
+ txControl.requestYield = 1;
+ }
+ else
+ txControl.requestYield = 0;
+
+ //Print debug info as needed
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: ");
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ systemPrint((uint8_t)((srcVc == VC_UNASSIGNED) ? srcVc : srcVc & VCAB_NUMBER_MASK));
+ systemPrint(" --> ");
+ systemPrint((uint8_t)((txDestVc == VC_BROADCAST) ? txDestVc : txDestVc & VCAB_NUMBER_MASK));
+ systemWrite(' ');
+ }
+ systemPrint(radioDatagramType[txControl.datagramType]);
+ switch (txControl.datagramType)
+ {
+ default:
+ systemPrintln();
+ break;
+
+ case DATAGRAM_DATA:
+ case DATAGRAM_DATA_ACK:
+ case DATAGRAM_REMOTE_COMMAND:
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ case DATAGRAM_HEARTBEAT:
+ if (settings.operatingMode != MODE_MULTIPOINT)
+ {
+ systemPrint(" (");
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ systemPrint("VC ");
+ systemPrint("ACK #");
+ systemPrint(txControl.ackNumber);
+ systemPrint(")");
+
+ if (txControl.requestYield)
+ systemPrint(" (requestYield)");
+ }
+ systemPrintln();
+ break;
+ }
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ | | |
+ | |<- Length -->|
+ |<-------------------- txDatagramSize --------------------->|
+ */
+
+ //Display the packet contents
+ if (settings.printPktData || settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Datagram ");
+ systemPrint(length);
+ systemPrint(" (0x");
+ systemPrint(length, HEX);
+ systemPrintln(") bytes");
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printPktData)
+ dumpBuffer(&endOfTxData[-length], length);
+ outputSerialData(true);
+ }
+
+ //Build the datagram header
+ header = outgoingPacket;
+ if (headerBytes && settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Header");
+ systemPrint(headerBytes);
+ systemPrint(" (0x");
+ systemPrint(headerBytes);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ /*
+ .------ Header endOfTxData ---.
+ | |
+ V V
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ | | |
+ | |<- Length -->|
+ |<-------------------- txDatagramSize --------------------->|
+ */
+
+ //Add the netID if necessary
+ if ((settings.operatingMode == MODE_POINT_TO_POINT) || settings.verifyRxNetID)
+ {
+ *header++ = settings.netID;
+
+ //Display the netID value
+ if (settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint(" NetID: ");
+ systemPrint(settings.netID);
+ systemPrint(" (0x");
+ systemPrint(settings.netID, HEX);
+ systemPrintln(")");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ }
+ }
+
+ //Add the control byte
+ control = *(uint8_t *)&txControl;
+ *header++ = control;
+
+ /*
+ .------ Header endOfTxData ---.
+ | |
+ V V
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ | | |
+ | |<- Length -->|
+ |<-------------------- txDatagramSize --------------------->|
+ */
+
+ //Display the control value
+ if (settings.debugTransmit)
+ printControl(control);
+
+ //Add the clock sync information
+ if (settings.frequencyHop == true)
+ {
+ //Make sure that the transmitted msToNextHop is in the range 0 - maxDwellTime
+ if (timeToHop)
+ hopChannel();
+
+ //Measure the time to the next hop
+ triggerEvent(TRIGGER_TX_LOAD_CHANNEL_TIMER_VALUE);
+ txSetChannelTimerMicros = micros();
+ unsigned long currentMillis = millis();
+ uint16_t msToNextHop; //TX channel timer value
+ if (channelTimerMsec)
+ msToNextHop = channelTimerMsec - (currentMillis - channelTimerStart);
+ else
+ msToNextHop = settings.maxDwellTime;
+
+ //Validate this value
+ if (ENABLE_DEVELOPER && (!clockSyncReceiver))
+ {
+ if ((msToNextHop < 0) || (msToNextHop > settings.maxDwellTime))
+ {
+ int16_t channelTimer;
+ uint8_t * data;
+
+ systemPrint("TX Frame ");
+ systemPrintln(radioDatagramType[txControl.datagramType]);
+ data = outgoingPacket;
+ if ((settings.operatingMode == MODE_POINT_TO_POINT) || settings.verifyRxNetID)
+ {
+ systemPrint(" Net Id: ");
+ systemPrint(*data);
+ systemPrint(" (0x");
+ systemPrint(*data++, HEX);
+ systemPrintln(")");
+ }
+ printControl(*data++);
+ memcpy(&channelTimer, data, sizeof(channelTimer));
+ data += sizeof(channelTimer);
+ systemPrint(" Channel Timer(ms): ");
+ systemPrintln(channelTimer);
+
+ systemPrint("ERROR: Invalid msToNextHop value, ");
+ systemPrintln(msToNextHop);
+
+ //Set a valid value
+ msToNextHop = settings.maxDwellTime;
+ }
+ else if (settings.debugSync)
+ {
+ switch (txControl.datagramType)
+ {
+ case DATAGRAM_DATA_ACK:
+ case DATAGRAM_SYNC_CLOCKS:
+ systemPrint("TX msToNextHop: ");
+ systemPrint(msToNextHop);
+ systemPrintln(" mSec");
+ break;
+ }
+ }
+ } //ENABLE_DEVELOPER
+
+ //Set the time in the frame
+ memcpy(header, &msToNextHop, sizeof(msToNextHop));
+ header += sizeof(msToNextHop); //aka CHANNEL_TIMER_BYTES
+
+ if (settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint(" Channel Timer(ms): ");
+ systemPrintln(msToNextHop);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ }
+ else
+ txSetChannelTimerMicros = micros();
+
+ /*
+ Header ------. endOfTxData ---.
+ | |
+ V V
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ | | |
+ | |<- Length -->|
+ |<-------------------- txDatagramSize --------------------->|
+ */
+
+ //Add the spread factor 6 length if required
+ if (settings.radioSpreadFactor == 6)
+ {
+ *header++ = length;
+
+ //Send either a short ACK or full length packet
+ switch (txControl.datagramType)
+ {
+ default:
+ txDatagramSize = MAX_PACKET_SIZE - trailerBytes; //We're now going to transmit a full size datagram
+ break;
+
+ case DATAGRAM_FIND_PARTNER:
+ case DATAGRAM_SYNC_CLOCKS:
+ case DATAGRAM_ZERO_ACKS:
+ txDatagramSize = headerBytes + CLOCK_MILLIS_BYTES; //Short packet is 5 + 4
+ break;
+
+ case DATAGRAM_DATA_ACK:
+ txDatagramSize = headerBytes; //Short ACK packet is 5
+ break;
+ }
+
+ radio.implicitHeader(txDatagramSize); //Set header size so that hardware CRC is calculated correctly
+
+ endOfTxData = &outgoingPacket[txDatagramSize];
+ if (settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint(" SF6 Length: ");
+ systemPrintln(length);
+ systemPrint(" SF6 TX Header Size: ");
+ systemPrintln(txDatagramSize);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ }
+
+ /* endOfTxData ---.
+ Header ------. |
+ | |
+ V V
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ | | |
+ | |<- Length -->|
+ |<-------------------- txDatagramSize --------------------->|
+ */
+
+ //Verify the Virtual-Circuit length
+ if (settings.debugTransmit && (settings.operatingMode == MODE_VIRTUAL_CIRCUIT))
+ {
+ systemPrintTimestamp();
+ systemPrint(" Length: ");
+ systemPrintln(vcHeader->length);
+ systemPrint(" DestAddr: ");
+ if (txDestVc == VC_BROADCAST)
+ systemPrintln("Broadcast");
+ else
+ systemPrintln(txDestVc);
+ systemPrint(" SrcAddr: ");
+ if (srcVc == VC_UNASSIGNED)
+ systemPrintln("Unassigned");
+ else
+ systemPrintln(srcVc);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ | |
+ |<-------------------- txDatagramSize --------------------->|
+ */
+
+ //Add the datagram trailer
+ if (settings.enableCRC16)
+ {
+ uint16_t crc;
+ uint8_t * txData;
+
+ //Compute the CRC-16 value
+ crc = 0xffff;
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ for (txData = outgoingPacket; txData < endOfTxData; txData++)
+ crc = crc16Table[*txData ^ (uint8_t)(crc >> (16 - 8))] ^ (crc << 8);
+ *endOfTxData++ = (uint8_t)(crc >> 8);
+ *endOfTxData++ = (uint8_t)(crc & 0xff);
+ }
+ txDatagramSize += trailerBytes;
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ //Display the trailer
+ if (trailerBytes && settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Trailer ");
+ systemPrint(trailerBytes);
+ systemPrint(" (0x");
+ systemPrint(trailerBytes);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ //Display the CRC
+ if (settings.enableCRC16 && (settings.printPktData || settings.debugReceive))
+ {
+ systemPrintTimestamp();
+ systemPrint(" CRC-16: 0x");
+ systemPrint(endOfTxData[-2], HEX);
+ systemPrintln(endOfTxData[-1], HEX);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ }
+
+ /*
+ endOfTxData ---.
+ |
+ V
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ | |
+ |<-------------------- txDatagramSize --------------------->|
+ */
+
+ //Display the transmitted packet bytes
+ if (settings.printRfData || settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Unencrypted Frame ");
+ systemPrint(txDatagramSize);
+ systemPrint(" (0x");
+ systemPrint(txDatagramSize, HEX);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printRfData)
+ dumpBuffer(outgoingPacket, txDatagramSize);
+ outputSerialData(true);
+ }
+
+ //Print raw packet bytes before encryption
+ if (settings.debugTransmit)
+ {
+ systemPrint("out: ");
+ dumpBufferRaw(outgoingPacket, 14);
+ }
+
+ //Encrypt the datagram
+ if (settings.encryptData == true)
+ {
+ encryptBuffer(outgoingPacket, txDatagramSize);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ //Scramble the datagram
+ if (settings.dataScrambling == true)
+ radioComputeWhitening(outgoingPacket, txDatagramSize);
+
+ //Display the transmitted packet bytes
+ if ((settings.printRfData || settings.debugTransmit)
+ && (settings.encryptData || settings.dataScrambling))
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Encrypted Frame ");
+ systemPrint(txDatagramSize);
+ systemPrint(" (0x");
+ systemPrint(txDatagramSize, HEX);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printRfData)
+ dumpBuffer(outgoingPacket, txDatagramSize);
+ outputSerialData(true);
+ }
+
+ //If we are trainsmitting at high data rates the receiver is often not ready
+ //for new data. Pause for a few ms (measured with logic analyzer).
+ if (settings.txToRxUsec < 100)
+ delay(2);
+
+ //Reset the buffer data pointer for the next transmit operation
+ endOfTxData = &outgoingPacket[headerBytes];
+
+ //Transmit this datagram
+ frameSentCount = 0; //This is the first time this frame is being sent
+ return (retransmitDatagram(vc));
+}
+
+//Print the control byte value
+void printControl(uint8_t value)
+{
+ CONTROL_U8 * control = (CONTROL_U8 *)&value;
+
+ systemPrintTimestamp();
+ systemPrint(" Control: 0x");
+ systemPrintln(value, HEX);
+
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ systemPrintTimestamp();
+ systemPrint(" ACK # ");
+ systemPrintln(value & 3);
+
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ systemPrintTimestamp();
+ systemPrint(" datagramType ");
+ if (control->datagramType < MAX_DATAGRAM_TYPE)
+ systemPrintln(radioDatagramType[control->datagramType]);
+ else
+ {
+ systemPrint("Unknown ");
+ systemPrintln(control->datagramType);
+ }
+
+ if (control->requestYield)
+ {
+ systemPrintTimestamp();
+ systemPrintln(" requestYield");
+ }
+
+ if (control->ignoreFrame)
+ {
+ systemPrintTimestamp();
+ systemPrintln(" Ignore Frame");
+ }
+
+ outputSerialData(true);
+
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ petWDT();
+}
+
+//The previous transmission was not received, retransmit the datagram
+//Returns false if we could not start tranmission due to packet received or RX in process
+bool retransmitDatagram(VIRTUAL_CIRCUIT * vc)
+{
+ radioCallHistory[RADIO_CALL_retransmitDatagram] = millis();
+
+ /*
+ +----------+----------+----------+------------+--- ... ---+----------+
+ | Optional | | Optional | Optional | | Optional |
+ | NET ID | Control | C-Timer | SF6 Length | Data | Trailer |
+ | 8 bits | 8 bits | 2 bytes | 8 bits | n bytes | n Bytes |
+ +----------+----------+----------+------------+-------------+----------+
+ | |
+ |<------------------------- txDatagramSize --------------------------->|
+ */
+
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ //Display the transmitted frame bytes
+ if (frameSentCount && (settings.printRfData || settings.debugTransmit))
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Retransmit ");
+ systemPrint((settings.encryptData || settings.dataScrambling) ? "Encrypted " : "Unencrypted ");
+ systemPrint("Frame ");
+ systemPrint(txDatagramSize);
+ systemPrint(" (0x");
+ systemPrint(txDatagramSize, HEX);
+ systemPrintln(") bytes");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ if (settings.printRfData)
+ dumpBuffer(outgoingPacket, txDatagramSize);
+ outputSerialData(true);
+ }
+
+ //Transmit this frame
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ frameAirTimeUsec = calcAirTimeUsec(txDatagramSize); //Calculate frame air size while we're transmitting in the background
+
+ uint16_t responseDelay = frameAirTimeUsec / responseDelayDivisor; //Give the receiver a bit of wiggle time to respond
+
+ //Drop this datagram if the receiver is active
+ if (
+ (receiveInProcess() == true)
+ || (transactionComplete == true)
+ || (
+ //If we are in VC mode, and destination is not broadcast,
+ //and the destination circuit is offline
+ //and we are not scanning for servers
+ //then don't transmit
+ (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ && (txDestVc != VC_BROADCAST)
+ && (virtualCircuitList[txDestVc & VCAB_NUMBER_MASK].vcState == VC_STATE_LINK_DOWN)
+ && (txDestVc != VC_UNASSIGNED)
+ && (radioState != RADIO_DISCOVER_SCANNING)
+ )
+ )
+ {
+ triggerEvent(TRIGGER_TRANSMIT_CANCELED);
+ if (settings.debugReceive || settings.debugDatagrams)
+ {
+ systemPrint("TX failed: ");
+ if (transactionComplete)
+ systemPrintln("RXTC");
+ else if (receiveInProcess())
+ systemPrintln("RXIP");
+ else
+ systemPrintln("VC link down");
+ outputSerialData(true);
+ }
+ return (false); //Do not start transmit while RX is or has occured
+ }
+ else
+ {
+ //Move the data to the radio over SPI
+ int state = radio.startTransmit(outgoingPacket, txDatagramSize);
+
+ if (state == RADIOLIB_ERR_NONE)
+ {
+ if (receiveInProcess() == true)
+ {
+ //Edge case: if we have started TX, but during the SPI transaction a preamble was detected
+ //then return false. This will cause the radio to transmit, then a transactionComplete ISR will trigger.
+ //The state machine will then process what the radio receives. The received datagram will be corrupt,
+ //or it will be successful. Either way, the read will clear the RxDone bit within the SX1276.
+ triggerEvent(TRIGGER_RECEIVE_IN_PROCESS);
+ return (false);
+ }
+
+ xmitTimeMillis = millis();
+ triggerEvent(TRIGGER_TX_SPI_DONE);
+ txSuccessMillis = xmitTimeMillis;
+ frameSentCount++;
+ if (vc)
+ vc->framesSent++;
+ framesSent++;
+ if (settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: frameAirTime ");
+ systemPrint(frameAirTimeUsec);
+ systemPrintln(" uSec");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ systemPrintTimestamp();
+ systemPrint("TX: responseDelay ");
+ systemPrint(responseDelay);
+ systemPrintln(" mSec");
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+ }
+ else
+ {
+ txFailureMillis = millis();
+ txFailureState = state;
+ if (settings.debugTransmit)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Transmit error, state ");
+ systemPrintln(state);
+ outputSerialData(true);
+ }
+ }
+ }
+
+ frameAirTimeUsec += responseDelay;
+ datagramTimer = millis(); //Move timestamp even if error
+
+ //Compute the interval before a retransmission occurs in milliseconds,
+ //this value increases with each transmission
+ retransmitTimeout = random(txDataAckUsec / 1000, ((frameAirTimeUsec + txDataAckUsec) / 1000))
+ * (frameSentCount + 1) * 3 / 2;
+
+ //BLink the TX LED
+ blinkRadioTxLed(true);
+
+ return (true); //Transmission has started
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Transmit Ignored Frames
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+bool getTxTime(bool (*transmitFrame)(), uint32_t * txFrameUsec, const char * frameName)
+{
+ bool txStatus;
+ uint32_t transmitDelay;
+
+#define IGNORE_TRANSMIT_DELAY_MSEC 100
+
+ //Transmit the frame
+ transmitDelay = 0;
+ do
+ {
+ //Delay between retries
+ if (transmitDelay)
+ delay(transmitDelay);
+ transmitDelay += IGNORE_TRANSMIT_DELAY_MSEC;
+
+ //Fail transmission after 5 attempts
+ if (transmitDelay > (5 * IGNORE_TRANSMIT_DELAY_MSEC))
+ {
+ if (settings.debugSync)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX ignore ");
+ systemPrint(frameName);
+ systemPrintln(" failed!");
+ outputSerialData(true);
+ }
+ return false;
+ }
+
+ //Attempt to transmit the requested frame
+ txControl.ignoreFrame = true;
+ txStatus = transmitFrame();
+ txControl.ignoreFrame = false;
+ } while (!txStatus);
+
+ //Wait for transmit completion
+ while (!transactionComplete)
+ petWDT();
+ transactionComplete = false;
+
+ //Compute the transmit time
+ *txFrameUsec = transactionCompleteMicros - txSetChannelTimerMicros;
+ if (settings.debugSync)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX ");
+ systemPrint(frameName);
+ systemPrint(": ");
+ systemPrint(((float)*txFrameUsec) / 1000., 5);
+ systemPrintln(" mSec");
+ outputSerialData(true);
+ }
+ return true;
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Use the maximum dwell setting to start the timer that indicates when to hop channels
+void startChannelTimer()
+{
+ startChannelTimer(settings.maxDwellTime);
+}
+
+//Use the specified value to start the timer that indicates when to hop channels
+void startChannelTimer(int16_t startAmount)
+{
+ radioCallHistory[RADIO_CALL_startChannelTimer] = millis();
+
+ channelTimer.disableTimer();
+ channelTimer.setInterval_MS(startAmount, channelTimerHandler);
+ digitalWrite(pin_hop_timer, channelNumber & 1);
+ reloadChannelTimer = (startAmount != settings.maxDwellTime);
+ timeToHop = false;
+ channelTimerStart = millis(); //startChannelTimer - ISR updates value
+ channelTimerMsec = startAmount; //startChannelTimer - ISR updates value
+ channelTimer.enableTimer();
+ triggerEvent(TRIGGER_HOP_TIMER_START);
+}
+
+//Stop the channel (hop) timer
+void stopChannelTimer()
+{
+ radioCallHistory[RADIO_CALL_stopChannelTimer] = millis();
+
+ //Turn off the channel timer
+ channelTimer.disableTimer();
+ digitalWrite(pin_hop_timer, channelNumber & 1);
+ channelTimerMsec = 0; //Indicate that the timer is off
+
+ triggerEvent(TRIGGER_HOP_TIMER_STOP);
+ timeToHop = false;
+}
+
+//Given the remote unit's number of ms before its next hop,
+//adjust our own channelTimer interrupt to be synchronized with the remote unit
+void syncChannelTimer(uint32_t frameAirTimeUsec)
+{
+ int16_t adjustment;
+ uint8_t caseNumber;
+ unsigned long currentMillis;
+ int8_t delayedHopCount;
+ uint16_t frameAirTimeMsec;
+ int16_t lclHopTimeMsec;
+ int16_t msToNextHop;
+ int16_t rmtHopTimeMsec;
+
+ currentMillis = millis();
+ radioCallHistory[RADIO_CALL_syncChannelTimer] = currentMillis;
+
+ if (!clockSyncReceiver) return; //syncChannelTimer
+ if (settings.frequencyHop == false) return;
+
+ //msToNextHopRemote is obtained during rcvDatagram() and is in the range of
+ //0 - settings.maxDwellTime
+ //Validate this range
+ if (ENABLE_DEVELOPER)
+ {
+ if ((msToNextHopRemote < 0) || (msToNextHopRemote > settings.maxDwellTime))
+ {
+ int16_t channelTimer;
+ uint8_t * data;
+
+ systemPrintln("RX Frame");
+ dumpBuffer(incomingBuffer, headerBytes + rxDataBytes + trailerBytes);
+
+ data = incomingBuffer;
+ if ((settings.operatingMode == MODE_POINT_TO_POINT) || settings.verifyRxNetID)
+ {
+ systemPrint(" Net Id: ");
+ systemPrint(*data);
+ systemPrint(" (0x");
+ systemPrint(*data++, HEX);
+ systemPrintln(")");
+ }
+ printControl(*data++);
+ memcpy(&channelTimer, data, sizeof(channelTimer));
+ data += sizeof(channelTimer);
+ systemPrint(" Channel Timer(ms): ");
+ systemPrint(channelTimer);
+ systemPrint(" (0x");
+ systemPrint(channelTimer, HEX);
+ systemPrintln(")");
+
+ systemPrint("ERROR: Invalid msToNextHopRemote value, ");
+ systemPrintln(msToNextHopRemote);
+ return;
+ }
+ } //ENABLE_DEVELOPER
+
+ //----------------------------------------------------------------------
+ // Enter the critical section
+ //----------------------------------------------------------------------
+
+ //Synchronize with the hardware timer
+ channelTimer.disableTimer();
+
+ //When timeToHop is true, a hop is required to match the hops indicated by
+ //the channelTimerStart value. Delay this hop to avoid adding unaccounted
+ //delay. After the channel timer is restarted, perform this hop because
+ //the channelTimerStart value indicated that it was done. The channel
+ //timer update will add only microseconds to when the hop is done.
+ delayedHopCount = timeToHop ? 1 : 0;
+
+ //The radios are using the same frequencies since the frame was successfully
+ //received. The goal is to adjust the channel timer to fire in close proximity
+ //to the firing of the remote sysstem's channel timer. The following cases
+ //need to be identified:
+ //
+ // 1. Both systems are on the same channel
+ // Adjust channel timer value
+ // 2. Remote system is on next channel (remote hopped, local did not)
+ // Immediate local hop
+ // Adjust channel timer value
+ // 3. Remote system on previous channel (local hopped, remote did not)
+ // Extend channel timer value by maxDwellTime
+ //
+ //For low transmission rates, the transmission may have spanned multiple hops
+ //and all of the frequencies must have matched for the frame to be received
+ //successfully. Therefore the above cases hold for low frequencies as well.
+ //
+ //Compute the remote system's channel timer firing time offset in milliseconds
+ //using the channel timer value and the adjustments for transmit and receive
+ //time (time of flight)
+ frameAirTimeMsec = (frameAirTimeUsec + settings.txToRxUsec + micros() - transactionCompleteMicros) / 1000;
+ rmtHopTimeMsec = msToNextHopRemote - frameAirTimeMsec;
+
+ //Compute when the local system last hopped
+ lclHopTimeMsec = currentMillis - channelTimerStart;
+ adjustment = 0;
+
+#define REMOTE_SYSTEM_LIKELY_TO_HOP_MSEC 2
+#define CHANNEL_TIMER_SYNC_MSEC (frameAirTimeMsec + REMOTE_SYSTEM_LIKELY_TO_HOP_MSEC)
+
+ //Determine if the remote has hopped or is likely to hop very soon
+ if (rmtHopTimeMsec <= REMOTE_SYSTEM_LIKELY_TO_HOP_MSEC)
+ {
+ //Adjust the next channel timer value
+ adjustment += settings.maxDwellTime;
+
+ //Determine if the local system has just hopped
+ if (((unsigned long)lclHopTimeMsec) <= CHANNEL_TIMER_SYNC_MSEC)
+ {
+ caseNumber = 1;
+ //Case 1 above, both systems using the same channel
+ //
+ //Remote system
+ //
+ // channelTimerStart Channel timer fires
+ // |------...-------------------------------------------->|
+ // Channel Timer value |
+ // |<----------------------->|
+ // | | rmtHopTimeMsec
+ // | |<--|
+ // | |
+ // | Current Time
+ // |<------------>|<------------>|
+ // txTimeUsec rxTimeUsec |
+ // |
+ //Local system |
+ // lclHopTimeMsec |
+ // |------->|
+ // | | New timer value
+ // | |<--|----------------...-->|
+ // |----------------...-->|
+ // channelTimerStart Channel timer fires
+ //
+ //No hop is necessary
+ }
+ else
+ {
+ caseNumber = 2;
+ //Case 2 above, the local system did not hop
+ //
+ //Remote system
+ //
+ // channelTimerStart Channel timer fires Channel timer fires
+ // |...---------------------->|------...-------------------------------------------->|
+ // Channel Timer value |
+ // |<----->|
+ // | | rmtHopTimeMsec
+ // | |<--------------------|
+ // | Current Time
+ // |<------------>|<------------>|
+ // txTimeUsec rxTimeUsec |
+ // |
+ // |
+ //Local system |
+ // Computed value | New timer value
+ // |<--------------------|------...----------------------->|
+ // |
+ // lclHopTimeMsec |
+ // |------------------------------------>|
+ // |------...-------------------------------------------->|
+ // channelTimerStart Channel timer fires
+ //
+ //A hop is necessary to get to a common channel
+ delayedHopCount += 1;
+ }
+ }
+ else
+ {
+ caseNumber = 3;
+ //Case 3, both systems using the same channel
+ //
+ // channelTimerStart Channel timer fires
+ // |------...-------------------------------------------->|
+ // Channel Timer value |
+ // |<--------------------------------->|
+ // | |
+ // | rmtHopTimeMsec |
+ // | |---->|
+ // | Current Time
+ // |<------------>|<------------>|
+ // txTimeUsec rxTimeUsec |
+ // |
+ //Local system |
+ // | New timer value
+ // |---->|
+ // |------...-------------------------------------->|
+ // channelTimerStart | Channel timer fires
+ // |--------->|
+ // lclHopTimeMsec
+ //
+ //No hop is necessary
+ }
+
+ //Compute the next hop time
+ msToNextHop = rmtHopTimeMsec + adjustment;
+
+ //For low airspeeds multiple hops may occur resulting in a negative value
+ while (msToNextHop <= 0)
+ msToNextHop += settings.maxDwellTime;
+
+ //If our next hop is very nearly a dwell time, remote has hopped. Add local hop.
+ if (abs(settings.maxDwellTime - msToNextHop) <= 3)
+ delayedHopCount++;
+
+ //When the ISR fires, reload the channel timer with settings.maxDwellTime
+ reloadChannelTimer = true;
+
+ //Log the previous clock sync
+ clockSyncData[clockSyncIndex].msToNextHop = msToNextHop;
+ clockSyncData[clockSyncIndex].frameAirTimeMsec = frameAirTimeMsec;
+ clockSyncData[clockSyncIndex].msToNextHopRemote = msToNextHopRemote;
+ clockSyncData[clockSyncIndex].adjustment = adjustment;
+ clockSyncData[clockSyncIndex].delayedHopCount = delayedHopCount;
+ clockSyncData[clockSyncIndex].lclHopTimeMsec = lclHopTimeMsec;
+ clockSyncData[clockSyncIndex].timeToHop = timeToHop;
+ clockSyncIndex += 1;
+ if (clockSyncIndex >= (sizeof(clockSyncData) / sizeof(CLOCK_SYNC_DATA)) ) clockSyncIndex = 0;
+
+ //Restart the channel timer
+ timeToHop = false;
+ channelTimer.setInterval_MS(msToNextHop, channelTimerHandler); //Adjust our hardware timer to match our mate's
+ digitalWrite(pin_hop_timer, ((channelNumber + delayedHopCount) % settings.numberOfChannels) & 1);
+ channelTimerStart = currentMillis;
+ channelTimerMsec = msToNextHop; //syncChannelTimer update
+ channelTimer.enableTimer();
+
+ //----------------------------------------------------------------------
+ // Leave the critical section
+ //----------------------------------------------------------------------
+
+ //Trigger after adjustments to timer to avoid skew during debug
+ triggerEvent(TRIGGER_SYNC_CHANNEL_TIMER);
+
+ //Hop if the timer fired prior to disabling the timer, resetting the channelTimerStart value
+ if (delayedHopCount)
+ hopChannel(true, delayedHopCount);
+
+ //Display the channel sync timer calculations
+ if (settings.debugSync)
+ {
+ systemPrint("Case #");
+ systemPrint(caseNumber);
+ systemPrint(", ");
+ systemPrint(delayedHopCount);
+ systemPrint(" Hops, ");
+ systemPrint(msToNextHopRemote);
+ systemPrint(" Nxt Hop - ");
+ systemPrint(frameAirTimeMsec);
+ systemPrint(" (TX + RX)");
+ if (adjustment)
+ {
+ systemPrint(" + ");
+ systemPrint(adjustment);
+ systemPrint(" Adj");
+ }
+ systemPrint(" = ");
+ systemPrint(msToNextHop);
+ systemPrintln(" mSec");
+ }
+}
+
+//This function resets the heartbeat time and re-rolls the random time
+//Call when something has happened (ACK received, etc) where clocks have been sync'd
+//Short/long times set to avoid two radios attempting to xmit heartbeat at same time
+//Those who send an ACK have short time to next heartbeat. Those who send a heartbeat or data have long time to next heartbeat.
+void setHeartbeatShort()
+{
+ heartbeatTimer = millis();
+ radioCallHistory[RADIO_CALL_setHeartbeatShort] = heartbeatTimer;
+
+ //Ensure that the heartbeat can be received within the specified time
+ heartbeatRandomTime = settings.heartbeatTimeout;
+ heartbeatRandomTime -= (txHeartbeatUsec + txDataAckUsec + (2 * settings.txToRxUsec)) / 1000;
+ heartbeatRandomTime -= 2 * settings.overheadTime;
+
+ //Determine the transmit interval
+ heartbeatRandomTime = random(heartbeatRandomTime * 2 / 10, heartbeatRandomTime / 2); //20-50%
+}
+
+void setHeartbeatLong()
+{
+ heartbeatTimer = millis();
+ radioCallHistory[RADIO_CALL_setHeartbeatLong] = heartbeatTimer;
+
+ //Ensure that the heartbeat can be received within the specified time
+ heartbeatRandomTime = settings.heartbeatTimeout;
+ heartbeatRandomTime -= (txHeartbeatUsec + txDataAckUsec + (2 * settings.txToRxUsec)) / 1000;
+ heartbeatRandomTime -= 2 * settings.overheadTime;
+
+ heartbeatRandomTime = random(heartbeatRandomTime * 8 / 10, heartbeatRandomTime); //80-100%
+}
+
+//Only the server sends heartbeats in multipoint mode
+//But the clients still need to update their timeout
+//Not random, just the straight timeout
+void setHeartbeatMultipoint()
+{
+ heartbeatTimer = millis();
+ radioCallHistory[RADIO_CALL_setHeartbeatMultipoint] = heartbeatTimer;
+
+ //Ensure that the heartbeat can be received within the specified time
+ //MP does not use acks
+ //MP Linkup requires a HB on channel 0 so we leverage the VC technique
+ setVcHeartbeatTimer();
+}
+
+//Determine the delay for the next VC HEARTBEAT
+void setVcHeartbeatTimer()
+{
+ long deltaMillis;
+
+ heartbeatTimer = millis();
+ radioCallHistory[RADIO_CALL_setVcHeartbeatTimer] = heartbeatTimer;
+
+ /*
+ The goal of this routine is to randomize the placement of the HEARTBEAT
+ messages, allowing traffic to flow normally. However since clients are
+ waiting in channel zero (0) for a HEARTBEAT, the last couple of invervals
+ are adjusted for the server to ensure that a HEARTBEAT is sent in channel
+ zero.
+
+ dwellTime: 400 mSec
+ heartbeatTimeout: 3000 mSec
+ 50% heartbeatTimeout: 1500 mSec
+
+ channel 38 39 40 41 42 43 44 45 46 47 48 49 0 1 2
+ dwellTime | | | | | | | | | | | | | | |
+ seconds | . | . | . | . | . | . |
+ case 1: > 4.5, Use random, then remaining
+ ^--------------^^^^^^^^^^^^^^^^---------------^
+ case 2: 4.5 >= X >= 3, Use half, then second half
+ ^^^^^^^^^^^^^^^^-------^^^^^^^^--------------^
+ case 3: X < 3, Use remaining
+ ^----------------------------^
+ */
+ petWDT();
+
+ //Determine the delay before channel zero is reached
+ deltaMillis = mSecToChannelZero();
+
+ //Determine the delay before the next HEARTBEAT frame
+ if ((!settings.server) || (deltaMillis > ((3 * settings.heartbeatTimeout) / 2))
+ || (deltaMillis <= 0))
+ //Use the random interval: 50% - 100%
+ heartbeatRandomTime = random(settings.heartbeatTimeout / 2,
+ settings.heartbeatTimeout);
+ else if (deltaMillis >= settings.heartbeatTimeout)
+ heartbeatRandomTime = deltaMillis / 2;
+ else
+ heartbeatRandomTime = deltaMillis + VC_DELAY_HEARTBEAT_MSEC;
+
+ //Display the next HEARTBEAT time interval
+ if (settings.debugHeartbeat)
+ {
+ systemPrint("mSecToChannelZero: ");
+ systemPrintln(deltaMillis);
+ systemPrint("heartbeatRandomTime: ");
+ systemPrintln(heartbeatRandomTime);
+ }
+}
+
+//Conversion table from radio status value into a status string
+const I16_TO_STRING radioStatusCodes[] =
+{
+ {RADIOLIB_ERR_NONE, "RADIOLIB_ERR_NONE"},
+ {RADIOLIB_ERR_UNKNOWN, "RADIOLIB_ERR_UNKNOWN"},
+ {RADIOLIB_ERR_CHIP_NOT_FOUND, "RADIOLIB_ERR_CHIP_NOT_FOUND"},
+ {RADIOLIB_ERR_MEMORY_ALLOCATION_FAILED, "RADIOLIB_ERR_MEMORY_ALLOCATION_FAILED"},
+ {RADIOLIB_ERR_PACKET_TOO_LONG, "RADIOLIB_ERR_PACKET_TOO_LONG"},
+ {RADIOLIB_ERR_TX_TIMEOUT, "RADIOLIB_ERR_TX_TIMEOUT"},
+ {RADIOLIB_ERR_RX_TIMEOUT, "RADIOLIB_ERR_RX_TIMEOUT"},
+ {RADIOLIB_ERR_CRC_MISMATCH, "RADIOLIB_ERR_CRC_MISMATCH"},
+ {RADIOLIB_ERR_INVALID_BANDWIDTH, "RADIOLIB_ERR_INVALID_BANDWIDTH"},
+ {RADIOLIB_ERR_INVALID_SPREADING_FACTOR, "RADIOLIB_ERR_INVALID_SPREADING_FACTOR"},
+ {RADIOLIB_ERR_INVALID_CODING_RATE, "RADIOLIB_ERR_INVALID_CODING_RATE"},
+ {RADIOLIB_ERR_INVALID_BIT_RANGE, "RADIOLIB_ERR_INVALID_BIT_RANGE"},
+ {RADIOLIB_ERR_INVALID_FREQUENCY, "RADIOLIB_ERR_INVALID_FREQUENCY"},
+ {RADIOLIB_ERR_INVALID_OUTPUT_POWER, "RADIOLIB_ERR_INVALID_OUTPUT_POWER"},
+ {RADIOLIB_PREAMBLE_DETECTED, "RADIOLIB_PREAMBLE_DETECTED"},
+ {RADIOLIB_CHANNEL_FREE, "RADIOLIB_CHANNEL_FREE"},
+ {RADIOLIB_ERR_SPI_WRITE_FAILED, "RADIOLIB_ERR_SPI_WRITE_FAILED"},
+ {RADIOLIB_ERR_INVALID_CURRENT_LIMIT, "RADIOLIB_ERR_INVALID_CURRENT_LIMIT"},
+ {RADIOLIB_ERR_INVALID_PREAMBLE_LENGTH, "RADIOLIB_ERR_INVALID_PREAMBLE_LENGTH"},
+ {RADIOLIB_ERR_INVALID_GAIN, "RADIOLIB_ERR_INVALID_GAIN"},
+ {RADIOLIB_ERR_WRONG_MODEM, "RADIOLIB_ERR_WRONG_MODEM"},
+ {RADIOLIB_ERR_INVALID_NUM_SAMPLES, "RADIOLIB_ERR_INVALID_NUM_SAMPLES"},
+ {RADIOLIB_ERR_INVALID_RSSI_OFFSET, "RADIOLIB_ERR_INVALID_RSSI_OFFSET"},
+ {RADIOLIB_ERR_INVALID_ENCODING, "RADIOLIB_ERR_INVALID_ENCODING"},
+ {RADIOLIB_ERR_LORA_HEADER_DAMAGED, "RADIOLIB_ERR_LORA_HEADER_DAMAGED"},
+};
+
+//Return the status string matching the status value, return NULL if not found
+const char * getRadioStatusCode(int status)
+{
+ for (int index = 0; index < sizeof(radioStatusCodes) / sizeof(radioStatusCodes[0]); index++)
+ {
+ if (radioStatusCodes[index].value == status)
+ return radioStatusCodes[index].string;
+ }
+ return NULL;
+}
+
+//Conversion table from radio call value into a name string
+const I16_TO_STRING radioCallName[] =
+{
+ {RADIO_CALL_configureRadio, "configureRadio"},
+ {RADIO_CALL_setRadioFrequency, "setRadioFrequency"},
+ {RADIO_CALL_returnToReceiving, "returnToReceiving"},
+ {RADIO_CALL_calcAirTimeUsec, "calcAirTimeUsec"},
+ {RADIO_CALL_xmitDatagramP2PFindPartner, "xmitDatagramP2PFindPartner"},
+ {RADIO_CALL_xmitDatagramP2PSyncClocks, "xmitDatagramP2PSyncClocks"},
+ {RADIO_CALL_xmitDatagramP2PZeroAcks, "xmitDatagramP2PZeroAcks"},
+ {RADIO_CALL_xmitDatagramP2PCommand, "xmitDatagramP2PCommand"},
+ {RADIO_CALL_xmitDatagramP2PCommandResponse, "xmitDatagramP2PCommandResponse"},
+ {RADIO_CALL_xmitDatagramP2PData, "xmitDatagramP2PData"},
+ {RADIO_CALL_xmitDatagramP2PHeartbeat, "xmitDatagramP2PHeartbeat"},
+ {RADIO_CALL_xmitDatagramP2PAck, "xmitDatagramP2PAck"},
+ {RADIO_CALL_xmitDatagramMpData, "xmitDatagramMpData"},
+ {RADIO_CALL_xmitDatagramMpHeartbeat, "xmitDatagramMpHeartbeat"},
+ {RADIO_CALL_xmitDatagramTrainingFindPartner, "xmitDatagramTrainingFindPartner"},
+ {RADIO_CALL_xmitDatagramTrainingAck, "xmitDatagramTrainingAck"},
+ {RADIO_CALL_xmitDatagramTrainRadioParameters, "xmitDatagramTrainRadioParameters"},
+ {RADIO_CALL_xmitVcDatagram, "xmitVcDatagram"},
+ {RADIO_CALL_xmitVcHeartbeat, "xmitVcHeartbeat"},
+ {RADIO_CALL_xmitVcAckFrame, "xmitVcAckFrame"},
+ {RADIO_CALL_xmitVcUnknownAcks, "xmitVcUpdateAcks"},
+ {RADIO_CALL_xmitVcSyncAcks, "xmitVcSyncAcks"},
+ {RADIO_CALL_xmitVcZeroAcks, "xmitVcZeroAcks"},
+ {RADIO_CALL_rcvDatagram, "rcvDatagram"},
+ {RADIO_CALL_transmitDatagram, "transmitDatagram"},
+ {RADIO_CALL_retransmitDatagram, "retransmitDatagram"},
+ {RADIO_CALL_startChannelTimer, "startChannelTimer"},
+ {RADIO_CALL_stopChannelTimer, "stopChannelTimer"},
+ {RADIO_CALL_syncChannelTimer, "syncChannelTimer"},
+ {RADIO_CALL_setHeartbeatShort, "setHeartbeatShort"},
+ {RADIO_CALL_setHeartbeatLong, "setHeartbeatLong"},
+ {RADIO_CALL_setHeartbeatMultipoint, "setHeartbeatMultipoint"},
+ {RADIO_CALL_setVcHeartbeatTimer, "setVcHeartbeatTimer"},
+ {RADIO_CALL_hopChannel, "hopChannel"},
+
+ //Insert new values before this line
+ {RADIO_CALL_hopISR, "hopISR"},
+ {RADIO_CALL_transactionCompleteISR, "transactionCompleteISR"},
+ {RADIO_CALL_channelTimerHandler, "channelTimerHandler"},
+#ifdef RADIOLIB_LOW_LEVEL
+ {RADIO_CALL_readSX1276Register, "readSX1276Register"},
+ {RADIO_CALL_printSX1276Registers, "printSX1276Registers"},
+#endif //RADIOLIB_LOW_LEVEL
+};
+
+//Verify the RADIO_CALLS enum against the radioCallName
+const char * verifyRadioCallNames()
+{
+ bool valid;
+
+ valid = ((sizeof(radioCallName) / sizeof(radioCallName[0])) == RADIO_CALL_MAX);
+ if (!valid)
+ return "ERROR - Please update the radioCallName";
+ return NULL;
+}
+
+//Convert a radio call value into a string, return NULL if not found
+const char * getRadioCall(uint8_t radioCall)
+{
+ for (int index = 0; index < sizeof(radioCallName) / sizeof(radioCallName[0]); index++)
+ {
+ if (radioCallName[index].value == radioCall)
+ return radioCallName[index].string;
+ }
+ return NULL;
+}
+
+//Display the radio call history
+void displayRadioCallHistory()
+{
+ uint8_t index;
+ uint8_t sortOrder[RADIO_CALL_MAX];
+ const char * string;
+ uint8_t temp;
+
+ //Set the default sort order
+ petWDT();
+ for (index = 0; index < RADIO_CALL_MAX; index++)
+ sortOrder[index] = index;
+
+ //Perform a bubble sort
+ for (index = 0; index < RADIO_CALL_MAX; index++)
+ for (int x = index + 1; x < RADIO_CALL_MAX; x++)
+ if (radioCallHistory[sortOrder[index]] > radioCallHistory[sortOrder[x]])
+ {
+ temp = sortOrder[index];
+ sortOrder[index] = sortOrder[x];
+ sortOrder[x] = temp;
+ }
+
+ //Display the radio call history
+ for (index = 0; index < RADIO_CALL_MAX; index++)
+ if (radioCallHistory[sortOrder[index]])
+ {
+ systemPrint(" ");
+ systemPrintTimestamp(radioCallHistory[sortOrder[index]] + timestampOffset);
+ string = getRadioCall(sortOrder[index]);
+ if (string)
+ {
+ systemPrint(": ");
+ systemPrint(string);
+ }
+ systemPrintln();
+ }
+ petWDT();
+}
+
+//Read from radio to clear receiveInProcess bits
+void dummyRead()
+{
+ triggerEvent(TRIGGER_DUMMY_READ);
+ systemPrintln("Dummy read");
+
+ int state = radio.readData(incomingBuffer, MAX_PACKET_SIZE);
+
+ if (state != RADIOLIB_ERR_NONE)
+ {
+ if (settings.debug || settings.debugDatagrams || settings.debugReceive)
+ {
+ systemPrint("Receive error: ");
+ systemPrintln(state);
+ outputSerialData(true);
+ }
+ }
+}
diff --git a/Firmware/LoRaSerial/Serial.ino b/Firmware/LoRaSerial/Serial.ino
new file mode 100644
index 00000000..fd98d6b9
--- /dev/null
+++ b/Firmware/LoRaSerial/Serial.ino
@@ -0,0 +1,940 @@
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Serial RX - Data arriving at the USB or serial port
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Return number of bytes sitting in the serial receive buffer
+uint16_t availableRXBytes()
+{
+ if (rxHead >= rxTail) return (rxHead - rxTail);
+ return (sizeof(serialReceiveBuffer) - rxTail + rxHead);
+}
+
+//Returns true if CTS is asserted (high = host says it's ok to send data)
+bool isCTS()
+{
+ if (pin_cts == PIN_UNDEFINED) return (true); //CTS not implmented on this board
+ if (settings.flowControl == false) return (true); //CTS turned off
+ return (digitalRead(pin_cts) == HIGH) ^ settings.invertCts;
+}
+
+#define NEXT_RX_TAIL(n) ((rxTail + n) % sizeof(serialReceiveBuffer))
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Serial TX - Data being sent to the USB or serial port
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Return number of bytes sitting in the serial transmit buffer
+uint16_t availableTXBytes()
+{
+ if (txHead >= txTail) return (txHead - txTail);
+ return (sizeof(serialTransmitBuffer) - txTail + txHead);
+}
+
+//Add serial data to the output buffer
+void serialBufferOutput(uint8_t * data, uint16_t dataLength)
+{
+ int length;
+
+ length = 0;
+ if ((txHead + dataLength) > sizeof(serialTransmitBuffer))
+ {
+ //Copy the first portion of the received datagram into the buffer
+ length = sizeof(serialTransmitBuffer) - txHead;
+ memcpy(&serialTransmitBuffer[txHead], data, length);
+ txHead = 0;
+ }
+
+ //Copy the remaining portion of the received datagram into the buffer
+ memcpy(&serialTransmitBuffer[txHead], &data[length], dataLength - length);
+ txHead += dataLength - length;
+ txHead %= sizeof(serialTransmitBuffer);
+}
+
+//Add a single byte to the output buffer
+void serialOutputByte(uint8_t data)
+{
+ if (printerEndpoint == PRINT_TO_SERIAL)
+ {
+ //Add this byte to the serial output buffer
+ serialTransmitBuffer[txHead++] = data;
+ txHead %= sizeof(serialTransmitBuffer);
+ }
+ else
+ {
+ //Add this byte to the command response buffer
+ commandTXBuffer[commandTXHead++] = data;
+ commandTXHead %= sizeof(commandTXBuffer);
+ }
+}
+
+//Update the output of the RTS pin (host says it's ok to send data when assertRTS = true)
+void updateRTS(bool assertRTS)
+{
+ rtsAsserted = assertRTS;
+ if (settings.flowControl && (pin_rts != PIN_UNDEFINED))
+ digitalWrite(pin_rts, assertRTS ^ settings.invertRts);
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Radio TX - Data to provide to the long range radio
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Return number of bytes sitting in the radio TX buffer
+uint16_t availableRadioTXBytes()
+{
+ if (radioTxHead >= radioTxTail) return (radioTxHead - radioTxTail);
+ return (sizeof(radioTxBuffer) - radioTxTail + radioTxHead);
+}
+
+#define NEXT_RADIO_TX_HEAD(n) ((radioTxHead + n) % sizeof(radioTxBuffer))
+#define NEXT_RADIO_TX_TAIL(n) ((radioTxTail + n) % sizeof(radioTxBuffer))
+
+//If we have data to send, get the packet ready
+//Return true if new data is ready to be sent
+bool processWaitingSerial(bool sendNow)
+{
+ uint16_t dataBytes;
+
+ //Push any available data out
+ dataBytes = availableRadioTXBytes();
+ if (dataBytes >= maxDatagramSize)
+ {
+ if (settings.debugRadio)
+ systemPrintln("Sending max frame");
+ readyOutgoingPacket(dataBytes);
+ return (true);
+ }
+
+ //Check if we should send out a partial frame
+ else if (sendNow || (dataBytes > 0 && (millis() - lastByteReceived_ms) >= settings.serialTimeoutBeforeSendingFrame_ms))
+ {
+ if (settings.debugRadio)
+ systemPrintln("Sending partial frame");
+ readyOutgoingPacket(dataBytes);
+ return (true);
+ }
+ return (false);
+}
+
+//Send a portion of the radioTxBuffer to outgoingPacket
+void readyOutgoingPacket(uint16_t bytesToSend)
+{
+ uint16_t length;
+ if (bytesToSend > maxDatagramSize) bytesToSend = maxDatagramSize;
+
+ //Determine the number of bytes to send
+ length = 0;
+ if ((radioTxTail + bytesToSend) > sizeof(radioTxBuffer))
+ {
+ //Copy the first portion of the buffer
+ length = sizeof(radioTxBuffer) - radioTxTail;
+ memcpy(&outgoingPacket[headerBytes], &radioTxBuffer[radioTxTail], length);
+ radioTxTail = 0;
+ }
+
+ //Copy the remaining portion of the buffer
+ memcpy(&outgoingPacket[headerBytes + length], &radioTxBuffer[radioTxTail], bytesToSend - length);
+ radioTxTail = NEXT_RADIO_TX_TAIL(bytesToSend - length);
+ endOfTxData += bytesToSend;
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Command RX - Remote command data received from a remote system
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Return number of bytes sitting in the serial receive buffer
+uint16_t availableRXCommandBytes()
+{
+ if (commandRXHead >= commandRXTail) return (commandRXHead - commandRXTail);
+ return (sizeof(commandRXBuffer) - commandRXTail + commandRXHead);
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Command TX - Remote command data or command response data to be sent to the remote system
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Return number of bytes sitting in the serial transmit buffer
+uint16_t availableTXCommandBytes()
+{
+ if (commandTXHead >= commandTXTail) return (commandTXHead - commandTXTail);
+ return (sizeof(commandTXBuffer) - commandTXTail + commandTXHead);
+}
+
+#define NEXT_COMMAND_TX_TAIL(n) ((commandTXTail + n) % sizeof(commandTXBuffer))
+
+//Send a portion of the commandTXBuffer to serialTransmitBuffer
+void readyLocalCommandPacket()
+{
+ uint16_t bytesToSend;
+ uint16_t length;
+ uint16_t maxLength;
+
+ bytesToSend = availableTXCommandBytes();
+ maxLength = maxDatagramSize;
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ maxLength -= VC_RADIO_HEADER_BYTES;
+ if (bytesToSend > maxLength)
+ bytesToSend = maxLength;
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ //Build the VC header
+ serialOutputByte(START_OF_VC_SERIAL);
+ serialOutputByte(bytesToSend + VC_RADIO_HEADER_BYTES);
+ serialOutputByte(PC_REMOTE_RESPONSE | myVc);
+ serialOutputByte(myVc);
+ if (settings.debugSerial)
+ systemPrintln("Built VC header in serialTransmitBuffer");
+ }
+
+ //Place the command response bytes into serialTransmitBuffer
+ if (settings.debugSerial)
+ {
+ systemPrint("Moving ");
+ systemPrint(bytesToSend);
+ systemPrintln(" bytes from commandTXBuffer into serialTransmitBuffer");
+ outputSerialData(true);
+ }
+ for (length = 0; length < bytesToSend; length++)
+ {
+ serialOutputByte(commandTXBuffer[commandTXTail]);
+ commandTXTail = NEXT_COMMAND_TX_TAIL(1);
+ }
+}
+
+//Send a portion of the commandTXBuffer to outgoingPacket
+uint8_t readyOutgoingCommandPacket(uint16_t offset)
+{
+ uint16_t bytesToSend;
+ uint16_t length;
+ uint16_t maxLength;
+
+ //Limit the length to the frame size
+ maxLength = maxDatagramSize - offset;
+ bytesToSend = availableTXCommandBytes();
+ if (bytesToSend > maxLength)
+ {
+ bytesToSend = maxLength;
+
+ //checkCommand delivers the entire command response to the commandTXBuffer.
+ //The response to be broken into multiple frames for transmission to the remote
+ //radio and host. The code below separates the commnad response from the
+ //VC_COMMAND_COMPLETE_MESSAGE which follows the response. This separation
+ //ensures that the entire VC_COMMAND_COMPLETE_MESSAGE is delivered within a
+ //single frame. The result enables easy detection by the remote radio.
+ //
+ //Determine the number of command response bytes to send
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ //Reserve the bytes for the VC heeader
+ bytesToSend -= VC_SERIAL_HEADER_BYTES;
+
+ //Determine if the VC_COMMAND_COMPLETE_MESSAGE is split across two buffers
+
+ if (commandTXBuffer[commandTXTail] != START_OF_VC_SERIAL)
+ {
+ //OK if the entire VC_COMMAND_COMPLETE_MESSAGE is in the buffer. Start
+ //the search one byte into the VC_COMMAND_COMPLETE_MESSAGE position.
+ for (length = bytesToSend - VC_SERIAL_HEADER_BYTES
+ - sizeof(VC_COMMAND_COMPLETE_MESSAGE) + 1;
+ length < bytesToSend; length++)
+ if (commandTXBuffer[NEXT_COMMAND_TX_TAIL(length)] == START_OF_VC_SERIAL)
+ {
+ //Exclude the partial piece of the VC_COMMAND_COMPLETE_MESSAGE from
+ //this command response frame.
+ bytesToSend = length;
+ break;
+ }
+ }
+ }
+ }
+
+ //Display the amount of data being sent
+ if (settings.debugSerial)
+ {
+ systemPrint("Moving ");
+ systemPrint(bytesToSend);
+ systemPrintln(" bytes from commandTXBuffer into outgoingPacket");
+ dumpCircularBuffer(commandTXBuffer, commandTXTail, sizeof(commandTXBuffer), bytesToSend);
+ }
+
+ //Determine if the data wraps around to the beginning of the buffer
+ length = 0;
+ if ((commandTXTail + bytesToSend) > sizeof(commandTXBuffer))
+ {
+ //Copy the first portion of the buffer
+ length = sizeof(commandTXBuffer) - commandTXTail;
+ memcpy(&outgoingPacket[headerBytes + offset], &commandTXBuffer[commandTXTail], length);
+ commandTXTail = 0;
+ }
+
+ //Copy the remaining portion of the buffer
+ memcpy(&outgoingPacket[headerBytes + offset + length], &commandTXBuffer[commandTXTail], bytesToSend - length);
+ commandTXTail = NEXT_COMMAND_TX_TAIL(bytesToSend - length);
+ endOfTxData += bytesToSend;
+ return (uint8_t)bytesToSend;
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Move serial data through the system
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//See if there's any serial from the remote radio that needs printing
+//Record any characters to the receive buffer
+//Scan for escape characters
+void updateSerial()
+{
+ uint16_t previousHead;
+ int x;
+
+ //Assert RTS when there is enough space in the receive buffer
+ if ((!rtsAsserted) && (availableRXBytes() < (sizeof(serialReceiveBuffer) / 2))
+ && (availableTXBytes() < (sizeof(serialTransmitBuffer) / 4)))
+ updateRTS(true);
+
+ //Attempt to empty the serialTransmitBuffer
+ outputSerialData(false);
+
+ //Look for local incoming serial
+ previousHead = rxHead;
+ while (rtsAsserted && arch.serialAvailable() && (transactionComplete == false))
+ {
+ blinkSerialRxLed(true); //Turn on LED during serial reception
+
+ //Take a break if there are ISRs to attend to
+ petWDT();
+ if (timeToHop == true) hopChannel();
+
+ //Deassert RTS when the buffer gets full
+ if (rtsAsserted && (sizeof(serialReceiveBuffer) - availableRXBytes()) < 32)
+ updateRTS(false);
+
+ byte incoming = systemRead();
+
+ serialReceiveBuffer[rxHead++] = incoming; //Push char to holding buffer
+ rxHead %= sizeof(serialReceiveBuffer);
+ } //End Serial.available()
+ blinkSerialRxLed(false); //Turn off LED
+
+ //Print the number of bytes received via serial
+ if (settings.debugSerial && (rxHead - previousHead))
+ {
+ systemPrint("updateSerial moved ");
+ if (rxHead > previousHead)
+ systemPrint(rxHead - previousHead);
+ else
+ systemPrint(sizeof(serialReceiveBuffer) - previousHead + rxHead);
+ systemPrintln(" bytes into serialReceiveBuffer");
+ outputSerialData(true);
+ petWDT();
+ }
+
+ //Process the serial data
+ if (serialOperatingMode == MODE_VIRTUAL_CIRCUIT)
+ vcProcessSerialInput();
+ else
+ processSerialInput();
+
+ //Process any remote commands sitting in buffer
+ if (availableRXCommandBytes() && inCommandMode == false)
+ {
+ commandLength = availableRXCommandBytes();
+
+ for (x = 0 ; x < commandLength ; x++)
+ {
+ commandBuffer[x] = commandRXBuffer[commandRXTail++];
+ commandRXTail %= sizeof(commandRXBuffer);
+ }
+
+ //Print the number of bytes moved into the command buffer
+ if (settings.debugSerial && commandLength)
+ {
+ systemPrint("updateSerial moved ");
+ systemPrint(commandLength);
+ systemPrintln(" bytes from commandRXBuffer into commandBuffer");
+ outputSerialData(true);
+ petWDT();
+ }
+
+ if (commandBuffer[0] == 'R') //Error check
+ {
+ commandBuffer[0] = 'A'; //Convert this RT command to an AT command for local consumption
+ printerEndpoint = PRINT_TO_RF; //Send prints to RF link
+ checkCommand(); //Parse the command buffer
+ printerEndpoint = PRINT_TO_SERIAL;
+ remoteCommandResponse = true;
+ }
+ else
+ {
+ if (settings.debugRadio)
+ systemPrintln("Corrupt remote command received");
+ }
+ }
+}
+
+//Process serial input for point-to-point and multi-point modes
+void processSerialInput()
+{
+ uint16_t radioHead;
+ static uint32_t lastEscapeCharEnteredMillis;
+
+ //Process the serial data
+ radioHead = radioTxHead;
+ while (availableRXBytes()
+ && (availableRadioTXBytes() < (sizeof(radioTxBuffer) - maxEscapeCharacters))
+ && (transactionComplete == false))
+ {
+ //Take a break if there are ISRs to attend to
+ petWDT();
+ if (timeToHop == true) hopChannel();
+
+ byte incoming = serialReceiveBuffer[rxTail++];
+ rxTail %= sizeof(serialReceiveBuffer);
+
+ if ((settings.echo == true) || (inCommandMode == true))
+ {
+ systemWrite(incoming);
+ outputSerialData(true);
+ }
+
+ //Process serial into either rx buffer or command buffer
+ if (inCommandMode == true)
+ {
+ if (incoming == '\r' && commandLength > 0)
+ {
+ printerEndpoint = PRINT_TO_SERIAL;
+ systemPrintln();
+ checkCommand(); //Process command buffer
+ }
+ else if (incoming == '\n')
+ ; //Do nothing
+ else
+ {
+ if (incoming == 8)
+ {
+ if (commandLength > 0)
+ {
+ //Remove this character from the command buffer
+ commandLength--;
+
+ //Erase the previous character
+ systemWrite(incoming);
+ systemWrite(' ');
+ systemWrite(incoming);
+ }
+ else
+ systemWrite(7);
+ outputSerialData(true);
+ }
+ else
+ {
+ //Move this character into the command buffer
+ commandBuffer[commandLength++] = incoming;
+ commandLength %= sizeof(commandBuffer);
+ }
+ }
+ }
+ else
+ {
+ //Check general serial stream for command characters
+ //Ignore escape characters received within 2 seconds of serial traffic
+ //Allow escape characters received within first 2 seconds of power on
+ if ((incoming == escapeCharacter)
+ && ((millis() - lastByteReceived_ms > minEscapeTime_ms)
+ || (millis() < minEscapeTime_ms)))
+ {
+ escapeCharsReceived++;
+ lastEscapeCharEnteredMillis = millis();
+ if (escapeCharsReceived == maxEscapeCharacters)
+ {
+ systemPrintln("\r\nOK");
+ outputSerialData(true);
+
+ inCommandMode = true; //Allow AT parsing. Prevent received RF data from being printed.
+ forceRadioReset = false; //Don't reset the radio link unless a setting requires it
+ writeOnCommandExit = false; //Don't record settings changes unless user commands it
+
+ tempSettings = settings;
+
+ escapeCharsReceived = 0;
+ lastByteReceived_ms = millis();
+ return; //Avoid recording this incoming command char
+ }
+ }
+
+ //This is just a character in the stream, ignore
+ else
+ {
+ //Update timeout check for escape char and partial frame
+ lastByteReceived_ms = millis();
+
+ //Replay any escape characters if the sequence was not entered in the
+ //necessary time
+ while (escapeCharsReceived)
+ {
+ escapeCharsReceived--;
+ radioTxBuffer[radioTxHead++] = escapeCharacter;
+ radioTxHead %= sizeof(radioTxBuffer);
+ }
+
+ //The input data byte will be sent over the long range radio
+ radioTxBuffer[radioTxHead++] = incoming;
+ radioTxHead %= sizeof(radioTxBuffer);
+ }
+ } //End process rx buffer
+ }
+
+ //Check for escape timeout, more than two seconds have elapsed without entering
+ //command mode. The escape characters must be part of the input stream but were
+ //the last characters entered. Send these characters over the long range radio.
+ if (escapeCharsReceived && (millis() - lastEscapeCharEnteredMillis > minEscapeTime_ms)
+ && (availableRXBytes() < (sizeof(radioTxBuffer) - maxEscapeCharacters)))
+ {
+ //Replay the escape characters
+ while (escapeCharsReceived)
+ {
+ escapeCharsReceived--;
+
+ //Transmit the escape character over the long range radio
+ radioTxBuffer[radioTxHead++] = escapeCharacter;
+ radioTxHead %= sizeof(radioTxBuffer);
+ }
+ }
+
+ //Print the number of bytes placed into the rxTxBuffer
+ if (settings.debugSerial && (radioTxHead != radioHead))
+ {
+ systemPrint("processSerialInput moved ");
+ if (radioTxHead > radioHead)
+ systemPrint(radioTxHead - radioHead);
+ else
+ systemPrint(sizeof(radioTxBuffer) - radioHead + radioTxHead);
+ systemPrintln(" bytes from serialReceiveBuffer into radioTxBuffer");
+ outputSerialData(true);
+ }
+}
+
+//Move the serial data from serialTransmitBuffer to the USB or serial port
+void outputSerialData(bool ignoreISR)
+{
+ int dataBytes;
+
+ //Forget printing if there are ISRs to attend to
+ dataBytes = availableTXBytes();
+ while (dataBytes-- && isCTS() && (ignoreISR || (!transactionComplete)))
+ {
+ blinkSerialTxLed(true); //Turn on LED during serial transmissions
+
+ //Take a break if there are ISRs to attend to
+ petWDT();
+ if (timeToHop == true) hopChannel();
+
+ arch.serialWrite(serialTransmitBuffer[txTail]);
+ systemFlush(); //Prevent serial hardware from blocking more than this one write
+
+ txTail++;
+ txTail %= sizeof(serialTransmitBuffer);
+ }
+ blinkSerialTxLed(false); //Turn off LED
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Virtual-Circuit support
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Get the message length byte from the serial buffer
+bool vcSerialMsgGetLengthByte(uint8_t * msgLength)
+{
+ //Get the length byte for the received serial message, account for the start byte
+ *msgLength = radioTxBuffer[radioTxTail];
+ return true;
+}
+
+//Determine if received serial data may be sent to the remote system
+bool vcSerialMessageReceived()
+{
+ int8_t channel;
+ uint16_t dataBytes;
+ uint8_t msgLength;
+ int8_t vcDest; //Byte from VC_RADIO_MESSAGE_HEADER
+ int8_t vcIndex; //Index into virtualCircuitList
+
+ do
+ {
+ //Determine if the radio is idle
+ if (receiveInProcess())
+ //The radio is busy, wait until it is idle
+ break;
+
+ //Check for some data bytes
+ dataBytes = availableRadioTXBytes();
+ if (!dataBytes)
+ break;
+
+ //Wait until the length byte is available
+ msgLength = radioTxBuffer[radioTxTail];
+
+ //Print the message length and availableRadioTXBytes
+ if (settings.debugSerial)
+ {
+ systemPrint("msgLength: ");
+ systemPrintln(msgLength);
+ systemPrint("availableRadioTXBytes(): ");
+ systemPrintln(availableRadioTXBytes());
+ outputSerialData(true);
+ }
+
+ //Verify that the entire message is in the serial buffer
+ if (availableRadioTXBytes() < msgLength)
+ {
+ //The entire message is not in the buffer
+ if (settings.debugSerial)
+ {
+ systemPrintln("VC serial RX: Waiting for entire buffer");
+ outputSerialData(true);
+ }
+ break;
+ }
+
+ //vcProcessSerialInput validates the vcDest value, this check validates
+ //that internally generated traffic uses valid vcDest values. Only messages
+ //enabled for receive on a remote radio may be transmitted.
+ vcDest = radioTxBuffer[NEXT_RADIO_TX_TAIL(1)];
+ vcIndex = -1;
+ if ((uint8_t)vcDest < (uint8_t)MIN_RX_NOT_ALLOWED)
+ vcIndex = vcDest & VCAB_NUMBER_MASK;
+ if ((vcIndex < 0) && (vcDest != VC_BROADCAST))
+ {
+ if (settings.debugSerial || settings.debugTransmit)
+ {
+ systemPrint("ERROR: Invalid internally generated vcDest ");
+ systemPrint(vcDest);
+ systemPrintln(", discarding message!");
+ outputSerialData(true);
+ }
+
+ //Discard this message
+ radioTxTail = NEXT_RADIO_TX_TAIL(msgLength);
+ break;
+ }
+
+ //Determine if the message is too large
+ if (msgLength > maxDatagramSize)
+ {
+ if (settings.debugSerial || settings.debugTransmit)
+ {
+ systemPrintln("VC serial RX: Message too long, discarded");
+ outputSerialData(true);
+ }
+
+ //Discard this message, it is too long to transmit over the radio link
+ radioTxTail = NEXT_RADIO_TX_TAIL(msgLength);
+
+ //Nothing to do for invalid addresses or the broadcast address
+ if (((uint8_t)vcDest >= (uint8_t)MIN_TX_NOT_ALLOWED) && (vcDest != VC_BROADCAST))
+ break;
+
+ //Break the link to this host since message delivery is guarranteed and
+ //this message is being discarded
+ vcBreakLink(vcDest & VCAB_NUMBER_MASK);
+ break;
+ }
+
+ //Verify that the destination link is connected
+ if ((vcDest != VC_BROADCAST)
+ && (virtualCircuitList[vcIndex].vcState < VC_STATE_CONNECTED))
+ {
+ if (settings.debugSerial || settings.debugTransmit)
+ {
+ systemPrint("Link not connected ");
+ systemPrint(vcIndex);
+ systemPrintln(", discarding message!");
+ outputSerialData(true);
+ }
+
+ //Discard this message
+ radioTxTail = NEXT_RADIO_TX_TAIL(msgLength);
+
+ //If the PC is trying to send this message then notify the PC of the delivery failure
+ if ((uint8_t)vcDest < (uint8_t)MIN_TX_NOT_ALLOWED)
+ vcSendPcAckNack(vcIndex, false);
+ break;
+ }
+
+ //Print the data ready for transmission
+ if (settings.debugSerial)
+ {
+ systemPrint("Readying ");
+ systemPrint(msgLength);
+ systemPrintln(" byte for transmission");
+ dumpCircularBuffer(radioTxBuffer, radioTxTail, sizeof(radioTxBuffer), msgLength);
+ }
+
+ //If sending to ourself, just place the data in the serial output buffer
+ readyOutgoingPacket(msgLength);
+ channel = GET_CHANNEL_NUMBER(vcDest);
+ if ((vcDest != VC_BROADCAST) && ((vcDest & VCAB_NUMBER_MASK) == myVc)
+ && (channel == 0))
+ {
+ if (settings.debugSerial)
+ systemPrintln("VC: Sending data to ourself");
+ systemWrite(START_OF_VC_SERIAL);
+ systemWrite(outgoingPacket, msgLength);
+ endOfTxData -= msgLength;
+ break;
+ }
+
+ //Send this message
+ return true;
+ } while (0);
+
+ //Nothing to send at this time
+ return false;
+}
+
+//Notify the PC of the message delivery failure
+void vcSendPcAckNack(int8_t vcIndex, bool ackMsg)
+{
+ //Build the VC state message
+ VC_DATA_ACK_NACK_MESSAGE message;
+ message.msgDestVc = vcIndex;
+
+ //Build the message header
+ VC_SERIAL_MESSAGE_HEADER header;
+ header.start = START_OF_VC_SERIAL;
+ header.radio.length = VC_RADIO_HEADER_BYTES + sizeof(message);
+ header.radio.destVc = ackMsg ? PC_DATA_ACK : PC_DATA_NACK;
+ header.radio.srcVc = myVc;
+
+ //Send the VC state message
+ systemWrite((uint8_t *)&header, sizeof(header));
+ systemWrite((uint8_t *)&message, sizeof(message));
+}
+
+//Process serial input when running in MODE_VIRTUAL_CIRCUIT
+void vcProcessSerialInput()
+{
+ char * cmd;
+ uint8_t data;
+ uint16_t dataBytes;
+ uint16_t index;
+ int8_t vcDest;
+ int8_t vcSrc;
+ uint8_t length;
+
+ //Process the serial data while there is space in radioTxBuffer
+ dataBytes = availableRXBytes();
+ while (dataBytes && (availableRadioTXBytes() < (sizeof(radioTxBuffer) - 256))
+ && (transactionComplete == false))
+ {
+ //Take a break if there are ISRs to attend to
+ petWDT();
+ if (timeToHop == true) hopChannel();
+
+ //Skip any garbage in the input stream
+ data = serialReceiveBuffer[rxTail];
+ if (data != START_OF_VC_SERIAL)
+ {
+ rxTail = NEXT_RX_TAIL(1);
+ if (settings.debugSerial)
+ {
+ systemPrint("vcProcessSerialInput discarding 0x");
+ systemPrint(data, HEX);
+ systemPrintln();
+ outputSerialData(true);
+ }
+
+ //Discard this data byte
+ dataBytes = availableRXBytes();
+ continue;
+ }
+
+ //Get the virtual circuit header
+ //The start byte has already been removed
+ length = serialReceiveBuffer[NEXT_RX_TAIL(1)];
+ if (length < VC_SERIAL_HEADER_BYTES)
+ {
+ if (settings.debugSerial)
+ {
+ systemPrint("ERROR - Invalid length ");
+ systemPrint(length);
+ systemPrint(", discarding 0x");
+ systemPrint(data, HEX);
+ systemPrintln();
+ outputSerialData(true);
+ }
+
+ //Invalid message length, discard the START_OF_VC_SERIAL
+ dataBytes = availableRXBytes();
+ continue;
+ }
+
+ //Skip if there is not enough data in the buffer
+ if (dataBytes < (length + 1))
+ break;
+
+ //Remove the START_OF_VC_SERIAL byte
+ rxTail = NEXT_RX_TAIL(1);
+
+ //Get the source and destination virtual circuits
+ index = NEXT_RX_TAIL(1);
+ vcDest = serialReceiveBuffer[index];
+ index = NEXT_RX_TAIL(2);
+ vcSrc = serialReceiveBuffer[index];
+
+ //Process this message
+ switch ((uint8_t)vcDest)
+ {
+ //Send data over the radio link
+ default:
+ //Validate the source virtual circuit
+ //Data that is being transmitted should always use myVC
+ if ((vcSrc != myVc) || (myVc == VC_UNASSIGNED))
+ {
+ if (settings.debugSerial)
+ {
+ systemPrint("ERROR: Invalid myVc ");
+ systemPrint(myVc);
+ systemPrintln(" for data message, discarding message!");
+ outputSerialData(true);
+ }
+
+ //Discard this message
+ rxTail = NEXT_RX_TAIL(length);
+ break;
+ }
+
+ //Verify the destination virtual circuit
+ if (((uint8_t)vcDest >= (uint8_t)MIN_TX_NOT_ALLOWED) && (vcDest < VC_BROADCAST))
+ {
+ if (settings.debugSerial)
+ {
+ systemPrint("ERROR: Invalid vcDest ");
+ systemPrint(vcDest);
+ systemPrintln(" for data message, discarding message!");
+ outputSerialData(true);
+ }
+
+ //Discard this message
+ rxTail = NEXT_RX_TAIL(length);
+ break;
+ }
+
+ if (settings.debugSerial)
+ {
+ systemPrint("vcProcessSerialInput moving ");
+ systemPrint(length);
+ systemPrintln(" bytes into radioTxBuffer");
+ dumpCircularBuffer(serialReceiveBuffer, rxTail, sizeof(serialReceiveBuffer), length);
+ outputSerialData(true);
+ }
+
+ //Place the data in radioTxBuffer
+ for (; length > 0; length--)
+ {
+ radioTxBuffer[radioTxHead] = serialReceiveBuffer[rxTail];
+ rxTail = NEXT_RX_TAIL(1);
+ radioTxHead = NEXT_RADIO_TX_HEAD(1);
+ }
+ break;
+
+ //Process this command
+ case (uint8_t)VC_COMMAND:
+ //Validate the source virtual circuit
+ if ((vcSrc != PC_COMMAND) || (length > (sizeof(commandBuffer) - 1)))
+ {
+ if (settings.debugSerial)
+ {
+ systemPrint("ERROR: Invalid vcSrc ");
+ systemPrint(myVc);
+ systemPrintln(" for command message, discarding message!");
+ outputSerialData(true);
+ }
+
+ //Discard this message
+ rxTail = NEXT_RX_TAIL(length);
+ break;
+ }
+
+ //Discard the VC header
+ length -= VC_RADIO_HEADER_BYTES;
+ rxTail = NEXT_RX_TAIL(VC_RADIO_HEADER_BYTES);
+
+ //Move this message into the command buffer
+ for (cmd = commandBuffer; length > 0; length--)
+ {
+ *cmd++ = toupper(serialReceiveBuffer[rxTail]);
+ rxTail = NEXT_RX_TAIL(1);
+ }
+ commandLength = cmd - commandBuffer;
+
+ if (settings.debugSerial)
+ {
+ systemPrint("vcProcessSerialInput moving ");
+ systemPrint(commandLength);
+ systemPrintln(" bytes into commandBuffer");
+ outputSerialData(true);
+ dumpBuffer((uint8_t *)commandBuffer, commandLength);
+ }
+
+ //Process this command
+ tempSettings = settings;
+ checkCommand();
+ settings = tempSettings;
+ break;
+ }
+
+ //Determine how much data is left in the buffer
+ dataBytes = availableRXBytes();
+ }
+
+ //Take a break if there are ISRs to attend to
+ petWDT();
+ if (timeToHop == true) hopChannel();
+}
+
+//Display any serial data for output, discard:
+// * Serial input data
+// * Radio transmit data
+// * Received remote command data
+// * Remote command response data
+void resetSerial()
+{
+ uint32_t delayTime;
+ uint32_t lastCharacterReceived;
+
+ //Display any debug output
+ outputSerialData(true);
+
+ //Determine the amount of time needed to receive a character
+ delayTime = (1000 * 8 * 2) / settings.serialSpeed;
+ if (delayTime < 200)
+ delayTime = 200;
+
+ //Enable RTS
+ updateRTS(true);
+
+ //Flush the incoming serial
+ lastCharacterReceived = millis();
+ do
+ {
+ //Discard any incoming serial data
+ while (arch.serialAvailable())
+ {
+ petWDT();
+ systemRead();
+ lastCharacterReceived = millis();
+ }
+ petWDT();
+
+ //Wait enough time to receive any remaining data from the host
+ } while ((millis() - lastCharacterReceived) < delayTime);
+
+ //Empty the buffers
+ rxHead = rxTail;
+ radioTxHead = radioTxTail;
+ txHead = txTail;
+ commandRXHead = commandRXTail;
+ commandTXHead = commandTXTail;
+ endOfTxData = &outgoingPacket[headerBytes];
+ commandLength = 0;
+}
diff --git a/Firmware/LoRaSerial/States.ino b/Firmware/LoRaSerial/States.ino
new file mode 100644
index 00000000..b3abe0db
--- /dev/null
+++ b/Firmware/LoRaSerial/States.ino
@@ -0,0 +1,3199 @@
+#define SAVE_TX_BUFFER() \
+ { \
+ petWDT(); \
+ memcpy(rexmtBuffer, outgoingPacket, MAX_PACKET_SIZE); \
+ rexmtControl = txControl; \
+ rexmtLength = txDatagramSize; \
+ rexmtFrameSentCount = frameSentCount; \
+ }
+
+#define RESTORE_TX_BUFFER() \
+ { \
+ petWDT(); \
+ memcpy(outgoingPacket, rexmtBuffer, MAX_PACKET_SIZE); \
+ txControl = rexmtControl; \
+ txDatagramSize = rexmtLength; \
+ frameSentCount = rexmtFrameSentCount; \
+ }
+
+#define P2P_SEND_ACK(trigger) \
+ { \
+ /*Compute the frequency correction*/ \
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0; \
+ \
+ /*Send the ACK to the remote system*/ \
+ triggerEvent(trigger); \
+ if (xmitDatagramP2PAck() == true) \
+ { \
+ /*We ack'd the packet so be responsible for sending the next heartbeat*/ \
+ setHeartbeatShort(); \
+ changeState(RADIO_P2P_LINK_UP_WAIT_TX_DONE); \
+ } \
+ }
+
+#define START_ACK_TIMER() \
+ { \
+ /*Start the ACK timer*/ \
+ ackTimer = datagramTimer; \
+ \
+ /*Since ackTimer is off when equal to zero, force it to a non-zero value*/ \
+ /*Subtract one so that the comparisons result in a small number*/ \
+ if (!ackTimer) \
+ ackTimer -= 1; \
+ }
+
+#define STOP_ACK_TIMER() \
+ { \
+ /*Stop the ACK timer*/ \
+ ackTimer = 0; \
+ }
+
+#define COMPUTE_TIMESTAMP_OFFSET(millisBuffer, rShift, frameAirTimeUsec) \
+ { \
+ unsigned long deltaUsec = frameAirTimeUsec + micros() - transactionCompleteMicros; \
+ memcpy(&remoteSystemMillis, millisBuffer, sizeof(remoteSystemMillis)); \
+ timestampOffset = remoteSystemMillis + (deltaUsec / 1000) - millis(); \
+ timestampOffset >>= rShift; \
+ }
+
+//Process the radio states
+void updateRadioState()
+{
+ int8_t addressByte;
+ uint8_t channel;
+ unsigned long clockOffset;
+ unsigned long currentMillis;
+ unsigned long deltaMillis;
+ uint8_t * header = outgoingPacket;
+ bool heartbeatTimeout;
+ int index;
+ uint16_t length;
+ uint8_t radioSeed;
+ bool serverLinkBroken;
+ unsigned long timeoutMsec;
+ VIRTUAL_CIRCUIT * vc;
+ VC_RADIO_MESSAGE_HEADER * vcHeader;
+
+ switch (radioState)
+ {
+ default:
+ {
+ systemPrint("Unknown state: ");
+ systemPrintln(radioState);
+ waitForever("ERROR - Unknown radio state!");
+ }
+ break;
+
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ // Reset
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+ case RADIO_RESET:
+ petWDT();
+
+ //Empty the buffers
+ discardPreviousData();
+
+ //Set all of the ACK numbers to zero
+ *(uint8_t *)(&txControl) = 0;
+
+ //Initialize the radio
+ rssi = -200;
+ radioSeed = radio.randomByte(); //Puts radio into standy-by state
+ randomSeed(radioSeed);
+ if ((settings.debug == true) || (settings.debugRadio == true))
+ {
+ systemPrint("RadioSeed: ");
+ systemPrintln(radioSeed);
+ outputSerialData(true);
+ }
+
+ generateHopTable(); //Generate frequency table based on user settings.
+
+ selectHeaderAndTrailerBytes(); //Determine the components of the frame header and trailer
+
+ stopChannelTimer(); //Stop frequency hopping - reset
+ clockSyncReceiver = true; //Assume receiving clocks - reset
+
+ configureRadio(); //Setup radio, set freq to channel 0, calculate air times
+
+ //Determine the maximum frame air time
+ maxFrameAirTimeMsec = (calcAirTimeUsec(MAX_PACKET_SIZE) + 500) / 1000;
+
+ sf6ExpectedSize = headerBytes + CLOCK_MILLIS_BYTES + trailerBytes; //Tell SF6 to receive FIND_PARTNER packet
+
+ petWDT();
+
+ //Stop the ACK timer
+ STOP_ACK_TIMER();
+
+ //Start the link between the radios
+ if (settings.operatingMode == MODE_POINT_TO_POINT)
+ {
+ //Determine transmit frame times for SYNC_CLOCKS, ACK
+ getTxTime(xmitDatagramP2PFindPartner, &txFindPartnerUsec, "FIND_PARTNER");
+ getTxTime(xmitDatagramP2PSyncClocks, &txSyncClocksUsec, "SYNC_CLOCKS");
+ getTxTime(xmitDatagramP2PHeartbeat, &txHeartbeatUsec, "HEARTBEAT");
+ getTxTime(xmitDatagramP2PAck, &txDataAckUsec, "ACK");
+ setHeartbeatShort(); //Both radios start with short heartbeat period
+
+ randomTime = random(txDataAckUsec, txDataAckUsec * 2) / 1000; //Fast FIND_PARTNER
+
+ //Start receiving
+ returnToReceiving();
+ changeState(RADIO_P2P_LINK_DOWN);
+ break;
+ }
+
+ //Virtual circuit mode
+ if (settings.operatingMode == MODE_VIRTUAL_CIRCUIT)
+ {
+ //Determine transmit frame time for HEARTBEAT
+ getTxTime(xmitVcHeartbeat, &txHeartbeatUsec, "HEARTBEAT");
+ setVcHeartbeatTimer();
+ if (settings.server)
+ {
+ //Reserve the server's address (0)
+ myVc = vcIdToAddressByte(VC_SERVER, myUniqueId);
+ clockSyncReceiver = false; //VC server is clock source
+ if (settings.frequencyHop)
+ startChannelTimer();
+ }
+ else
+ //Unknown client address
+ myVc = VC_UNASSIGNED;
+
+ //Server: Start sending HEARTBEAT
+ //Client: Determine HEARTBEAT transmit time
+ xmitVcHeartbeat(myVc, myUniqueId);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ break;
+ }
+
+ //Multipoint mode
+ //Determine transmit frame times for SYNC_CLOCKS, HEARTBEAT, ACK
+ getTxTime(xmitDatagramP2PSyncClocks, &txSyncClocksUsec, "SYNC_CLOCKS");
+ getTxTime(xmitDatagramMpHeartbeat, &txHeartbeatUsec, "HEARTBEAT");
+ getTxTime(xmitDatagramP2PAck, &txDataAckUsec, "ACK");
+ setHeartbeatMultipoint();
+
+ //Start receiving
+ returnToReceiving();
+
+ if (settings.server == true)
+ {
+ clockSyncReceiver = false; //Multipoint server is clock source
+ startChannelTimer(); //Start hopping - multipoint clock source
+
+ //Start receiving
+ returnToReceiving();
+ changeState(RADIO_MP_STANDBY);
+ }
+ else
+ //Start receiving
+ returnToReceiving();
+ changeState(RADIO_DISCOVER_BEGIN);
+ break;
+
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ //No Link
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ //Point-To-Point: Bring up the link
+ //
+ //A three way handshake is used to get both systems to agree that data can flow in both
+ //directions. This handshake is also used to synchronize the HOP timer and zero the ACKs.
+ /*
+ System A System B
+
+ RESET RESET <-------------------------.
+ | | |
+ Channel 0 | | Channel 0 |
+ Stop HOP Timer | | Stop HOP Timer |
+ clockSyncReceiver | = true | clockSyncReceiver = true |
+ | | |
+ V V |
+ .----> P2P_NO_LINK P2P_NO_LINK <------------------. |
+ | | Tx FIND_PARTNER | | |
+ | Timeout | | Stop HOP Timer | |
+ | V | clockSyncReceiver | |
+ | P2P_WAIT_TX_FIND_PARTNER_DONE | = true | |
+ | | | | |
+ | | Tx Complete - - - - - > | Rx FIND_PARTNER | |
+ | | Start Rx | clockSyncReceiver | |
+ | | MAX_PACKET_SIZE | = false | |
+ | V | | |
+ `---- P2P_WAIT_SYNC_CLOCKS | | |
+ | | Tx SYNC_CLOCKS | |
+ | V | |
+ | P2P_WAIT_TX_SYNC_CLOCKS_DONE | |
+ | | | |
+ Rx Complete ISR | < - - - - - - - - - - - | Tx Complete ISR | |
+ | | Start HOP Timer | |
+ | Start HOP Timer | | |
+ | V | |
+ V | In state machine | |
+ Rx SYNC_CLOCKS | In state machine | Tx Complete | |
+ | | Start Rx | |
+ | | MAX_PACKET_SIZE | |
+ | | | |
+ | V Timeout | |
+ | P2P_WAIT_ZERO_ACKS ----------------' |
+ | | |
+ | TX ZERO_ACKS | |
+ | | |
+ V | |
+ P2P_WAIT_TX_ZERO_ACKS_DONE | |
+ | Tx Complete - - - - - > | Rx ZERO_ACKS |
+ | Start Rx | Start Rx |
+ | MAX_PACKET_SIZE | MAX_PACKET_SIZE |
+ | Zero ACKs | Zero ACKs |
+ | | |
+ V V Rx FIND_PARTNER |
+ P2P_LINK_UP P2P_LINK_UP -----------------------’
+ | |
+ | Rx Data | Rx Data
+ | |
+ V V
+
+ Two timers are in use:
+ datagramTimer: Set at end of transmit, measures ACK timeout
+ heartbeatTimer: Set upon entry to P2P_NO_LINK, measures time to send next FIND_PARTNER
+ */
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+ case RADIO_P2P_LINK_DOWN:
+ //If we are on the wrong channel, go home
+ if (channelNumber != 0)
+ {
+ channelNumber = 0;
+ setRadioFrequency(false);
+ }
+
+ //Stop the channel timer if it is running
+ if (channelTimerMsec)
+ stopChannelTimer();
+
+ //Determine if a FIND_PARTNER was received
+ if (transactionComplete)
+ {
+ //Decode the received packet
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_UNKNOWN_PACKET);
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Scan: Unhandled packet type ");
+ systemPrint(radioDatagramType[packetType]);
+ systemPrintln();
+ }
+ break;
+
+ case DATAGRAM_BAD:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_CRC_ERROR:
+ triggerEvent(TRIGGER_CRC_ERROR);
+ break;
+
+ case DATAGRAM_FIND_PARTNER:
+ //Received FIND_PARTNER
+ COMPUTE_TIMESTAMP_OFFSET(rxData, 1, txFindPartnerUsec);
+
+ //This system is the source of clock synchronization
+ clockSyncReceiver = false; //P2P clock source
+
+ //Display the channelTimer source
+ if (settings.debugSync)
+ {
+ systemPrintTimestamp();
+ systemPrintln("Sourcing channelTimer");
+ }
+
+ //Acknowledge the FIND_PARTNER with SYNC_CLOCKS
+ triggerEvent(TRIGGER_TX_SYNC_CLOCKS);
+ if (xmitDatagramP2PSyncClocks() == true)
+ {
+ startChannelTimerPending = true; //Starts at SYNC_CLOCKS TX done
+ sf6ExpectedSize = headerBytes + P2P_ZERO_ACKS_BYTES + trailerBytes; //Tell SF6 we expect ZERO_ACKS to contain millis info
+ changeState(RADIO_P2P_WAIT_TX_SYNC_CLOCKS_DONE);
+ }
+ break;
+ }
+ }
+
+ //Is it time to send the FIND_PARTNER to the remote system
+ else if ((receiveInProcess() == false) && ((millis() - heartbeatTimer) >= randomTime))
+ {
+ //Transmit the FIND_PARTNER
+ triggerEvent(TRIGGER_TX_FIND_PARTNER);
+ if (xmitDatagramP2PFindPartner() == true)
+ {
+ if (settings.debugSync)
+ triggerFrequency(channels[channelNumber]);
+ sf6ExpectedSize = headerBytes + CLOCK_MILLIS_BYTES + trailerBytes; //Tell SF6 we expect SYNC_CLOCKS to contain millis info
+ changeState(RADIO_P2P_WAIT_TX_FIND_PARTNER_DONE);
+ }
+ }
+ break;
+
+ case RADIO_P2P_WAIT_TX_FIND_PARTNER_DONE:
+ //Determine if a FIND_PARTNER has completed transmission
+ if (transactionComplete)
+ {
+ triggerEvent(TRIGGER_TX_DONE);
+ transactionComplete = false; //Reset ISR flag
+ irqFlags = radio.getIRQFlags();
+ startChannelTimerPending = true; //Starts at RX of SYNC_CLOCKS frame
+ returnToReceiving();
+ changeState(RADIO_P2P_WAIT_SYNC_CLOCKS);
+ }
+ break;
+
+ case RADIO_P2P_WAIT_SYNC_CLOCKS:
+ if (transactionComplete)
+ {
+ //Decode the received packet
+ PacketType packetType = rcvDatagram();
+
+ //Restart the channel timer when the SYNC_CLOCKS frame is received
+ if (packetType != DATAGRAM_SYNC_CLOCKS)
+ {
+ stopChannelTimer(); //Restart channel timer if SYNC_CLOCKS not RX
+ startChannelTimerPending = true; //Restart channel timer if SYNC_CLOCKS not RX
+ }
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_UNKNOWN_PACKET);
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Scan: Unhandled packet type ");
+ systemPrint(radioDatagramType[packetType]);
+ systemPrintln();
+ }
+ break;
+
+ case DATAGRAM_BAD:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_CRC_ERROR:
+ triggerEvent(TRIGGER_CRC_ERROR);
+ break;
+
+ case DATAGRAM_FIND_PARTNER:
+ //Received FIND_PARTNER
+ //Compute the receive time
+ COMPUTE_TIMESTAMP_OFFSET(rxData + 1, 1, txFindPartnerUsec);
+
+ //Acknowledge the FIND_PARTNER
+ triggerEvent(TRIGGER_TX_SYNC_CLOCKS);
+ if (xmitDatagramP2PSyncClocks() == true)
+ {
+ sf6ExpectedSize = headerBytes + P2P_ZERO_ACKS_BYTES + trailerBytes; //Tell SF6 we expect ZERO_ACKS to contain millis info
+ changeState(RADIO_P2P_WAIT_TX_SYNC_CLOCKS_DONE);
+ }
+ break;
+
+ case DATAGRAM_SYNC_CLOCKS:
+ //Received SYNC_CLOCKS
+ //Display the channelTimer sink
+ if (settings.debugSync)
+ {
+ systemPrintTimestamp();
+ systemPrintln("Syncing channelTimer");
+ }
+
+ //Compute the receive time
+ COMPUTE_TIMESTAMP_OFFSET(rxData + 1, 1, txSyncClocksUsec);
+
+ //Hop to the next channel
+ hopChannel();
+
+ //Acknowledge the SYNC_CLOCKS
+ triggerEvent(TRIGGER_TX_ZERO_ACKS);
+ if (xmitDatagramP2PZeroAcks() == true)
+ {
+ sf6ExpectedSize = MAX_PACKET_SIZE; //Tell SF6 to return to max packet length
+ changeState(RADIO_P2P_WAIT_TX_ZERO_ACKS_DONE);
+ }
+ break;
+ }
+ }
+ else
+ {
+ //If we timeout during handshake, return to link down
+ timeoutMsec = ((frameAirTimeUsec + txSyncClocksUsec) / 1000) + settings.overheadTime + (settings.txToRxUsec / 1000);
+ if ((millis() - datagramTimer) >= timeoutMsec)
+ {
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrintln("RX: SYNC_CLOCKS Timeout");
+ outputSerialData(true);
+ }
+
+ stopChannelTimer(); //Stop channel timer if no response received
+ startChannelTimerPending = false;
+
+ //Start the TX timer: time to delay before transmitting the FIND_PARTNER
+ triggerEvent(TRIGGER_HANDSHAKE_SYNC_CLOCKS_TIMEOUT);
+ setHeartbeatShort();
+
+ //Slow down FIND_PARTNERs
+ if ((txDataAckUsec / 1000) < settings.maxDwellTime)
+ randomTime = random(settings.maxDwellTime * 2, settings.maxDwellTime * 4);
+ else
+ randomTime = random(txDataAckUsec * 4, txDataAckUsec * 8) / 1000;
+
+ sf6ExpectedSize = headerBytes + CLOCK_MILLIS_BYTES + trailerBytes; //Tell SF6 to receive FIND_PARTNER packet
+ returnToReceiving();
+
+ changeState(RADIO_P2P_LINK_DOWN);
+ }
+ }
+ break;
+
+ case RADIO_P2P_WAIT_TX_SYNC_CLOCKS_DONE:
+ //Determine if a SYNC_CLOCKS has completed transmission
+ if (transactionComplete)
+ {
+ triggerEvent(TRIGGER_TX_DONE);
+ transactionComplete = false; //Reset ISR flag
+ irqFlags = radio.getIRQFlags();
+
+ //Hop to the next channel
+ hopChannel();
+ returnToReceiving();
+ changeState(RADIO_P2P_WAIT_ZERO_ACKS);
+ }
+ break;
+
+ case RADIO_P2P_WAIT_ZERO_ACKS:
+ if (transactionComplete == true)
+ {
+ //Decode the received packet
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_UNKNOWN_PACKET);
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Scan: Unhandled packet type ");
+ systemPrint(radioDatagramType[packetType]);
+ systemPrintln();
+ }
+ break;
+
+ case DATAGRAM_BAD:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_CRC_ERROR:
+ triggerEvent(TRIGGER_CRC_ERROR);
+ break;
+
+ case DATAGRAM_ZERO_ACKS:
+ setHeartbeatLong(); //We sent SYNC_CLOCKS and they sent ZERO_ACKS, so don't be the first to send heartbeat
+
+ //Bring up the link
+ enterLinkUp();
+ break;
+ }
+ }
+ else
+ {
+ //If we timeout during handshake, return to link down
+ timeoutMsec = settings.overheadTime + ((frameAirTimeUsec + txDataAckUsec + settings.txToRxUsec) / 1000);
+ if ((millis() - datagramTimer) >= timeoutMsec)
+ {
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrintln("RX: ZERO_ACKS Timeout");
+ outputSerialData(true);
+ }
+
+ //Stop the channel timer
+ stopChannelTimer(); //P2P_WAIT_ZERO_ACKS timeout
+ clockSyncReceiver = true; //P2P link timeout
+
+ //Start the TX timer: time to delay before transmitting the FIND_PARTNER
+ triggerEvent(TRIGGER_HANDSHAKE_ZERO_ACKS_TIMEOUT);
+ setHeartbeatShort();
+
+ //Slow down FIND_PARTNERs
+ if ((txDataAckUsec / 1000) < settings.maxDwellTime)
+ randomTime = random(settings.maxDwellTime * 2, settings.maxDwellTime * 4);
+ else
+ randomTime = random(txDataAckUsec * 4, txDataAckUsec * 8) / 1000;
+
+ sf6ExpectedSize = headerBytes + CLOCK_MILLIS_BYTES + trailerBytes; //Tell SF6 to receive FIND_PARTNER packet
+ returnToReceiving();
+
+ changeState(RADIO_P2P_LINK_DOWN);
+ }
+ }
+ break;
+
+ case RADIO_P2P_WAIT_TX_ZERO_ACKS_DONE:
+ //Determine if a ACK 2 has completed transmission
+ if (transactionComplete)
+ {
+ transactionComplete = false; //Reset ISR flag
+ irqFlags = radio.getIRQFlags();
+ setHeartbeatShort(); //We sent the last ack so be responsible for sending the next heartbeat
+
+ //Bring up the link
+ enterLinkUp();
+ }
+ break;
+
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ //Link Up
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ //Point-To-Point: Data Exchange
+
+ /*
+ System A System B
+
+ P2P_LINK_DOWN .-----------------------.
+ ^ | |
+ | V |
+ timeout | P2P_LINK_UP_WAIT_ACK_DONE |
+ | | |
+ .--------- P2P_LINK_UP_WAIT_ACK -----. | |
+ | | | | |
+ | | ACK Timeout | | |
+ | | | | |
+ | Rx ACK | < - - - - - - -)- - - - | Tx Complete |
+ | | | | Start Rx |
+ | | | | MAX_PACKET_SIZE |
+ | | Retransmit | | |
+ | V | V |
+ | P2P_LINK_UP | P2P_LINK_UP |
+ | | | | |
+ | | Tx DATA | | |
+ | | | | |
+ | V | | |
+ | P2P_LINK_UP_WAIT_TX_DONE <--' | |
+ | | | |
+ | | | |
+ | Tx Complete | Tx Complete - - - - - > | Rx DATA |
+ | Start Rx | | Rx Duplicate |
+ | MAX_PACKET_SIZE | | |
+ | | | Tx ACK |
+ '-------------------' | |
+ '-----------------------'
+
+ Three timers are in use:
+ datagramTimer: Set at end of transmit, measures ACK timeout
+ heartbeatTimer: Set upon entry to P2P_LINK_UP, reset upon HEARTBEAT transmit,
+ measures time to send next HEARTBEAT
+
+ Timestamp offset synchronization:
+
+ System A System B
+
+ FIND_PARTNER ----> Update timestampOffset
+
+ Update timestampOffset <---- SYNC_CLOCKS
+
+ ACK 2 ----> Update timestampOffset
+
+ HEARTBEAT 0 ----> Update timestampOffset
+
+ Update timestampOffset <---- HEARTBEAT 0
+
+ HEARTBEAT 1 --X
+
+ Update timestampOffset <---- HEARTBEAT 1
+
+ HEARTBEAT 1 ----> Update timestampOffset
+ */
+
+ //====================
+ //Wait for the data transmission to complete
+ //====================
+ case RADIO_P2P_LINK_UP_WAIT_TX_DONE:
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ if (transactionComplete)
+ {
+ transactionComplete = false; //Reset ISR flag
+ triggerEvent(TRIGGER_TX_DONE);
+ irqFlags = radio.getIRQFlags();
+
+ //Determine the next packet size for SF6
+ if (ackTimer)
+ {
+ //Waiting for an ACK
+ sf6ExpectedSize = headerBytes + CHANNEL_TIMER_BYTES + trailerBytes;
+ }
+ else
+ sf6ExpectedSize = MAX_PACKET_SIZE;
+
+ //Receive the next packet
+ returnToReceiving();
+ changeState(RADIO_P2P_LINK_UP);
+ }
+ break;
+
+ //====================
+ //Wait for the next operation (listed in priority order):
+ // * Frame received
+ // * Time to send HEARTBEAT
+ // * Time to retransmit previous frame
+ // * Remote command response to send
+ // * Data to send
+ // * Link timeout
+ //====================
+ case RADIO_P2P_LINK_UP:
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+
+ //Check for a received datagram
+ if (transactionComplete == true)
+ {
+ //Decode the received datagram
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_UNKNOWN_PACKET);
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("LinkUp: Unhandled packet type ");
+ systemPrint(radioDatagramType[packetType]);
+ systemPrintln();
+ outputSerialData(true);
+ }
+ break;
+
+ case DATAGRAM_SYNC_CLOCKS:
+ case DATAGRAM_ZERO_ACKS:
+ case DATAGRAM_BAD:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_CRC_ERROR:
+ triggerEvent(TRIGGER_CRC_ERROR);
+ break;
+
+ case DATAGRAM_NETID_MISMATCH:
+ triggerEvent(TRIGGER_NETID_MISMATCH);
+ break;
+
+ case DATAGRAM_FIND_PARTNER:
+ triggerEvent(TRIGGER_RX_FIND_PARTNER);
+ breakLink();
+ break;
+
+ case DATAGRAM_HEARTBEAT:
+ //Received heartbeat while link was idle. Send ack to sync clocks.
+ //Adjust the timestamp offset
+ COMPUTE_TIMESTAMP_OFFSET(rxData, 1, txHeartbeatUsec);
+ triggerEvent(TRIGGER_RX_HEARTBEAT);
+ blinkHeartbeatLed(true);
+
+ //Transmit ACK
+ P2P_SEND_ACK(TRIGGER_TX_ACK);
+ break;
+
+ case DATAGRAM_DATA:
+ triggerEvent(TRIGGER_RX_DATA);
+
+ //Place the data in the serial output buffer
+ serialBufferOutput(rxData, rxDataBytes);
+
+ //Transmit ACK
+ P2P_SEND_ACK(TRIGGER_TX_ACK);
+ break;
+
+ case DATAGRAM_DUPLICATE:
+ P2P_SEND_ACK(TRIGGER_TX_DUPLICATE_ACK);
+ break;
+
+ case DATAGRAM_DATA_ACK:
+ //Adjust the timestamp offset
+ COMPUTE_TIMESTAMP_OFFSET(rxData, 1, txDataAckUsec);
+
+ //The datagram we are expecting
+ syncChannelTimer(txDataAckUsec); //Adjust freq hop ISR based on remote's remaining clock
+
+ triggerEvent(TRIGGER_RX_ACK);
+
+ //Stop the ACK timer
+ STOP_ACK_TIMER();
+
+ setHeartbeatLong(); //Those who send an ACK have short time to next heartbeat. Those who send a heartbeat or data have long time to next heartbeat.
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+ break;
+
+ case DATAGRAM_REMOTE_COMMAND:
+ triggerEvent(TRIGGER_RX_COMMAND);
+
+ //Determine the number of bytes received
+ length = 0;
+ if ((commandRXHead + rxDataBytes) > sizeof(commandRXBuffer))
+ {
+ //Copy the first portion of the received datagram into the buffer
+ length = sizeof(commandRXBuffer) - commandRXHead;
+ memcpy(&commandRXBuffer[commandRXHead], rxData, length);
+ commandRXHead = 0;
+ }
+
+ //Copy the remaining portion of the received datagram into the buffer
+ memcpy(&commandRXBuffer[commandRXHead], &rxData[length], rxDataBytes - length);
+ commandRXHead += rxDataBytes - length;
+ commandRXHead %= sizeof(commandRXBuffer);
+
+ //Transmit ACK
+ P2P_SEND_ACK(TRIGGER_TX_ACK);
+ break;
+
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ triggerEvent(TRIGGER_RX_COMMAND_RESPONSE);
+
+ //Print received data. This is blocking but we do not use the serialTransmitBuffer because we're in command mode (and it's not much data to print).
+ for (int x = 0 ; x < rxDataBytes ; x++)
+ Serial.write(rxData[x]);
+
+ //Transmit ACK
+ P2P_SEND_ACK(TRIGGER_TX_ACK);
+ break;
+ }
+ }
+
+ else if (receiveInProcess() == false)
+ {
+ //----------
+ //Priority 1: Transmit a HEARTBEAT if necessary
+ //----------
+ heartbeatTimeout = ((millis() - heartbeatTimer) > heartbeatRandomTime);
+ if (heartbeatTimeout)
+ {
+ if (xmitDatagramP2PHeartbeat() == true)
+ {
+ triggerEvent(TRIGGER_TX_HEARTBEAT);
+ changeState(RADIO_P2P_LINK_UP_WAIT_TX_DONE);
+ }
+
+ //Save the message for retransmission
+ SAVE_TX_BUFFER();
+ setHeartbeatLong(); //We're sending a heartbeat, so don't be the first to send next heartbeat
+
+ START_ACK_TIMER();
+ }
+
+ //----------
+ //Priority 2: Wait for an outstanding ACK until it is received, don't
+ //transmit any other data
+ //----------
+
+ //An ACK is expected when the ACK timer running
+ else if (ackTimer)
+ {
+ //Throttle back retransmits based on the number of retransmits we've attempted
+ //retransmitTimeout is a random number set in retransmitDatagram
+ if (millis() - datagramTimer > retransmitTimeout)
+ {
+ //Determine if another retransmission is allowed
+ if ((!settings.maxResends) || (frameSentCount < settings.maxResends))
+ {
+ lostFrames++;
+
+ //Display the retransmit
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrintln("RX: ACK Timeout");
+ outputSerialData(true);
+ }
+
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Retransmit ");
+ systemPrint(frameSentCount);
+ systemPrint(", ");
+ systemPrint(radioDatagramType[txControl.datagramType]);
+ switch (txControl.datagramType)
+ {
+ default:
+ systemPrintln();
+ break;
+
+ case DATAGRAM_DATA:
+ case DATAGRAM_DATA_ACK:
+ case DATAGRAM_REMOTE_COMMAND:
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ case DATAGRAM_HEARTBEAT:
+ systemPrint(" (ACK #");
+ systemPrint(txControl.ackNumber);
+ systemPrint(")");
+ systemPrintln();
+ break;
+ }
+ outputSerialData(true);
+ }
+
+ //Attempt the retransmission
+ RESTORE_TX_BUFFER();
+ if (rexmtControl.datagramType == DATAGRAM_HEARTBEAT)
+ {
+ //Never retransmit the heartbeat, always send a new version to
+ //send the updated time value
+ if (xmitDatagramP2PHeartbeat() == true)
+ {
+ triggerEvent(TRIGGER_TX_HEARTBEAT);
+ changeState(RADIO_P2P_LINK_UP_WAIT_TX_DONE);
+ }
+ }
+ else if (retransmitDatagram(NULL) == true)
+ {
+ triggerEvent(TRIGGER_RETRANSMIT);
+ changeState(RADIO_P2P_LINK_UP_WAIT_TX_DONE);
+ }
+
+ //We're re-sending data, so don't be the first to send next heartbeat
+ setHeartbeatLong();
+ START_ACK_TIMER();
+ }
+ else
+ {
+ lostFrames++;
+
+ //Failed to reach the other system, break the link
+ triggerEvent(TRIGGER_RETRANSMIT_FAIL);
+
+ //Break the link
+ breakLink();
+ }
+ }
+ }
+
+ //----------
+ //Priority 3: Send the entire command or response, toggle between waiting
+ //for ACK above and transmitting the command or response
+ //----------
+
+ else if (availableTXCommandBytes()) //If we have command bytes to send out
+ {
+ //Load command bytes into outgoing packet
+ readyOutgoingCommandPacket(0);
+
+ if (remoteCommandResponse)
+ {
+ //Send the command response
+ if (xmitDatagramP2PCommandResponse() == true)
+ {
+ triggerEvent(TRIGGER_TX_COMMAND_RESPONSE);
+ changeState(RADIO_P2P_LINK_UP_WAIT_TX_DONE);
+ }
+ }
+ else
+ {
+ //Send the command
+ if (xmitDatagramP2PCommand() == true)
+ {
+ triggerEvent(TRIGGER_TX_COMMAND);
+ changeState(RADIO_P2P_LINK_UP_WAIT_TX_DONE);
+ }
+ }
+
+ //Save the message for retransmission
+ SAVE_TX_BUFFER();
+ setHeartbeatLong(); //We're sending command, so don't be the first to send next heartbeat
+
+ START_ACK_TIMER();
+ }
+
+ //----------
+ //Lowest Priority: Check for data to send
+ //----------
+
+ //If we have data, try to send it out
+ else if (availableRadioTXBytes())
+ {
+ //Check if we are yielding for 2-way comm
+ if (requestYield == false ||
+ (requestYield == true && (millis() - yieldTimerStart > (settings.framesToYield * maxFrameAirTimeMsec)))
+ )
+ {
+ //Yield has expired, allow transmit.
+ requestYield = false;
+
+ //Check for time to send serial data
+ if (processWaitingSerial(heartbeatTimeout) == true)
+ {
+ if (xmitDatagramP2PData() == true)
+ {
+ triggerEvent(TRIGGER_TX_DATA);
+ changeState(RADIO_P2P_LINK_UP_WAIT_TX_DONE);
+ }
+
+ //Save the message for retransmission
+ SAVE_TX_BUFFER();
+ setHeartbeatLong(); //We're sending data, so don't be the first to send next heartbeat
+
+ START_ACK_TIMER();
+ }
+ }
+ }
+ }
+
+ //----------
+ //Always check for link timeout
+ //----------
+ if ((millis() - linkDownTimer) >= (P2P_LINK_BREAK_MULTIPLIER * settings.heartbeatTimeout))
+ //Break the link
+ breakLink();
+ break;
+
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ //Multi-Point Data Exchange
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+ /*
+ Server Client
+
+ Reset Reset
+ | |
+ | |
+ V V
+ .--------------> RADIO_MP_STANDBY RADIO_DISCOVER_BEGIN
+ | | |
+ | No TX | |
+ | Do ??? RX other V |
+ +<--------+<------------+ V
+ ^ | | .--------> RADIO_DISCOVER_SCANNING
+ | | TX Resp | | TX done |
+ | | | | |
+ | | | WAIT_TX_FIND_PARTNER_DONE |
+ | .---' | ^ |
+ | | RX | | |
+ | | FIND_PARTNER | < - - - - - - | TX FIND_PARTNER |
+ | | | | |
+ | | | | Delay |
+ | | | | 10 Sec |
+ | | | +<----------. |
+ | | | ^ | |
+ | | | | Yes | No |
+ | | | + <---- Loops < 10 |
+ | | | ^ ^ |
+ | | | No | Yes | |
+ | | | Channel 0 ------' |
+ | | | ^ |
+ | | | | Hop reverse |
+ | | | | RX timeout V
+ | | | '---------------------+
+ | | | |
+ | | | |
+ | | TX | |
+ | | SYNC_CLOCKS | - - - - - - - - - - - - - - - - - > | RX SYNC_CLOCKS
+ | | | |
+ | | | | Sync clocks
+ | | v | Update channel #
+ | '-----> RADIO_MP_WAIT_TX_DONE |
+ | | |
+ | v |
+ `-----------------------+<--------------------------------------'
+
+ */
+
+ //====================
+ //Start searching for other radios
+ //====================
+ case RADIO_DISCOVER_BEGIN:
+ if (settings.server)
+ {
+ changeState(RADIO_MP_STANDBY);
+ break;
+ }
+
+ //If our airspeed is so low that a FindPartner packet will take more than half a dwell time
+ //then skip active discovery and go to standby
+ if (((frameAirTimeUsec + txDataAckUsec + settings.txToRxUsec) / 1000) > (settings.maxDwellTime / 2))
+ {
+ stopChannelTimer();
+ channelNumber = 0;
+ setRadioFrequency(false);
+ changeState(RADIO_DISCOVER_STANDBY);
+ }
+ else
+ {
+ if (settings.debugSync)
+ {
+ systemPrintln("Start scanning");
+ outputSerialData(true);
+ }
+
+ multipointChannelLoops = 0;
+
+ //Mark start time for uptime calculation
+ lastLinkUpTime = millis();
+
+ triggerEvent(TRIGGER_MP_SCAN);
+ changeState(RADIO_DISCOVER_SCANNING);
+ }
+ break;
+
+ //====================
+ //Walk through channel table backwards, transmitting a FIND_PARTNER and looking for a SYNC_CLOCKS
+ //====================
+ case RADIO_DISCOVER_SCANNING:
+ if (settings.server)
+ {
+ changeState(RADIO_MP_STANDBY);
+ break;
+ }
+
+ stopChannelTimer(); //Stop hopping - multipoint discovery
+
+ if (transactionComplete)
+ {
+ //Decode the received datagram
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_UNKNOWN_PACKET);
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("Scan: Unhandled packet type ");
+ systemPrint(radioDatagramType[packetType]);
+ systemPrintln();
+ outputSerialData(true);
+ }
+ break;
+
+ case DATAGRAM_BAD:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_CRC_ERROR:
+ triggerEvent(TRIGGER_CRC_ERROR);
+ break;
+
+ case DATAGRAM_NETID_MISMATCH:
+ triggerEvent(TRIGGER_NETID_MISMATCH);
+ break;
+
+ case DATAGRAM_ZERO_ACKS:
+ case DATAGRAM_DATA:
+ case DATAGRAM_DATA_ACK:
+ case DATAGRAM_FIND_PARTNER: //Clients do not respond to FIND_PARTNER, only the server
+ case DATAGRAM_REMOTE_COMMAND:
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ //We should not be receiving these datagrams, but if we do, just ignore
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_SYNC_CLOCKS:
+ if (!settings.server)
+ {
+ //Change to the server's channel number
+ channelNumber = rxData[0];
+ setRadioFrequency(false);
+
+ //Update the timestamp
+ COMPUTE_TIMESTAMP_OFFSET(rxData + 1, 0, txSyncClocksUsec);
+
+ //Server has responded to FIND_PARTNER with SYNC_CLOCKS
+ //Start and adjust freq hop ISR based on remote's remaining clock
+ startChannelTimer();
+ channelTimerStart -= settings.maxDwellTime;
+ syncChannelTimer(txSyncClocksUsec);
+ triggerEvent(TRIGGER_RX_SYNC_CLOCKS);
+
+ if (settings.debugSync)
+ {
+ systemPrint(" Channel Number: ");
+ systemPrintln(channelNumber);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+
+ lastPacketReceived = millis(); //Reset
+ changeState(RADIO_MP_STANDBY);
+ }
+ break;
+ }
+ }
+
+ //Nothing received
+ else if (receiveInProcess() == false)
+ {
+ //Check for a receive timeout
+ timeoutMsec = settings.overheadTime + ((frameAirTimeUsec + txDataAckUsec + settings.txToRxUsec) / 1000);
+ if ((millis() - datagramTimer) >= timeoutMsec)
+ {
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrintln("MP: SYNC_CLOCKS Timeout");
+ outputSerialData(true);
+ }
+
+ //Move to previous channel in table
+ hopChannelReverse();
+
+ if (channelNumber == 0) multipointChannelLoops++;
+
+ //Limit agressive discovery mode to 10s. After that, move to passive and wait for HB.
+ unsigned long multipointTimeForOneScan = ((frameAirTimeUsec + txDataAckUsec + settings.txToRxUsec) / 1000) * settings.numberOfChannels;
+ int multipointMaxLoops = 10000 / multipointTimeForOneScan;
+
+ if (multipointChannelLoops >= multipointMaxLoops)
+ {
+ multipointChannelLoops = 0;
+
+ //Give up, return to channel 0, and wait in Standby for Server to Xmit HB
+ channelNumber = 0;
+ setRadioFrequency(false);
+ changeState(RADIO_DISCOVER_STANDBY);
+ }
+
+ //Send FIND_PARTNER
+ else if (xmitDatagramP2PFindPartner() == true)
+ {
+ triggerEvent(TRIGGER_TX_FIND_PARTNER);
+ changeState(RADIO_DISCOVER_WAIT_TX_FIND_PARTNER_DONE);
+ }
+ }
+ }
+
+ break;
+
+ //====================
+ //Wait for the FIND_PARTNER to complete transmission
+ //====================
+ case RADIO_DISCOVER_WAIT_TX_FIND_PARTNER_DONE:
+ if (transactionComplete)
+ {
+ transactionComplete = false; //Reset ISR flag
+ irqFlags = radio.getIRQFlags();
+ returnToReceiving();
+ changeState(RADIO_DISCOVER_SCANNING);
+ }
+ break;
+
+ //====================
+ //Wait for the Server to transmit a HB on Channel 0
+ //====================
+ case RADIO_DISCOVER_STANDBY:
+
+ //Process the receive packet
+ if (transactionComplete == true)
+ {
+ triggerEvent(TRIGGER_MP_PACKET_RECEIVED);
+
+ //Decode the received datagram
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_UNKNOWN_PACKET);
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("MP Standby: Unhandled packet type ");
+ systemPrint(radioDatagramType[packetType]);
+ systemPrintln();
+ outputSerialData(true);
+ }
+ break;
+
+ case DATAGRAM_BAD:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_CRC_ERROR:
+ triggerEvent(TRIGGER_CRC_ERROR);
+ break;
+
+ case DATAGRAM_NETID_MISMATCH:
+ triggerEvent(TRIGGER_NETID_MISMATCH);
+ break;
+
+ case DATAGRAM_SYNC_CLOCKS:
+ case DATAGRAM_ZERO_ACKS:
+ case DATAGRAM_DATAGRAM:
+ case DATAGRAM_DATA_ACK:
+ case DATAGRAM_REMOTE_COMMAND:
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ //We should not be receiving these datagrams, but if we do, just ignore
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_FIND_PARTNER:
+ triggerEvent(TRIGGER_RX_FIND_PARTNER);
+ break;
+
+ case DATAGRAM_HEARTBEAT:
+ //Sync clock if server sent the heartbeat
+ if (settings.server == false)
+ {
+ //Change to the server's channel number
+ channelNumber = rxData[0];
+ setRadioFrequency(false);
+
+ //Start and adjust freq hop ISR based on remote's remaining clock
+ startChannelTimer();
+ channelTimerStart -= settings.maxDwellTime;
+ syncChannelTimer(txSyncClocksUsec);
+ triggerEvent(TRIGGER_RX_SYNC_CLOCKS);
+
+ if (settings.debugSync)
+ {
+ systemPrint(" Channel Number: ");
+ systemPrintln(channelNumber);
+ outputSerialData(true);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ }
+
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+
+ lastPacketReceived = millis(); //Update timestamp for Link LED
+
+ //Received heartbeat - do not ack.
+ triggerEvent(TRIGGER_RX_HEARTBEAT);
+
+ blinkHeartbeatLed(true);
+
+ if (settings.debugSync)
+ systemPrintln("Received HB, leaving DISCOVER standby");
+
+ changeState(RADIO_MP_STANDBY);
+ }
+
+ break;
+
+ case DATAGRAM_DATA:
+ //Don't deal with data until we are sync'd with server
+ triggerEvent(TRIGGER_RX_DATA);
+ break;
+ }
+ }
+ break;
+
+ //====================
+ //Wait for the next operation (listed in priority order):
+ // * Frame received
+ // * Data to send
+ // * Time to send HEARTBEAT
+ // * Link timeout
+ //====================
+ case RADIO_MP_STANDBY:
+ //Hop channels when required
+ if (timeToHop == true)
+ hopChannel();
+
+ //Process the receive packet
+ if (transactionComplete == true)
+ {
+ triggerEvent(TRIGGER_MP_PACKET_RECEIVED);
+
+ //Decode the received datagram
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_UNKNOWN_PACKET);
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("MP Standby: Unhandled packet type ");
+ systemPrint(radioDatagramType[packetType]);
+ systemPrintln();
+ outputSerialData(true);
+ }
+ break;
+
+ case DATAGRAM_BAD:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_CRC_ERROR:
+ triggerEvent(TRIGGER_CRC_ERROR);
+ break;
+
+ case DATAGRAM_NETID_MISMATCH:
+ triggerEvent(TRIGGER_NETID_MISMATCH);
+ break;
+
+ case DATAGRAM_SYNC_CLOCKS:
+ case DATAGRAM_ZERO_ACKS:
+ case DATAGRAM_DATAGRAM:
+ case DATAGRAM_DATA_ACK:
+ case DATAGRAM_REMOTE_COMMAND:
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ //We should not be receiving these datagrams, but if we do, just ignore
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_FIND_PARTNER:
+ triggerEvent(TRIGGER_RX_FIND_PARTNER);
+
+ //A new radio is saying hello
+ if (settings.server == true)
+ {
+ //Ack their FIND_PARTNER with SYNC_CLOCK
+ if (xmitDatagramP2PSyncClocks() == true)
+ {
+ triggerEvent(TRIGGER_TX_SYNC_CLOCKS);
+ changeState(RADIO_MP_WAIT_TX_DONE);
+ }
+ }
+ else
+ {
+ changeState(RADIO_MP_STANDBY);
+ }
+ break;
+
+ case DATAGRAM_HEARTBEAT:
+ //Sync clock if server sent the heartbeat
+ if (settings.server == false)
+ {
+ //Adjust freq hop ISR based on server's remaining clock
+ syncChannelTimer(txHeartbeatUsec);
+
+ //Received heartbeat - do not ack.
+ triggerEvent(TRIGGER_RX_HEARTBEAT);
+
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+
+ lastPacketReceived = millis(); //Update timestamp for Link LED
+
+ blinkHeartbeatLed(true);
+ changeState(RADIO_MP_STANDBY);
+ }
+ break;
+
+ case DATAGRAM_DATA:
+ //Received data - do not ack.
+ triggerEvent(TRIGGER_RX_DATA);
+
+ //Place any available data in the serial output buffer
+ serialBufferOutput(rxData, rxDataBytes);
+
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+
+ lastPacketReceived = millis(); //Update timestamp for Link LED
+
+ changeState(RADIO_MP_STANDBY);
+ break;
+ }
+ }
+
+ //If the radio is available, send any data in the serial buffer over the radio
+ else if (receiveInProcess() == false)
+ {
+ heartbeatTimeout = ((millis() - heartbeatTimer) > heartbeatRandomTime);
+
+ //Only the server transmits heartbeats
+ if ((settings.server == true) && (heartbeatTimeout))
+ {
+ if (xmitDatagramMpHeartbeat() == true)
+ {
+ triggerEvent(TRIGGER_TX_HEARTBEAT);
+ blinkHeartbeatLed(true);
+ setHeartbeatMultipoint(); //We're sending something with clock data so reset heartbeat timer
+ changeState(RADIO_MP_WAIT_TX_DONE); //Wait for heartbeat to transmit
+ }
+ }
+
+ //Check for time to send serial data
+ else if (availableRadioTXBytes() && (processWaitingSerial(heartbeatTimeout) == true))
+ {
+ if (xmitDatagramMpData() == true)
+ {
+ triggerEvent(TRIGGER_MP_TX_DATA);
+ changeState(RADIO_MP_WAIT_TX_DONE);
+ }
+ }
+
+ //If the client hasn't received a packet in too long, return to scanning
+ else if (settings.server == false)
+ {
+ if ((millis() - lastPacketReceived) > (settings.heartbeatTimeout * 3))
+ {
+ if (settings.debugSync)
+ {
+ systemPrintln("HEARTBEAT Timeout");
+ outputSerialData(true);
+ dumpClockSynchronization();
+ }
+ changeState(RADIO_DISCOVER_BEGIN);
+ }
+ }
+ }
+ break;
+
+ //====================
+ //Wait for the frame transmission to complete
+ //====================
+ case RADIO_MP_WAIT_TX_DONE:
+ //Hop channels when required
+ if (timeToHop == true)
+ hopChannel();
+
+ //If transmit is complete then start receiving
+ if (transactionComplete == true)
+ {
+ transactionComplete = false; //Reset ISR flag
+ irqFlags = radio.getIRQFlags();
+ returnToReceiving();
+ changeState(RADIO_MP_STANDBY);
+ }
+ break;
+
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ //Client Training
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+ /*
+
+ 2 Second Button Press ATT Command
+ | |
+ | |
+ +--------------------------------------------'
+ |
+ V
+ commandSaveSettings
+ |
+ V
+ beginTrainingClient
+ |
+ V
+ +<--------------------------------------.
+ | |
+ | Send FIND_PARTNER |
+ | | Timeout
+ V |
+ RADIO_TRAIN_WAIT_TX_FIND_PARTNER_DONE |
+ | |
+ V |
+ RADIO_TRAIN_WAIT_RX_RADIO_PARAMETERS ---------->+
+ | |
+ | RX RADIO_PARAMETERS |
+ | ATO | or 2 Second
+ | Send ACK ATZ | Button Push
+ V | && (! Command Mode)
+ RADIO_TRAIN_WAIT_TX_ACK_DONE |
+ | V
+ V commandRestoreSettings(writeOnCommandExit)
+ endTrainingClientServer |
+ | |
+ | |
+ | commandRestoreSettings(true) |
+ V V
+ Reboot Return to
+ Previous mode
+ */
+
+ //====================
+ //Wait for the FIND_PARTNER to complete transmission
+ //====================
+ case RADIO_TRAIN_WAIT_TX_FIND_PARTNER_DONE:
+
+ //If dio0ISR has fired, we are done transmitting
+ if (transactionComplete == true)
+ {
+ transactionComplete = false;
+
+ //Indicate that the receive is complete
+ triggerEvent(TRIGGER_TRAINING_CLIENT_TX_FIND_PARTNER_DONE);
+ irqFlags = radio.getIRQFlags();
+
+ //Start the receive operation
+ returnToReceiving();
+
+ //Set the next state
+ changeState(RADIO_TRAIN_WAIT_RX_RADIO_PARAMETERS);
+ }
+ break;
+
+ //====================
+ //Wait to receive the radio parameters
+ //====================
+ case RADIO_TRAIN_WAIT_RX_RADIO_PARAMETERS:
+
+ //If dio0ISR has fired, a packet has arrived
+ if (transactionComplete == true)
+ {
+ trainingPreviousRxInProgress = false;
+
+ //Decode the received datagram
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_TRAINING_PARAMS:
+ //Verify the IDs
+ if ((memcmp(rxData, myUniqueId, UNIQUE_ID_BYTES) != 0)
+ && (memcmp(rxData, myUniqueId, UNIQUE_ID_BYTES) != 0))
+ {
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+ }
+
+ //Save the training partner ID
+ memcpy(trainingPartnerID, &rxData[UNIQUE_ID_BYTES], UNIQUE_ID_BYTES);
+
+ //Get the radio parameters
+ updateRadioParameters(&rxData[UNIQUE_ID_BYTES * 2]);
+
+ //Acknowledge the radio parameters
+ if (xmitDatagramTrainingAck(&rxData[UNIQUE_ID_BYTES]) == true)
+ changeState(RADIO_TRAIN_WAIT_TX_PARAM_ACK_DONE);
+ break;
+ }
+ }
+
+ //Determine if a receive is in process
+ else if (receiveInProcess())
+ {
+ if (!trainingPreviousRxInProgress)
+ {
+ trainingPreviousRxInProgress = true;
+ triggerEvent(TRIGGER_TRAINING_CLIENT_RX_PARAMS);
+ }
+ }
+
+ //Check for a receive timeout
+ else if ((millis() - datagramTimer) > (settings.clientFindPartnerRetryInterval * 1000))
+ {
+ xmitDatagramTrainingFindPartner();
+ }
+ break;
+
+ //====================
+ //Wait for the ACK frame to complete transmission
+ //====================
+ case RADIO_TRAIN_WAIT_TX_PARAM_ACK_DONE:
+
+ //If dio0ISR has fired, we are done transmitting
+ if (transactionComplete == true)
+ {
+ transactionComplete = false;
+ irqFlags = radio.getIRQFlags();
+ endClientServerTraining(TRIGGER_TRAINING_CLIENT_TX_ACK_DONE);
+ }
+ break;
+
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ //Server Training
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+ /*
+
+ Command Mode 5 second button press
+ | |
+ | ATT |
+ | |
+ V |
+ +<---------------------'
+ |
+ V
+ commandSaveSettings
+ |
+ V
+ beginTrainingServer
+ |
+ V
+ +<--------------------------------.
+ | |
+ V |
+ .------ RADIO_TRAIN_WAIT_FOR_FIND_PARTNER |
+ | | |
+ | | Send RADIO_PARAMS |
+ | | |
+ | V |
+ | RADIO_TRAIN_WAIT_TX_RADIO_PARAMS_DONE -----'
+ |
+ |
+ | ATO, ATZ or (2 second training button press && ! command mode)
+ |
+ `---------------.
+ |
+ V
+ commandRestoreSettings(writeOnCommandExit)
+ |
+ V
+ +----------------------------.
+ | |
+ | ATZ command | ATO command
+ | |
+ V V
+ Reboot Return to
+ Previous Mode
+ */
+
+ //====================
+ //Wait for a FIND_PARTNER frame from a client
+ //====================
+ case RADIO_TRAIN_WAIT_FOR_FIND_PARTNER:
+
+ //If dio0ISR has fired, a packet has arrived
+ if (transactionComplete == true)
+ {
+ trainingPreviousRxInProgress = false;
+
+ //Decode the received datagram
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_TRAINING_FIND_PARTNER:
+ //Save the client ID
+ memcpy(trainingPartnerID, rxData, UNIQUE_ID_BYTES);
+
+ //Find a slot in the NVM unique ID table
+ for (index = 0; index < MAX_VC; index++)
+ if (!nvmIsVcUniqueIdSet(index))
+ {
+ //Save the client unique ID
+ nvmSaveUniqueId(index, trainingPartnerID);
+ break;
+ }
+
+ //Wait for the transmit to complete
+ if (xmitDatagramTrainRadioParameters(trainingPartnerID) == true)
+ changeState(RADIO_TRAIN_WAIT_TX_RADIO_PARAMS_DONE);
+ break;
+
+ case DATAGRAM_TRAINING_ACK:
+ //Verify the client ID
+ if (memcmp(trainingPartnerID, &rxData[UNIQUE_ID_BYTES], UNIQUE_ID_BYTES) == 0)
+ {
+ //Don't respond to the client ACK, just start another receive operation
+ triggerEvent(TRIGGER_TRAINING_SERVER_RX_ACK);
+
+ //Print the client trained message
+ systemPrint("Client ");
+ systemPrintUniqueID(trainingPartnerID);
+ systemPrintln(" Trained");
+
+ //If we are training via button, and in point to point mode, and the user has not manually set the server
+ //then reboot with current settings after a single client acks
+ if (inTraining
+ && (trainingSettings.operatingMode == MODE_POINT_TO_POINT)
+ && (!trainingSettings.server))
+ {
+ //Save the training parameters
+ settings = trainingSettings;
+ recordSystemSettings();
+
+ //Reboot the radio with the newly generated random netID/Key parameters
+ commandReset();
+ }
+ }
+ break;
+ }
+ }
+
+ //Determine if a receive is in process
+ else if (receiveInProcess())
+ if (!trainingPreviousRxInProgress)
+ {
+ trainingPreviousRxInProgress = true;
+ triggerEvent(TRIGGER_TRAINING_SERVER_RX);
+ }
+ break;
+
+ //====================
+ //Wait for the radio parameters to complete transmission
+ //====================
+ case RADIO_TRAIN_WAIT_TX_RADIO_PARAMS_DONE:
+
+ //If dio0ISR has fired, we are done transmitting
+ if (transactionComplete == true)
+ {
+ transactionComplete = false;
+
+ //Indicate that the receive is complete
+ triggerEvent(TRIGGER_TRAINING_SERVER_TX_PARAMS_DONE);
+ irqFlags = radio.getIRQFlags();
+
+ //Start the receive operation
+ returnToReceiving();
+
+ //Set the next state
+ changeState(RADIO_TRAIN_WAIT_FOR_FIND_PARTNER);
+ }
+ break;
+
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+ //Virtual Circuit States
+ //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+ /*
+
+ Radio States:
+
+ RADIO_RESET
+ |
+ V
+ RADIO_DISCOVER_SCANNING
+ |
+ V
+ +<-------------------------.
+ | |
+ | Send VC_HEARTBEAT |
+ | |
+ V |
+ .-----> RADIO_VC_WAIT_TX_DONE |
+ | | |
+ | V | Heartbeat timeout
+ | RADIO_VC_WAIT_RECEIVE ---------------'
+ | |
+ | ACK Timeout | Receive serial data
+ | Retransmit | Send DATA
+ | |
+ | Remote Cmd Rsp | Remote Cmd
+ | Send Cmd Rsp | Send remote Cmd
+ | |
+ '-----------------'
+
+ The ACK synchronization handshake occurs between VCs that want to
+ communicate. Normally this occurs between the client and the server, but
+ may also occur between two clients that want to communicate with each
+ other. One of the systems initiates the three way handshake by sending
+ UNKNOWN_ACKS. The second system responses with SYNC_ACKSZERO_ACKS causing the
+ first system to respond with ZERO_ACKS.
+
+ 3-way Handshake to zero ACKs:
+
+ TX UNKNOWN_ACKS --> RX SYNC_ACKS --> TX ZERO_ACKS
+ or
+ RX UNKNOWN_ACKS --> TX SYNC_ACKS --> RX ZERO_ACKS
+
+ VC States:
+
+ .-------------> VC_STATE_LINK_DOWN <-------------------------------------.
+ | | HB Timeout |
+ | | HEARTBEAT received |
+ | HB Timeout v |
+ +<----------- VC_STATE_LINK_ALIVE ------------------------. |
+ ^ | RX UNKNOWN_ACKS | |
+ | | ATC command | |
+ | HB Timeout V | |
+ +<--------- VC_STATE_SEND_UNKNOWN_ACKS <-. | |
+ ^ | | | |
+ | TX UNKNOWN_ACKS | ZERO_ACKS RX | | |
+ | TX Complete | Timeout | RX | |
+ | HB Timeout V | UNKNOWN_ACKS V |
+ +<---------- VC_STATE_WAIT_SYNC_ACKS --->+----------->+-->+ |
+ ^ | ^ ^ | TX |
+ | | RX SYNC_ACKS | ZERO_ACKS | | SYNC_ACKS |
+ | | TX ZERO_ACKS | RX | | TX Complete |
+ | | TX Complete | TMO | V |
+ | Zero ACK values | | VC_STATE_WAIT_ZERO_ACKS --'
+ | | .---------' |
+ | | | RX UNKNOWN_ACKS | RX ZERO_ACKS
+ | HB Timeout V | | Zero ACK values
+ '-------------- VC_STATE_CONNECTED <----------------------'
+
+ */
+
+ //====================
+ //Wait for a HEARTBEAT from the server
+ //====================
+ case RADIO_VC_WAIT_SERVER:
+ //The server should never be in this state
+ if (myVc == VC_SERVER)
+ {
+ changeState(RADIO_VC_WAIT_RECEIVE);
+ break;
+ }
+
+ //Stop the frequency hopping
+ if (channelTimerMsec)
+ stopChannelTimer();
+ if (channelNumber != 0)
+ {
+ channelNumber = 0;
+ setRadioFrequency(false);
+ }
+
+ //If dio0ISR has fired, a packet has arrived
+ currentMillis = millis();
+ if (transactionComplete == true)
+ {
+ //Decode the received datagram
+ PacketType packetType = rcvDatagram();
+
+ //Process the received datagram
+ if ((packetType == DATAGRAM_VC_HEARTBEAT) && (rxSrcVc == VC_SERVER))
+ {
+ virtualCircuitList[VC_SERVER].lastTrafficMillis = currentMillis;
+
+ //Start the channel timer
+ startChannelTimer();
+ channelTimerStart -= settings.maxDwellTime >> 1;
+
+ //Synchronize the channel timer with the server
+ vcReceiveHeartbeat(millis() - currentMillis);
+
+ //Delay for a while before sending the HEARTBEAT
+ heartbeatRandomTime = random((settings.heartbeatTimeout * 2) / 10, settings.heartbeatTimeout);
+ changeState(RADIO_VC_WAIT_RECEIVE);
+ }
+ else
+ //Ignore this datagram
+ triggerEvent(TRIGGER_BAD_PACKET);
+ }
+ break;
+
+ //====================
+ //Wait for the transmission to complete
+ //====================
+ case RADIO_VC_WAIT_TX_DONE:
+ //Hop channels when required
+ if (timeToHop == true)
+ hopChannel();
+
+ //If dio0ISR has fired, we are done transmitting
+ if (transactionComplete == true)
+ {
+ //Indicate that the transmission is complete
+ transactionComplete = false;
+ triggerEvent(TRIGGER_TX_DONE);
+ irqFlags = radio.getIRQFlags();
+
+ //Start the receive operation
+ returnToReceiving();
+
+ //Set the next state
+ if (virtualCircuitList[VC_SERVER].vcState == VC_STATE_LINK_DOWN)
+ changeState(RADIO_VC_WAIT_SERVER);
+ else
+ changeState(RADIO_VC_WAIT_RECEIVE);
+ }
+ break;
+
+ //====================
+ //Wait for the next operation (listed in priority order):
+ // * Frame received
+ // * Time to send HEARTBEAT
+ // * Time to retransmit previous frame
+ // * Remote command response to send
+ // * Data to send
+ // * Link timeout
+ //====================
+ case RADIO_VC_WAIT_RECEIVE:
+ //Hop channels when required
+ if (timeToHop == true)
+ hopChannel();
+
+ //If dio0ISR has fired, a packet has arrived
+ currentMillis = millis();
+ if (transactionComplete == true)
+ {
+ //Decode the received datagram
+ PacketType packetType = rcvDatagram();
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)rxData;
+
+ //Indicate receive traffic from this VC including HEARTBEATs
+ if ((uint8_t)rxSrcVc < (uint8_t)MIN_RX_NOT_ALLOWED)
+ virtualCircuitList[rxSrcVc & VCAB_NUMBER_MASK].lastTrafficMillis = currentMillis;
+
+ //Process the received datagram
+ switch (packetType)
+ {
+ default:
+ triggerEvent(TRIGGER_BAD_PACKET);
+ break;
+
+ case DATAGRAM_VC_HEARTBEAT:
+ vcReceiveHeartbeat(millis() - currentMillis);
+ break;
+
+ case DATAGRAM_DATA:
+ triggerEvent(TRIGGER_RX_DATA);
+
+ //Move the data into the serial output buffer
+ if (settings.debugSerial)
+ {
+ systemPrint("updateRadioState moving ");
+ systemPrint(rxDataBytes);
+ systemPrintln(" bytes from inputBuffer into serialTransmitBuffer");
+ outputSerialData(true);
+ }
+ systemWrite(START_OF_VC_SERIAL);
+ serialBufferOutput(rxData, rxDataBytes);
+
+ //Acknowledge the data frame
+ if (xmitVcAckFrame(rxSrcVc))
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ break;
+
+ case DATAGRAM_DATAGRAM:
+ triggerEvent(TRIGGER_RX_DATAGRAM);
+
+ //Move the data into the serial output buffer
+ if (settings.debugSerial)
+ {
+ systemPrint("updateRadioState moving ");
+ systemPrint(rxDataBytes);
+ systemPrintln(" bytes from inputBuffer into serialTransmitBuffer");
+ outputSerialData(true);
+ }
+ systemWrite(START_OF_VC_SERIAL);
+ serialBufferOutput(rxData, rxDataBytes);
+
+ //Datagrams do NOT get ACKed
+ break;
+
+ case DATAGRAM_DATA_ACK:
+ triggerEvent(TRIGGER_RX_ACK);
+ vcSendPcAckNack(rexmtTxDestVc, true);
+ STOP_ACK_TIMER();
+ break;
+
+ case DATAGRAM_DUPLICATE:
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+
+ if (xmitVcAckFrame(rxSrcVc))
+ {
+ triggerEvent(TRIGGER_TX_DUPLICATE_ACK);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+ break;
+
+ //Second step in the 3-way handshake, received UNKNOWN_ACKS, respond
+ //with SYNC_ACKS
+ case DATAGRAM_VC_UNKNOWN_ACKS:
+ triggerEvent(TRIGGER_RX_VC_UNKNOWN_ACKS);
+ if (xmitVcSyncAcks(rxSrcVc))
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ vcChangeState(rxSrcVc, VC_STATE_WAIT_ZERO_ACKS);
+ virtualCircuitList[rxSrcVc].timerMillis = datagramTimer;
+ break;
+
+ //Third step in the 3-way handshake, received SYNC_ACKS, respond with ZERO_ACKS
+ case DATAGRAM_VC_SYNC_ACKS:
+ triggerEvent(TRIGGER_RX_VC_SYNC_ACKS);
+ if (xmitVcZeroAcks(rxSrcVc))
+ {
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ vcZeroAcks(rxSrcVc);
+ vcChangeState(rxSrcVc, VC_STATE_CONNECTED);
+ }
+ break;
+
+ //Last step in the 3-way handshake, received ZERO_ACKS, done
+ case DATAGRAM_VC_ZERO_ACKS:
+ triggerEvent(TRIGGER_RX_VC_ZERO_ACKS);
+ vcZeroAcks(rxSrcVc);
+ vcChangeState(rxSrcVc, VC_STATE_CONNECTED);
+ break;
+
+ case DATAGRAM_REMOTE_COMMAND:
+ triggerEvent(TRIGGER_RX_COMMAND);
+ rmtCmdVc = rxSrcVc;
+
+ //Copy the command into the command buffer
+ commandLength = rxDataBytes - VC_RADIO_HEADER_BYTES;
+ memcpy(commandBuffer, &rxData[VC_RADIO_HEADER_BYTES], commandLength);
+ if (settings.debugSerial)
+ {
+ systemPrint("RX: Moving ");
+ systemPrint(commandLength);
+ systemPrintln(" bytes into commandBuffer");
+ outputSerialData(true);
+ dumpBuffer((uint8_t *)commandBuffer, commandLength);
+ }
+ petWDT();
+
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+
+ //Transmit ACK
+ if (xmitVcAckFrame(rxSrcVc))
+ {
+ triggerEvent(TRIGGER_TX_ACK);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+
+ //Process the command
+ petWDT();
+ printerEndpoint = PRINT_TO_RF; //Send prints to RF link
+ tempSettings = settings;
+ checkCommand(); //Parse the command buffer
+ settings = tempSettings;
+ petWDT();
+ printerEndpoint = PRINT_TO_SERIAL;
+ length = availableTXCommandBytes();
+ if (settings.debugSerial)
+ {
+ systemPrint("RX: checkCommand placed ");
+ systemPrint(length);
+ systemPrintln(" bytes into commandTXBuffer");
+ dumpCircularBuffer(commandTXBuffer, commandTXTail, sizeof(commandTXBuffer), length);
+ outputSerialData(true);
+ petWDT();
+ }
+ break;
+
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ triggerEvent(TRIGGER_RX_COMMAND_RESPONSE);
+
+ //The VC_COMMAND_COMPLETE_MESSAGE is located at the end of the command
+ //response. This method of splitting the message works because the
+ //VC_COMMAND_COMPLETE_MESSAGE is delivered via a separate frame. As
+ //such, the reception is transactional, the frame is either present or
+ //it is not. Determine if the VC_COMMAND_COMPLETE_MESSAGE is contained
+ //in this response.
+ length = rxDataBytes - VC_SERIAL_HEADER_BYTES - sizeof(VC_COMMAND_COMPLETE_MESSAGE);
+ if ((length > rxDataBytes) || (rxData[length] != START_OF_VC_SERIAL))
+ //The VC_COMMAND_COMPLETE_MESSAGE is not in this portion of the response
+ length = rxDataBytes;
+
+ //Transfer the response data to the host
+ if (length)
+ {
+ vcHeader->destVc |= PC_REMOTE_RESPONSE;
+ vcHeader->length = length;
+
+ //Debug the serial path
+ if (settings.debugSerial)
+ {
+ systemPrint("Moving ");
+ systemPrint(length);
+ systemPrintln(" from incomingBuffer to serialTransmitBuffer");
+ dumpBuffer(rxData, length);
+ outputSerialData(true);
+ }
+
+ //Place the data in to the serialTransmitBuffer
+ serialOutputByte(START_OF_VC_SERIAL);
+ serialBufferOutput(rxData, length);
+ }
+
+ //Transfer the VC_COMMAND_COMPLETE_MESSAGE
+ if (length < rxDataBytes)
+ {
+ index = length;
+ length = rxDataBytes - length;
+
+ //Debug the serial path
+ if (settings.debugSerial)
+ {
+ systemPrint("Moving ");
+ systemPrint(length);
+ systemPrintln(" from incomingBuffer to serialTransmitBuffer");
+ dumpBuffer(&rxData[index], length);
+ outputSerialData(true);
+ }
+
+ //Place the data in to the serialTransmitBuffer
+ serialBufferOutput(&rxData[index], length);
+ }
+
+ frequencyCorrection += radio.getFrequencyError() / 1000000.0;
+
+ //ACK the command response
+ if (xmitVcAckFrame(rxSrcVc)) //Transmit ACK
+ {
+ triggerEvent(TRIGGER_TX_ACK);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+ break;
+ }
+ }
+
+ //when not receiving process the pending transmit requests
+ else if (!receiveInProcess())
+ {
+ //----------
+ //Priority 1: Transmit a HEARTBEAT if necessary
+ //----------
+ if (((currentMillis - heartbeatTimer) >= heartbeatRandomTime))
+ {
+ //Send another heartbeat
+ if (xmitVcHeartbeat(myVc, myUniqueId))
+ {
+ if (settings.server)
+ blinkHeartbeatLed(true);
+ triggerEvent(TRIGGER_TX_VC_HEARTBEAT);
+ if (settings.debugHeartbeat && settings.server)
+ systemPrintln(channelNumber);
+ if (((uint8_t)myVc) < MAX_VC)
+ virtualCircuitList[myVc].lastTrafficMillis = currentMillis;
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+ }
+
+ //----------
+ //Priority 2: Wait for an outstanding ACK until it is received, don't
+ //transmit any other data
+ //----------
+ else if (ackTimer)
+ {
+ //Verify that the link is still up
+ txDestVc = rexmtTxDestVc;
+ timeoutMsec = settings.overheadTime + ((frameAirTimeUsec + txDataAckUsec + settings.txToRxUsec) / 1000);
+ if ((txDestVc != VC_BROADCAST)
+ && (virtualCircuitList[txDestVc & VCAB_NUMBER_MASK].vcState == VC_STATE_LINK_DOWN))
+ {
+ //Stop the retransmits
+ STOP_ACK_TIMER();
+ }
+
+ //Check for retransmit needed
+ else if ((currentMillis - ackTimer) >= timeoutMsec)
+ {
+ //Determine if another retransmit is allowed
+ if ((!settings.maxResends) || (rexmtFrameSentCount < settings.maxResends))
+ {
+ rexmtFrameSentCount++;
+
+ //Restore the message for retransmission
+ RESTORE_TX_BUFFER();
+ if (settings.debugDatagrams)
+ {
+ systemPrintTimestamp();
+ systemPrint("TX: Retransmit ");
+ systemPrint(frameSentCount);
+ systemPrint(", ");
+ systemPrint(radioDatagramType[txControl.datagramType]);
+ switch (txControl.datagramType)
+ {
+ default:
+ systemPrintln();
+ break;
+
+ case DATAGRAM_DATA:
+ case DATAGRAM_DATA_ACK:
+ case DATAGRAM_REMOTE_COMMAND:
+ case DATAGRAM_REMOTE_COMMAND_RESPONSE:
+ case DATAGRAM_HEARTBEAT:
+ systemPrint(" (ACK #");
+ systemPrint(txControl.ackNumber);
+ systemPrint(")");
+ systemPrintln();
+ break;
+ }
+ outputSerialData(true);
+ }
+
+ //Retransmit the packet
+ if (retransmitDatagram(((uint8_t)txDestVc <= MAX_VC) ? &virtualCircuitList[txDestVc] : NULL))
+ {
+ triggerEvent(TRIGGER_RETRANSMIT);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+
+ START_ACK_TIMER();
+ lostFrames++;
+ }
+ else
+ {
+ //HEARTBEATs have not timed out, request to reestablish the connection
+ vc->flags.wasConnected = true;
+
+ //Failed to reach the other system, break the link
+ vcBreakLink(txDestVc);
+ }
+ }
+ }
+
+ //----------
+ //Priority 3: Send the entire command response, toggle between waiting for
+ //ACK above and transmitting the command response
+ //----------
+ else if (availableTXCommandBytes())
+ {
+ //Send the next portion of the command response
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)&outgoingPacket[headerBytes];
+ endOfTxData += VC_RADIO_HEADER_BYTES;
+ vcHeader->destVc = rmtCmdVc;
+ vcHeader->srcVc = myVc;
+ vcHeader->length = readyOutgoingCommandPacket(VC_RADIO_HEADER_BYTES)
+ + VC_RADIO_HEADER_BYTES;
+ if (xmitDatagramP2PCommandResponse())
+ {
+ triggerEvent(TRIGGER_TX_COMMAND_RESPONSE);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+
+ START_ACK_TIMER();
+
+ //Save the message for retransmission
+ SAVE_TX_BUFFER();
+ rexmtTxDestVc = txDestVc;
+ }
+
+ //----------
+ //Priority 4: Walk through the 3-way handshake
+ //----------
+ else if (vcConnecting)
+ {
+ for (index = 0; index < MAX_VC; index++)
+ {
+ if (receiveInProcess())
+ break;
+
+ //Determine the first VC that is walking through connections
+ if (vcConnecting & (1 << index))
+ {
+ //Determine if UNKNOWN_ACKS needs to be sent
+ timeoutMsec = settings.overheadTime + ((frameAirTimeUsec + txDataAckUsec + settings.txToRxUsec) / 1000);
+ if (virtualCircuitList[index].vcState <= VC_STATE_SEND_UNKNOWN_ACKS)
+ {
+ //Send the UNKNOWN_ACKS datagram, first part of the 3-way handshake
+ if (xmitVcUnknownAcks(index))
+ {
+ triggerEvent(TRIGGER_RX_VC_UNKNOWN_ACKS);
+ vcChangeState(index, VC_STATE_WAIT_SYNC_ACKS);
+ virtualCircuitList[index].timerMillis = datagramTimer;
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+ }
+
+ //The SYNC_ACKS is handled with the receive code
+ //Check for a timeout waiting for the SYNC_ACKS
+ else if (virtualCircuitList[index].vcState == VC_STATE_WAIT_SYNC_ACKS)
+ {
+ if ((currentMillis - virtualCircuitList[index].timerMillis) >= timeoutMsec)
+ {
+ //Retransmit the UNKNOWN_ACKS
+ if (xmitVcUnknownAcks(index))
+ {
+ triggerEvent(TRIGGER_RX_VC_UNKNOWN_ACKS);
+ virtualCircuitList[index].timerMillis = datagramTimer;
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+ }
+ }
+
+ //The ZERO_ACKS is handled with the receive code
+ //Check for a timeout waiting for the ZERO_ACKS
+ else if (virtualCircuitList[index].vcState == VC_STATE_WAIT_ZERO_ACKS)
+ {
+ if ((currentMillis - virtualCircuitList[index].timerMillis) >= timeoutMsec)
+ {
+ //Retransmit the SYNC_CLOCKS
+ if (xmitVcSyncAcks(index))
+ {
+ triggerEvent(TRIGGER_RX_VC_SYNC_ACKS);
+ virtualCircuitList[index].timerMillis = datagramTimer;
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+ }
+ }
+
+ //Work on only one connection at a time
+ break;
+ }
+ }
+ }
+
+ //----------
+ //Lowest Priority: Check for data to send
+ //----------
+ else if (vcSerialMessageReceived())
+ {
+ //No need to add the VC header since the header is in the radioTxBuffer
+ //Get the VC header
+ vcHeader = (VC_RADIO_MESSAGE_HEADER *)&outgoingPacket[headerBytes];
+ if (vcHeader->destVc == VC_BROADCAST)
+ channel = 0;
+ else
+ channel = (vcHeader->destVc >> VCAB_NUMBER_BITS) & VCAB_CHANNEL_MASK;
+ switch (channel)
+ {
+ case 0: //Data packets
+ //Check for datagram transmission
+ if (vcHeader->destVc == VC_BROADCAST)
+ {
+ //Broadcast this data to all VCs, no ACKs will be received
+ if (xmitVcDatagram())
+ {
+ triggerEvent(TRIGGER_TX_DATA);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+ break;
+ }
+
+ //Transmit the packet
+ if (xmitDatagramP2PData() == true)
+ {
+ triggerEvent(TRIGGER_TX_DATA);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+
+ START_ACK_TIMER();
+
+ //Save the message for retransmission
+ SAVE_TX_BUFFER();
+ rexmtTxDestVc = txDestVc;
+ break;
+
+ case 1: //Remote command packets
+ //Remote commands must not be broadcast
+ if (vcHeader->destVc == VC_BROADCAST)
+ {
+ if (settings.debugSerial || settings.debugTransmit)
+ {
+ systemPrintln("ERROR: Remote commands may not be broadcast!");
+ outputSerialData(true);
+ }
+
+ //Discard this message
+ endOfTxData = &outgoingPacket[headerBytes];
+ break;
+ }
+
+ //Determine if this remote command gets processed on the local node
+ if ((vcHeader->destVc & VCAB_NUMBER_MASK) == myVc)
+ {
+ //Copy the command into the command buffer
+ commandLength = endOfTxData - &outgoingPacket[headerBytes + VC_RADIO_HEADER_BYTES];
+ memcpy(commandBuffer, &outgoingPacket[headerBytes + VC_RADIO_HEADER_BYTES], commandLength);
+ if (settings.debugSerial)
+ {
+ systemPrint("RX: Moving ");
+ systemPrint(commandLength);
+ systemPrintln(" bytes into commandBuffer");
+ outputSerialData(true);
+ dumpBuffer((uint8_t *)commandBuffer, commandLength);
+ }
+ petWDT();
+
+ //Reset the buffer data pointer for the next transmit operation
+ endOfTxData = &outgoingPacket[headerBytes];
+
+ //Process the command
+ petWDT();
+ printerEndpoint = PRINT_TO_RF; //Send prints to RF link
+ tempSettings = settings;
+ checkCommand(); //Parse the command buffer
+ settings = tempSettings;
+ petWDT();
+ printerEndpoint = PRINT_TO_SERIAL;
+ length = availableTXCommandBytes();
+ if (settings.debugSerial)
+ {
+ systemPrint("RX: checkCommand placed ");
+ systemPrint(length);
+ systemPrintln(" bytes into commandTXBuffer");
+ dumpCircularBuffer(commandTXBuffer, commandTXTail, sizeof(commandTXBuffer), length);
+ outputSerialData(true);
+ petWDT();
+ }
+
+ //Break up the command response
+ while (availableTXCommandBytes())
+ readyLocalCommandPacket();
+ break;
+ }
+
+ //Send the remote command
+ vcHeader->destVc &= VCAB_NUMBER_MASK;
+ if (xmitDatagramP2PCommand() == true)
+ {
+ triggerEvent(TRIGGER_TX_COMMAND);
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+
+ START_ACK_TIMER();
+
+ //Save the message for retransmission
+ SAVE_TX_BUFFER();
+ rexmtTxDestVc = txDestVc;
+ break;
+ }
+ }
+ }
+
+ //----------
+ //Check for link timeout
+ //----------
+ serverLinkBroken = false;
+ for (index = 0; index < MAX_VC; index++)
+ {
+ //Don't timeout the connection to myself
+ if (index == myVc)
+ continue;
+
+ //Determine if the link has timed out
+ vc = &virtualCircuitList[index];
+ if ((vc->vcState != VC_STATE_LINK_DOWN) && (serverLinkBroken
+ || ((currentMillis - vc->lastTrafficMillis) > (VC_LINK_BREAK_MULTIPLIER * settings.heartbeatTimeout))))
+ {
+ if (index == VC_SERVER)
+ {
+ //When the server connection breaks, break all other connections and
+ //wait for the server. The server provides the time (hop) synchronization
+ //between all of the nodes. When the server fails, the clocks drift
+ //and the radios loose communications because they are hopping at different
+ //times.
+ serverLinkBroken = true;
+ changeState(RADIO_VC_WAIT_SERVER);
+ }
+
+ //Break the link
+ vcBreakLink(index);
+ }
+ }
+ break;
+ }
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Compute the number of header and trailer bytes
+void selectHeaderAndTrailerBytes()
+{
+ //Determine the components of the frame header
+ headerBytes = 0;
+
+ //Add the netID to the header
+ if ((settings.operatingMode == MODE_POINT_TO_POINT) || settings.verifyRxNetID)
+ headerBytes += 1;
+
+ //Add the control byte to the header
+ headerBytes += 1;
+
+ //Add channel timer bytes to header
+ if (settings.frequencyHop == true)
+ headerBytes += CHANNEL_TIMER_BYTES;
+
+ //Add the byte containing the frame size (only needed in SF6)
+ if (settings.radioSpreadFactor == 6)
+ headerBytes += 1;
+
+ //Set the beginning of the data portion of the transmit buffer
+ endOfTxData = &outgoingPacket[headerBytes];
+
+ //Determine the size of the trailer
+ trailerBytes = (settings.enableCRC16 ? 2 : 0);
+
+ //Determine the minimum and maximum datagram sizes
+ minDatagramSize = headerBytes + trailerBytes;
+ maxDatagramSize = sizeof(outgoingPacket) - minDatagramSize;
+}
+
+//Return true if the radio is in a linked state
+//This is used for determining if we can do remote AT commands or not
+bool isLinked()
+{
+ if ((radioState >= RADIO_P2P_LINK_UP)
+ && (radioState <= RADIO_P2P_LINK_UP_WAIT_TX_DONE))
+ return (true);
+
+ return (false);
+}
+
+//Determine if multi-point sync is achieved
+bool isMultiPointSync()
+{
+ return ((radioState >= RADIO_MP_STANDBY) && (radioState <= RADIO_MP_WAIT_TX_DONE));
+}
+
+//Verify the radio state definitions against the radioStateTable
+const char * verifyRadioStateTable()
+{
+ int expectedState;
+ unsigned int i;
+ unsigned int index;
+ unsigned int maxDescriptionLength;
+ unsigned int maxNameLength;
+ bool missing;
+ int * order;
+ unsigned int tableEntries;
+ int temp;
+
+ //Verify that all the entries are in the state table
+ tableEntries = sizeof(radioStateTable) / sizeof(radioStateTable[0]);
+ for (index = 0; index < tableEntries; index++)
+ {
+ //Validate the current table entry
+ if (index == radioStateTable[index].state)
+ continue;
+
+ //Wait for the USB serial port
+ if (!settings.usbSerialWait)
+ while (!Serial);
+
+ //An invalid entry was found
+ //Try to build a valid table
+ order = (int *)malloc(tableEntries * sizeof(*order));
+ if (!order)
+ waitForever("ERROR - Failed to allocate the order table from the heap!");
+
+ //Assume the table is in the correct order
+ maxDescriptionLength = 0;
+ maxNameLength = 0;
+ for (index = 0; index < tableEntries; index++)
+ {
+ order[index] = index;
+ if (radioStateTable[index].state < RADIO_MAX_STATE)
+ {
+ if (maxNameLength < strlen(radioStateTable[index].name))
+ maxNameLength = strlen(radioStateTable[index].name);
+ if (radioStateTable[index].description
+ && (maxDescriptionLength < strlen(radioStateTable[index].description)))
+ maxDescriptionLength = strlen(radioStateTable[index].description);
+ }
+ }
+
+ //Bubble sort the entries
+ for (index = 0; index < tableEntries; index++)
+ {
+ for (i = index + 1; i < tableEntries; i++)
+ {
+ if (radioStateTable[order[i]].state < radioStateTable[order[index]].state)
+ {
+ //Swap the two values
+ temp = order[i];
+ order[i] = order[index];
+ order[index] = temp;
+ }
+ }
+ }
+
+ //Determine if there are missing states
+ missing = false;
+ for (index = 0; index < tableEntries; index++)
+ {
+ if (radioStateTable[order[i]].state != index)
+ {
+ missing = true;
+ break;
+ }
+ }
+
+ //Display the request
+ systemPrintln("Please replace radioStateTable in States.ino with the following table:");
+ if (missing)
+ systemPrintln("Please update the table with the missing states");
+ systemPrintln();
+
+ //Display the new table
+ systemPrintln("const RADIO_STATE_ENTRY radioStateTable[] =");
+ systemPrintln("{");
+ systemPrintln(" // State Name Description");
+ expectedState = 0;
+ for (index = 0; index < tableEntries; index++)
+ {
+ //Remove bad states from the table
+ if (radioStateTable[order[index]].state >= RADIO_MAX_STATE)
+ break;
+ if (radioStateTable[order[index]].state > expectedState)
+ {
+ //Print the missing entries
+ systemPrint("Missing state");
+ if ((expectedState + 1) < radioStateTable[order[index]].state)
+ {
+ systemPrint("s ");
+ systemPrint(expectedState);
+ systemPrint(" - ");
+ systemPrintln(radioStateTable[order[index]].state - 1);
+ }
+ else
+ {
+ systemPrint(" ");
+ systemPrintln(expectedState);
+ }
+ while (radioStateTable[order[index]].state > expectedState)
+ {
+ systemPrint(" {");
+ systemPrint(", ");
+ for (i = 0; i < (6 + maxNameLength); i++)
+ systemPrint(" ");
+ systemPrint("\"\", ");
+ for (i = 0; i < maxNameLength; i++)
+ systemPrint(" ");
+ systemPrint("\"\"},");
+ for (i = 0; i < maxDescriptionLength; i++)
+ systemPrint(" ");
+ systemPrint("//");
+ if (expectedState < 10)
+ systemPrint(" ");
+ systemPrintln(expectedState++);
+ }
+ }
+
+ //Print the state
+ systemPrint(" {RADIO_");
+ systemPrint(radioStateTable[order[index]].name);
+ systemPrint(", ");
+
+ //Align the name column
+ for (i = strlen(radioStateTable[order[index]].name); i < maxNameLength; i++)
+ systemPrint(" ");
+
+ //Print the name
+ systemPrint("\"");
+ systemPrint(radioStateTable[order[index]].name);
+ systemPrint("\", ");
+
+ //Align the description column
+ for (i = strlen(radioStateTable[order[index]].name); i < maxNameLength; i++)
+ systemPrint(" ");
+
+ //Print the description
+ if (radioStateTable[order[index]].description)
+ {
+ systemPrint("\"");
+ systemPrint(radioStateTable[order[index]].description);
+ systemPrint("\"},");
+ }
+ else
+ systemPrint("NULL},");
+
+ //Align the comments
+ for (i = radioStateTable[order[index]].description ? strlen(radioStateTable[order[index]].description) : 2;
+ i < maxDescriptionLength; i++)
+ systemPrint(" ");
+
+ //Add the state value comment
+ systemPrint("//");
+ if (expectedState < 10)
+ systemPrint(" ");
+ systemPrintln(expectedState++);
+ }
+ systemPrintln("};");
+ return "ERROR - Please update the radioStateTable";
+ }
+ return NULL;
+}
+
+//Verify the PacketType enums against the radioDatagramType
+const char * verifyRadioDatagramType()
+{
+ bool valid;
+
+ valid = ((sizeof(radioDatagramType) / sizeof(radioDatagramType[0])) == MAX_DATAGRAM_TYPE);
+ if (!valid)
+ return "ERROR - Please update the radioDatagramTable";
+ return NULL;
+}
+
+//Change states and print the new state
+void changeState(RadioStates newState)
+{
+ radioState = newState;
+ radioStateHistory[radioState] = millis();
+
+ if ((settings.debug == false) && (settings.debugStates == false))
+ return;
+
+ displayState(newState);
+ outputSerialData(true);
+}
+
+//Display the state transition
+void displayState(RadioStates newState)
+{
+ //Debug print
+ if (settings.printTimestamp)
+ systemPrintTimestamp();
+ systemPrint("State: ");
+ if (newState >= RADIO_MAX_STATE)
+ {
+ systemPrint(radioState);
+ systemPrintln(" is Unknown");
+ }
+ else
+ {
+ if (radioStateTable[radioState].description)
+ systemPrint(radioStateTable[radioState].description);
+ else
+ systemPrint(radioStateTable[radioState].name);
+ }
+
+ if (newState == RADIO_P2P_LINK_UP || newState == RADIO_MP_STANDBY)
+ {
+ unsigned int seconds = (millis() - lastLinkUpTime) / 1000;
+ unsigned int minutes = seconds / 60;
+ seconds -= (minutes * 60);
+ unsigned int hours = minutes / 60;
+ minutes -= (hours * 60);
+ unsigned int days = hours / 24;
+ hours -= (days * 24);
+
+ systemPrint(" LinkUptime: ");
+
+ if (days < 10) systemPrint(" ");
+ if (days)
+ systemPrint(days);
+ else
+ systemPrint(" ");
+ systemPrint(" ");
+
+ if (hours < 10) systemPrint(" ");
+ systemPrint(hours);
+ systemPrint(":");
+ if (minutes < 10) systemPrint("0");
+ systemPrint(minutes);
+ systemPrint(":");
+ if (seconds < 10) systemPrint("0");
+ systemPrint(seconds);
+ }
+
+ systemPrintln();
+}
+
+//Display the radio state history
+void displayRadioStateHistory()
+{
+ uint8_t index;
+ uint8_t sortOrder[RADIO_MAX_STATE];
+ uint8_t temp;
+
+ //Set the default sort order
+ petWDT();
+ for (index = 0; index < RADIO_MAX_STATE; index++)
+ sortOrder[index] = index;
+
+ //Perform a bubble sort
+ for (index = 0; index < RADIO_MAX_STATE; index++)
+ for (int x = index + 1; x < RADIO_MAX_STATE; x++)
+ if (radioStateHistory[sortOrder[index]] > radioStateHistory[sortOrder[x]])
+ {
+ temp = sortOrder[index];
+ sortOrder[index] = sortOrder[x];
+ sortOrder[x] = temp;
+ }
+
+ //Display the radio state history
+ for (index = 0; index < RADIO_MAX_STATE; index++)
+ if (radioStateHistory[sortOrder[index]])
+ {
+ systemPrint(" ");
+ systemPrintTimestamp(radioStateHistory[sortOrder[index]] + timestampOffset);
+ systemPrint(": ");
+ systemPrint(radioStateTable[sortOrder[index]].name);
+ systemPrintln();
+ }
+ petWDT();
+}
+
+//Dump the clock synchronization data
+void dumpClockSynchronization()
+{
+ if (settings.debugSync)
+ {
+ //Dump the clock sync data
+ petWDT();
+ for (uint8_t x = 0; x < (sizeof(clockSyncData) / sizeof(clockSyncData[0])); x++)
+ {
+ uint8_t index = (x + clockSyncIndex) % (sizeof(clockSyncData) / sizeof(clockSyncData[0]));
+ if (clockSyncData[index].frameAirTimeMsec)
+ {
+ systemPrint("Lcl: ");
+ systemPrint(clockSyncData[index].lclHopTimeMsec);
+ systemPrint(", Rmt: ");
+ systemPrint(clockSyncData[index].msToNextHopRemote);
+ systemPrint(" - ");
+ systemPrint(clockSyncData[index].frameAirTimeMsec);
+ systemPrint(" = ");
+ systemPrint(clockSyncData[index].msToNextHopRemote - clockSyncData[index].frameAirTimeMsec);
+ systemPrint(" + ");
+ systemPrint(clockSyncData[index].adjustment);
+ systemPrint(" = ");
+ systemPrint(clockSyncData[index].msToNextHop);
+ systemPrint(" msToNextHop");
+ if (clockSyncData[index].delayedHopCount)
+ {
+ systemPrint(", timeToHop: ");
+ systemPrint(clockSyncData[index].timeToHop);
+ systemPrint(", Hops: ");
+ systemPrint(clockSyncData[index].delayedHopCount);
+ }
+ systemPrintln();
+ outputSerialData(true);
+ petWDT();
+ }
+ }
+ }
+}
+
+//Break a point-to-point link
+void breakLink()
+{
+ unsigned long linkDownTime;
+
+ //Break the link
+ if (settings.printTimestamp)
+ {
+ linkDownTime = millis();
+
+ //Offset the value for display
+ if (!settings.displayRealMillis)
+ linkDownTime += timestampOffset;
+ }
+ linkFailures++;
+
+ //Stop the ACK timer
+ STOP_ACK_TIMER();
+
+ //Dump the clock synchronization
+ dumpClockSynchronization();
+
+ if (settings.printLinkUpDown)
+ {
+ if (settings.printTimestamp)
+ {
+ systemPrintTimestamp(linkDownTime);
+ systemPrint(": ");
+ }
+ systemPrintln("--------- Link DOWN ---------");
+ outputSerialData(true);
+ }
+
+ //Flush the buffers
+ resetSerial();
+
+ //Reset the radio and the link
+ triggerEvent(TRIGGER_RADIO_RESET);
+ changeState(RADIO_RESET);
+}
+
+//Point-to-point link is now up, following a 3-way handshake
+void enterLinkUp()
+{
+ VIRTUAL_CIRCUIT * vc;
+
+ //Bring up the link
+ triggerEvent(TRIGGER_HANDSHAKE_COMPLETE);
+
+ //For very low airspeeds (150 and below) the hop timer will expire during the handshake.
+ //Reset channel number to insure both radios are on same channel.
+ channelNumber = 0;
+ hopChannel(); //Leave home
+
+ //Synchronize the ACK numbers
+ vc = &virtualCircuitList[0];
+ vc->rmtTxAckNumber = 0;
+ vc->rxAckNumber = 0;
+ vc->txAckNumber = 0;
+
+ //Discard any previous data
+ discardPreviousData();
+
+ //Stop the ACK timer
+ STOP_ACK_TIMER();
+
+ //Mark start time for uptime calculation
+ lastLinkUpTime = millis();
+
+ //Start the receiver
+ changeState(RADIO_P2P_LINK_UP);
+ if (settings.printLinkUpDown)
+ {
+ systemPrintTimestamp();
+ systemPrintln("========== Link UP ==========");
+ outputSerialData(true);
+ }
+}
+
+//Empty the remote command receive buffer
+void discardPreviousData()
+{
+ //Output any debug messages
+ outputSerialData(true);
+
+ //Discard any previous data
+ radioTxTail = radioTxHead;
+ txTail = txHead;
+ commandRXTail = commandRXHead;
+ commandTXTail = commandTXHead;
+}
+
+//Output VC link status
+void vcChangeState(int8_t vcIndex, uint8_t state)
+{
+ VIRTUAL_CIRCUIT * vc;
+ uint32_t vcBit;
+
+ vc = &virtualCircuitList[vcIndex];
+ if (state != vc->vcState)
+ {
+ //Display the state change
+ if (settings.printLinkUpDown)
+ {
+ if ((state == VC_STATE_WAIT_ZERO_ACKS) && (vc->vcState == VC_STATE_CONNECTED))
+ {
+ systemPrint("-=-=- VC ");
+ systemPrint(vcIndex);
+ systemPrintln(" DISCONNECTED -=-=-");
+ }
+ if (state == VC_STATE_CONNECTED)
+ {
+ systemPrint("======= VC ");
+ systemPrint(vcIndex);
+ systemPrintln(" CONNECTED ======");
+ }
+ if (state == VC_STATE_LINK_DOWN)
+ {
+ systemPrint("--------- VC ");
+ systemPrint(vcIndex);
+ systemPrintln(" Down ---------");
+ }
+ else if (state == VC_STATE_LINK_ALIVE)
+ {
+ systemPrint("-=--=--=- VC ");
+ systemPrint(vcIndex);
+ systemPrintln(" ALIVE =--=--=-");
+ }
+ outputSerialData(true);
+ }
+
+ //Set the new state
+ vc->vcState = state;
+
+ //Determine if the VC is connecting
+ vcBit = 1 << vcIndex;
+ if (((state > VC_STATE_LINK_ALIVE) && (state < VC_STATE_CONNECTED))
+ || (vc->flags.wasConnected && (vc->vcState == VC_STATE_LINK_ALIVE)))
+ vcConnecting |= vcBit;
+ else
+ vcConnecting &= ~vcBit;
+
+ //Clear the connection request when connected
+ if (state == VC_STATE_CONNECTED)
+ vc->flags.wasConnected = false;
+ }
+ vcSendPcStateMessage(vcIndex, state);
+}
+
+//Send the PC the state message
+void vcSendPcStateMessage(int8_t vcIndex, uint8_t state)
+{
+ //Build the VC state message
+ VC_STATE_MESSAGE message;
+ message.vcState = state;
+
+ //Build the message header
+ VC_SERIAL_MESSAGE_HEADER header;
+ header.start = START_OF_VC_SERIAL;
+ header.radio.length = VC_RADIO_HEADER_BYTES + sizeof(message);
+ header.radio.destVc = PC_LINK_STATUS;
+ header.radio.srcVc = vcIndex;
+
+ //Send the VC state message
+ systemWrite((uint8_t *)&header, sizeof(header));
+ systemWrite((uint8_t *)&message, sizeof(message));
+}
+
+//Break the virtual-circuit link
+void vcBreakLink(int8_t vcIndex)
+{
+ VIRTUAL_CIRCUIT * vc;
+
+ //Only handle real VCs
+ if ((vcIndex >= PC_COMMAND) && (vcIndex <= VC_BROADCAST))
+ return;
+ vcIndex &= VCAB_NUMBER_MASK;
+
+ //If waiting for an ACK and the link breaks, stop the retransmissions
+ //by stopping the ACK timer.
+ if (ackTimer && (txDestVc == vcIndex))
+ {
+ STOP_ACK_TIMER();
+ vcSendPcAckNack(vcIndex, false);
+ }
+
+ //Get the virtual circuit data structure
+ if ((vcIndex >= 0) && (vcIndex != myVc) && (vcIndex < MAX_VC))
+ {
+ //Account for the link failure
+ vc = &virtualCircuitList[vcIndex];
+ vc->linkFailures++;
+ vcChangeState(vcIndex, VC_STATE_LINK_DOWN);
+ }
+ linkFailures++;
+
+ //Flush the buffers
+ outputSerialData(true);
+ if (vcIndex == myVc)
+ resetSerial();
+}
+
+//Place VC in LINK-UP state since it is receiving HEARTBEATs from the remote radio
+int8_t vcLinkAlive(int8_t vcIndex)
+{
+ VIRTUAL_CIRCUIT * vc = &virtualCircuitList[vcIndex];
+
+ //Send the status message
+ if (vc->vcState == VC_STATE_LINK_DOWN)
+ {
+ vc->firstHeartbeatMillis = millis();
+
+ //Update the link status
+ vcChangeState(vcIndex, VC_STATE_LINK_ALIVE);
+ }
+ return vcIndex;
+}
+
+void vcZeroAcks(int8_t vcIndex)
+{
+ VIRTUAL_CIRCUIT * vc = &virtualCircuitList[vcIndex];
+
+ //Reset the ACK counters
+ vc->txAckNumber = 0;
+ vc->rmtTxAckNumber = 0;
+ vc->rxAckNumber = 0;
+}
+
+//Translate the UNIQUE ID value into a VC number to reduce the communications overhead
+int8_t vcIdToAddressByte(int8_t srcAddr, uint8_t * id)
+{
+ VIRTUAL_CIRCUIT * vc;
+ int8_t vcIndex;
+
+ //Determine if the address is already in the list
+ for (vcIndex = 0; vcIndex < MAX_VC; vcIndex++)
+ {
+ //Verify that an address is present
+ vc = &virtualCircuitList[vcIndex];
+ if (!vc->flags.valid)
+ continue;
+
+ //Compare the unique ID values
+ if (memcmp(vc->uniqueId, id, UNIQUE_ID_BYTES) == 0)
+ //Update the link status
+ return vcLinkAlive(vcIndex);
+ }
+
+ //The unique ID is not in the list
+ //Fill in clients that were already running
+ vcIndex = srcAddr;
+ vc = &virtualCircuitList[vcIndex];
+
+ //Only the server can assign the address bytes
+ if ((srcAddr == VC_UNASSIGNED) && (!settings.server))
+ return -1;
+
+ //Assign an address if necessary
+ if (srcAddr == VC_UNASSIGNED)
+ {
+ //Unknown client ID
+ //Determine if there is a free address
+ for (vcIndex = 0; vcIndex < MAX_VC; vcIndex++)
+ {
+ vc = &virtualCircuitList[vcIndex];
+ if (!virtualCircuitList[vcIndex].flags.valid)
+ break;
+ }
+ if (vcIndex >= MAX_VC)
+ {
+ systemPrintln("ERROR: Too many clients, no free addresses!\n");
+ outputSerialData(true);
+ return -2;
+ }
+ srcAddr = vcIndex;
+ }
+
+ //Check for an address conflict
+ if (vc->flags.valid)
+ {
+ systemPrint("ERROR: Unknown ID with pre-assigned conflicting address: ");
+ systemPrintln(srcAddr);
+ systemPrint("Received ID: ");
+ for (int i = 0; i < UNIQUE_ID_BYTES; i++)
+ systemPrint(id[i], HEX);
+ systemPrintln();
+ systemPrint("Assigned ID: ");
+ for (int i = 0; i < UNIQUE_ID_BYTES; i++)
+ systemPrint(vc->uniqueId[i], HEX);
+ systemPrintln();
+ outputSerialData(true);
+ return -3;
+ }
+
+ //Save the unique ID to VC assignment in NVM
+ nvmSaveUniqueId(vcIndex, id);
+
+ //Mark this link as up
+ vc->flags.valid = true;
+ return vcLinkAlive(vcIndex);
+}
+
+//Process a received HEARTBEAT frame from a VC
+void vcReceiveHeartbeat(uint32_t rxMillis)
+{
+ uint32_t deltaMillis;
+ int vcSrc;
+
+ //Adjust freq hop ISR based on server's remaining clock
+ if ((rxSrcVc == VC_SERVER) || (memcmp(rxVcData, myUniqueId, sizeof(myUniqueId)) == 0))
+ syncChannelTimer(txHeartbeatUsec);
+
+ //Update the timestamp offset
+ if (rxSrcVc == VC_SERVER)
+ {
+ //Blink the heartbeat LED
+ blinkHeartbeatLed(true);
+
+ //Assume client and server are running the same level of debugging,
+ //then the delay from reading the millisecond value on the server should
+ //get offset by the transmit setup time and the receive overhead time.
+ memcpy(×tampOffset, &rxVcData[UNIQUE_ID_BYTES], sizeof(timestampOffset));
+ timestampOffset -= millis();
+ timestampOffset += (txHeartbeatUsec + settings.txToRxUsec + micros() - transactionCompleteMicros) / 1000;
+ }
+ triggerEvent(TRIGGER_RX_VC_HEARTBEAT);
+
+ //Save our address
+ if ((myVc == VC_UNASSIGNED) && (memcmp(myUniqueId, rxVcData, UNIQUE_ID_BYTES) == 0))
+ myVc = rxSrcVc;
+
+ //Translate the unique ID into an address byte
+ vcSrc = vcIdToAddressByte(rxSrcVc, rxVcData);
+ if (vcSrc < 0)
+ return;
+
+ //When the client does not know its address, it is assigned by the server
+ if (settings.server && (rxSrcVc == VC_UNASSIGNED))
+ {
+ //Assign the address to the client
+ if (xmitVcHeartbeat(vcSrc, rxVcData))
+ changeState(RADIO_VC_WAIT_TX_DONE);
+ }
+}
diff --git a/Firmware/LoRaSerial/System.ino b/Firmware/LoRaSerial/System.ino
new file mode 100644
index 00000000..374f1b4d
--- /dev/null
+++ b/Firmware/LoRaSerial/System.ino
@@ -0,0 +1,1292 @@
+//Copy the string into the serialTransmitBuffer or command response buffer (commandTXBuffer)
+void systemPrint(const char* string)
+{
+ uint16_t length;
+
+ length = strlen(string);
+ for (uint16_t x = 0 ; x < length ; x++)
+ serialOutputByte(string[x]);
+}
+
+//Print a string with a carriage return and linefeed
+void systemPrintln(const char* value)
+{
+ systemPrint(value);
+ systemPrint("\r\n");
+}
+
+//Print an integer value
+void systemPrint(int value)
+{
+ char temp[20];
+ sprintf(temp, "%d", value);
+ systemPrint(temp);
+}
+
+//Print an integer value as HEX or decimal
+void systemPrint(int value, uint8_t printType)
+{
+ char temp[20];
+
+ if (printType == HEX)
+ sprintf(temp, "%08x", value);
+ else if (printType == DEC)
+ sprintf(temp, "%d", value);
+
+ systemPrint(temp);
+}
+
+//Print a uint32_t value as HEX or decimal
+void systemPrint(uint32_t value, uint8_t printType)
+{
+ char temp[20];
+
+ if (printType == HEX)
+ sprintf(temp, "%08x", value);
+ else if (printType == DEC)
+ sprintf(temp, "%lu", value);
+
+ systemPrint(temp);
+}
+
+//Print a uint32_t value as HEX or decimal
+void systemPrintln(uint32_t value, uint8_t printType)
+{
+ systemPrint(value, printType);
+ systemPrintln();
+}
+
+//Print an integer value with a carriage return and line feed
+void systemPrintln(int value)
+{
+ systemPrint(value);
+ systemPrint("\r\n");
+}
+
+//Print an 8-bit value as HEX or decimal
+void systemPrint(uint8_t value, uint8_t printType)
+{
+ char temp[20];
+
+ if (printType == HEX)
+ sprintf(temp, "%02X", value);
+ else if (printType == DEC)
+ sprintf(temp, "%d", value);
+
+ systemPrint(temp);
+}
+
+//Print an 8-bit value as HEX or decimal with a carriage return and linefeed
+void systemPrintln(uint8_t value, uint8_t printType)
+{
+ systemPrint(value, printType);
+ systemPrint("\r\n");
+}
+
+//Print a 16-bit value as HEX or decimal
+void systemPrint(uint16_t value, uint8_t printType)
+{
+ char temp[20];
+
+ if (printType == HEX)
+ sprintf(temp, "%04X", value);
+ else if (printType == DEC)
+ sprintf(temp, "%d", value);
+
+ systemPrint(temp);
+}
+
+//Print a 16-bit value as HEX or decimal with a carriage return and linefeed
+void systemPrintln(uint16_t value, uint8_t printType)
+{
+ systemPrint(value, printType);
+ systemPrint("\r\n");
+}
+
+//Print a floating point value with a specified number of decimal places
+void systemPrint(float value, uint8_t decimals)
+{
+ char temp[20];
+ sprintf(temp, "%.*f", decimals, value);
+ systemPrint(temp);
+}
+
+//Print a floating point value with a specified number of decimal places and a
+//carriage return and linefeed
+void systemPrintln(float value, uint8_t decimals)
+{
+ systemPrint(value, decimals);
+ systemPrint("\r\n");
+}
+
+//Print a double precision floating point value with a specified number of decimal
+//places
+void systemPrint(double value, uint8_t decimals)
+{
+ char temp[300];
+ sprintf(temp, "%.*g", decimals, value);
+ systemPrint(temp);
+}
+
+//Print a double precision floating point value with a specified number of decimal
+//places and a carriage return and linefeed
+void systemPrintln(double value, uint8_t decimals)
+{
+ systemPrint(value, decimals);
+ systemPrint("\r\n");
+}
+
+//Print a carriage return and linefeed
+void systemPrintln()
+{
+ systemPrint("\r\n");
+}
+
+//Print a timestamp value: days hours:minutes:seconds.milliseconds
+void systemPrintTimestamp(unsigned int milliseconds)
+{
+ unsigned int seconds;
+ unsigned int minutes;
+ unsigned int hours;
+ unsigned int days;
+ unsigned int total;
+
+ petWDT();
+
+ //Compute the values for display
+ seconds = milliseconds / 1000;
+ minutes = seconds / 60;
+ hours = minutes / 60;
+ days = hours / 24;
+
+ total = days * 24;
+ hours -= total;
+
+ total = (total + hours) * 60;
+ minutes -= total;
+
+ total = (total + minutes) * 60;
+ seconds -= total;
+
+ total = (total + seconds) * 1000;
+ milliseconds -= total;
+
+ //Print the days
+ if (days < 10) systemPrint(" ");
+ if (days)
+ systemPrint(days);
+ else
+ systemPrint(" ");
+ systemPrint(" ");
+
+ //Print the time
+ if (hours < 10) systemPrint(" ");
+ systemPrint(hours);
+ systemPrint(":");
+ if (minutes < 10) systemPrint("0");
+ systemPrint(minutes);
+ systemPrint(":");
+ if (seconds < 10) systemPrint("0");
+ systemPrint(seconds);
+ systemPrint(".");
+ if (milliseconds < 100) systemPrint("0");
+ if (milliseconds < 10) systemPrint("0");
+ systemPrint(milliseconds);
+ petWDT();
+}
+
+//Print a timestamp value with an offset
+void systemPrintTimestamp()
+{
+ unsigned int milliseconds;
+
+ if (settings.printTimestamp)
+ {
+ //Get the clock value
+ milliseconds = millis();
+
+ //Offset the value for display
+ if (!settings.displayRealMillis)
+ milliseconds += timestampOffset;
+
+ //Print the time
+ systemPrintTimestamp(milliseconds);
+ systemPrint(": ");
+ }
+}
+
+//Print the unique ID value
+void systemPrintUniqueID(uint8_t * uniqueID)
+{
+ int index;
+
+ //Display in the same byte order as dump output
+ for (index = 0; index < UNIQUE_ID_BYTES; index++)
+ systemPrint(uniqueID[index], HEX);
+}
+
+//Output a byte to the serial port
+void systemWrite(uint8_t value)
+{
+ serialOutputByte(value);
+}
+
+//Output a buffer of the specified length to the serial port
+void systemWrite(uint8_t * buffer, uint16_t length)
+{
+ uint8_t * end;
+
+ //Output the entire buffer ignoring contents
+ end = &buffer[length];
+ while (buffer < end)
+ serialOutputByte(*buffer++);
+}
+
+//Ensure all serial output has been transmitted, FIFOs are empty
+void systemFlush()
+{
+ arch.serialFlush();
+}
+
+//Read a byte from the serial port
+uint8_t systemRead()
+{
+ return (arch.serialRead());
+}
+
+//Check the train button and change state accordingly
+void updateButton()
+{
+ bool buttonPressed;
+ static bool buttonWasPressed;
+ uint32_t deltaTime;
+ static Settings originalSettings;
+ static uint32_t pressedTime;
+
+ if (trainBtn != NULL)
+ {
+ //Determine the previous state of the button
+ buttonPressed = trainBtn->read();
+
+ //Determine the current button state
+ if (buttonWasPressed)
+ {
+ //Update the LEDs
+ deltaTime = millis() - pressedTime;
+ buttonLeds(deltaTime);
+ if (!buttonPressed)
+ {
+ //Button just released
+ settings = originalSettings;
+
+ //Check for reset to factory settings
+ if (deltaTime >= trainButtonFactoryResetTime)
+ {
+ //Erase the EEPROM
+ nvmErase();
+
+ //Reboot the radio
+ commandReset();
+ }
+
+ //Starting training or exiting training via the button is only possible
+ //when the radio is not in command mode!
+ else if (!inCommandMode)
+ {
+ //Check for server training request
+ if (deltaTime >= trainButtonServerTime)
+ {
+ //Set the training settings
+ trainingSettings = settings;
+ inTraining = true;
+ if (settings.operatingMode == MODE_POINT_TO_POINT)
+ {
+ //Select a random netID and encryption key
+ generateRandomKeysID(&trainingSettings);
+ }
+ beginTrainingServer();
+ }
+
+ //Check for client training request
+ else if (deltaTime >= trainButtonClientTime)
+ {
+ trainingSettings = settings; //Set the training settings
+ inTraining = true;
+ beginTrainingClient();
+ }
+
+ //Exit training
+ else
+ {
+ //The user has stopped training with the button
+ //Restore the previous settings
+ settings = originalSettings;
+ if (inTraining)
+ {
+ inTraining = false;
+ changeState(RADIO_RESET);
+ }
+ }
+ }
+ }
+ }
+
+ //The button was not previously pressed
+ else
+ {
+ //Determine if the button is pressed
+ if (buttonPressed)
+ {
+ //Button just pressed
+ pressedTime = millis();
+
+ //Save the previous led state
+ if (!inTraining)
+ originalSettings = settings;
+ }
+ }
+
+ //Save the current button state
+ buttonWasPressed = buttonPressed;
+ }
+}
+
+//Platform specific reset commands
+void systemReset()
+{
+ arch.systemReset();
+}
+
+//Display any debug serial data and then loop forever
+void waitForever(const char * errorMessage)
+{
+ //Wait forever
+ while (1)
+ {
+ petWDT();
+ blinkErrorLed(errorMessage);
+ }
+}
+
+//Encrypt a given array in place
+void encryptBuffer(uint8_t *bufferToEncrypt, uint8_t arraySize)
+{
+ gcm.setKey(settings.encryptionKey, sizeof(settings.encryptionKey));
+ gcm.setIV(AESiv, sizeof(AESiv));
+
+ gcm.encrypt(bufferToEncrypt, bufferToEncrypt, arraySize);
+}
+
+//Decrypt a given array in place
+void decryptBuffer(uint8_t *bufferToDecrypt, uint8_t arraySize)
+{
+ gcm.setKey(settings.encryptionKey, sizeof(settings.encryptionKey));
+ gcm.setIV(AESiv, sizeof(AESiv));
+
+ gcm.decrypt(bufferToDecrypt, bufferToDecrypt, arraySize);
+}
+
+
+//IBM Whitening process from Semtech "Software Whitening and CRC on SX12xx Devices" app note
+//Removes DC Bias from data with long strings of 1s or 0s
+void radioComputeWhitening(uint8_t *buffer, uint16_t bufferSize)
+{
+ uint8_t WhiteningKeyMSB = 0x01;
+ uint8_t WhiteningKeyLSB = 0xFF;
+ uint8_t WhiteningKeyMSBPrevious = 0;
+
+ for (uint16_t j = 0 ; j < bufferSize ; j++)
+ {
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ buffer[j] ^= WhiteningKeyLSB;
+
+ for (uint8_t i = 0 ; i < 8 ; i++)
+ {
+ WhiteningKeyMSBPrevious = WhiteningKeyMSB;
+ WhiteningKeyMSB = (WhiteningKeyLSB & 0x01) ^ ((WhiteningKeyLSB >> 5) & 0x01);
+ WhiteningKeyLSB = ((WhiteningKeyLSB >> 1 ) & 0xFF) | ((WhiteningKeyMSBPrevious << 7) & 0x80);
+ }
+ }
+}
+
+//Toggle a pin. Used for logic analyzer debugging.
+void triggerEvent(uint8_t triggerNumber)
+{
+ uint8_t triggerBitNumber;
+ uint32_t triggerEnable;
+ uint16_t triggerWidth;
+
+ //Determine if the trigger pin is enabled
+ if (pin_trigger == PIN_UNDEFINED)
+ return;
+
+ //Determine which trigger enable to use
+ triggerBitNumber = triggerNumber;
+ triggerEnable = settings.triggerEnable;
+ if (triggerNumber >= 32)
+ {
+ triggerBitNumber -= 32;
+ triggerEnable = settings.triggerEnable2;
+ }
+
+ //Determine if the trigger is enabled
+ if (triggerEnable & (1 << triggerBitNumber))
+ {
+ //Determine the trigger pulse width
+ triggerWidth = settings.triggerWidth;
+ if (settings.triggerWidthIsMultiplier)
+ triggerWidth *= (triggerNumber + 1);
+
+ //Output the trigger pulse
+ digitalWrite(pin_trigger, LOW);
+ delayMicroseconds(triggerWidth);
+ digitalWrite(pin_trigger, HIGH);
+ }
+}
+
+//Copy the contents of settings struct to outgoing array
+//Note: All variables in struct_settings must be fully cast (uint16_t, int32_t, etc, not int)
+//so that we will have alignment between radios using different platforms (ie ESP32 vs SAMD)
+void moveSettingsToPacket(Settings settings, uint8_t* packetBuffer)
+{
+ //Get a byte pointer that points to the beginning of the struct
+ uint8_t *bytePtr = (uint8_t*)&settings;
+
+ for (uint8_t x = 0 ; x < sizeof(settings) ; x++)
+ packetBuffer[x] = bytePtr[x];
+}
+
+//Used to move an incoming packet into the remoteSettings temp buffer
+void movePacketToSettings(Settings settings, uint8_t* packetBuffer)
+{
+ // Get a byte pointer that points to the beginning of the struct
+ uint8_t *bytePtr = (uint8_t*)&settings;
+
+ for (uint8_t x = 0 ; x < sizeof(settings) ; x++)
+ bytePtr[x] = packetBuffer[x];
+}
+
+//Convert ASCII character to base 16
+int8_t charToHex(char a)
+{
+ a = toupper(a);
+
+ if ('0' <= a && a <= '9') a -= '0';
+ else if ('A' <= a && a <= 'F') a = a - 'A' + 10;
+ else a = -1;
+ return a;
+}
+
+//Given two letters, convert to base 10
+uint8_t charHexToDec(char a, char b)
+{
+ a = charToHex(a);
+ b = charToHex(b);
+ return ((a << 4) | b);
+}
+
+//Dump a buffer with offset from buffer start, 16 bytes per row, displaying hex and ASCII
+void dumpBuffer(uint8_t * data, int length)
+{
+ char byte[2];
+ int bytes;
+ uint8_t * dataEnd;
+ uint8_t * dataStart;
+ const int displayWidth = 16;
+ int index;
+
+ byte[1] = 0;
+ dataStart = data;
+ dataEnd = &data[length];
+ while (data < dataEnd)
+ {
+ // Display the offset
+ systemPrint(" 0x");
+ systemPrint((uint8_t)(data - dataStart), HEX);
+ systemPrint(": ");
+
+ // Determine the number of bytes to display
+ bytes = dataEnd - data;
+ if (bytes > displayWidth)
+ bytes = displayWidth;
+
+ // Display the data bytes in hex
+ for (index = 0; index < bytes; index++)
+ {
+ systemPrint(" ");
+ systemPrint(*data++, HEX);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ }
+
+ // Space over to the ASCII display
+ for (; index < displayWidth; index++)
+ {
+ systemPrint(" ");
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ }
+ systemPrint(" ");
+
+ // Display the ASCII bytes
+ data -= bytes;
+ for (index = 0; index < bytes; index++) {
+ byte[0] = *data++;
+ systemPrint(((byte[0] < ' ') || (byte[0] >= 0x7f)) ? "." : byte);
+ }
+ systemPrintln();
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ }
+}
+
+//Dump a buffer assuming that it contains text
+void dumpBufferRaw(uint8_t * data, int length)
+{
+ systemPrint("0x ");
+ for (int x = 0 ; x < length ; x++)
+ {
+ systemPrint(data[x], HEX);
+ systemPrint(" ");
+ }
+ systemPrintln();
+}
+
+//Dump a circular buffer with offset from buffer start, 16 bytes per row, displaying hex and ASCII
+void dumpCircularBuffer(uint8_t * buffer, uint16_t tail, uint16_t bufferLength, int length)
+{
+ int bytes;
+ uint8_t data;
+ uint16_t delta;
+ const int displayWidth = 16;
+ uint16_t i;
+ int index;
+ uint16_t offset;
+
+ offset = tail;
+ while (length > 0)
+ {
+ //Display the offset
+ systemPrint(" 0x");
+ systemPrint((uint16_t)(offset % bufferLength), HEX);
+ systemPrint(": ");
+
+ //Adjust for the offset
+ delta = offset % displayWidth;
+ if (delta)
+ {
+ bytes -= delta;
+ for (index = 0; index < delta; index++)
+ {
+ systemPrint(" ");
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ }
+ }
+
+ //Determine the number of bytes to display
+ bytes = length;
+ if (bytes > (displayWidth - delta))
+ bytes = displayWidth - delta;
+
+ //Display the data bytes in hex
+ for (index = 0; index < bytes; index++)
+ {
+ systemWrite(' ');
+ data = buffer[(offset + index) % bufferLength];
+ systemPrint(data, HEX);
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ }
+
+ //Space over to the ASCII display
+ for (; (delta + index) < displayWidth; index++)
+ {
+ systemPrint(" ");
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ }
+ systemPrint(" ");
+
+ //Display the ASCII bytes
+ for (index = 0; index < delta; index++)
+ systemWrite(' ');
+ for (index = 0; index < bytes; index++) {
+ data = buffer[(offset + index) % bufferLength];
+ systemWrite(((data < ' ') || (data >= 0x7f)) ? '.' : data);
+ }
+ systemPrintln();
+ if (timeToHop == true) //If the channelTimer has expired, move to next frequency
+ hopChannel();
+ petWDT();
+ outputSerialData(true);
+ offset += bytes;
+ length -= bytes;
+ }
+}
+
+//Update the state of the 4 green LEDs
+void setRSSI(uint8_t ledBits)
+{
+ if (ledBits & 0b0001)
+ digitalWrite(pin_green_1_LED, HIGH);
+ else
+ digitalWrite(pin_green_1_LED, LOW);
+
+ if (ledBits & 0b0010)
+ digitalWrite(pin_green_2_LED, HIGH);
+ else
+ digitalWrite(pin_green_2_LED, LOW);
+
+ if (ledBits & 0b0100)
+ digitalWrite(pin_green_3_LED, HIGH);
+ else
+ digitalWrite(pin_green_3_LED, LOW);
+
+ if (ledBits & 0b1000)
+ digitalWrite(pin_green_4_LED, HIGH);
+ else
+ digitalWrite(pin_green_4_LED, LOW);
+}
+
+//Start the cylon LEDs
+void startCylonLEDs()
+{
+ cylonLedPattern = 0b0001;
+ cylonPatternGoingLeft = false;
+}
+
+//Update the RSSI LED or LEDs
+void blinkRadioRssiLed()
+{
+ unsigned long currentMillis;
+ static uint32_t ledPreviousRssiMillis;
+ static unsigned long lastCylonBlink; //Controls LED during training
+ static int8_t ledRssiPulseWidth; //Target pulse width for LED display
+
+ currentMillis = millis();
+ switch (settings.selectLedUse)
+ {
+ //Update the pattern on the 4 green LEDs
+ case LEDS_CYLON:
+ //Determine if it is time to update the cylon pattern
+ if ((currentMillis - lastCylonBlink) > 75)
+ {
+ lastCylonBlink = currentMillis;
+
+ //The following shows the cylon pattern in four LEDs
+ //
+ // LED3 LED2 LED1 LED0
+ // X
+ // X
+ // X
+ // X
+ // X
+ // X
+ // X
+ // X
+ // ...
+ //
+ //Cylon the RSSI LEDs
+ setRSSI(cylonLedPattern);
+
+ //Determine if a change in direction is necessary
+ if ((cylonLedPattern == 0b1000) || (cylonLedPattern == 0b0001))
+ cylonPatternGoingLeft = cylonPatternGoingLeft ? false : true;
+
+ if (cylonPatternGoingLeft)
+ cylonLedPattern <<= 1;
+ else
+ cylonLedPattern >>= 1;
+ }
+ break;
+
+ //Update the single RSSI LED
+ case LEDS_MULTIPOINT:
+ case LEDS_P2P:
+ case LEDS_RADIO_USE:
+ case LEDS_VC:
+ //Check for the start of a new pulse
+ if ((currentMillis - ledPreviousRssiMillis) >= LED_MAX_PULSE_WIDTH)
+ {
+ ledPreviousRssiMillis = currentMillis;
+
+ //Determine the RSSI LED pulse width
+ //The RSSI value ranges from -164 to 30 dB
+ ledRssiPulseWidth = (150 + rssi) / 10;
+ if (ledRssiPulseWidth > 0)
+ digitalWrite(GREEN_LED_3, LED_ON);
+ }
+
+ //Check for time to turn off the LED
+ else if ((currentMillis - ledPreviousRssiMillis) >= ledRssiPulseWidth)
+ digitalWrite(GREEN_LED_3, LED_OFF);
+ break;
+
+ //Update the 4 green LEDs based upon the RSSI value
+ case LEDS_RSSI:
+ if (rssi > -70)
+ setRSSI(0b1111);
+ else if (rssi > -100)
+ setRSSI(0b0111);
+ else if (rssi > -120)
+ setRSSI(0b0011);
+ else if (rssi > -150)
+ setRSSI(0b0001);
+ else
+ setRSSI(0);
+ break;
+ }
+}
+
+//Set the serial TX (blue) LED value
+void blinkSerialTxLed(bool illuminate)
+{
+ switch (settings.selectLedUse)
+ {
+ case LEDS_RSSI:
+ if (pin_blue_LED != PIN_UNDEFINED)
+ {
+ if (illuminate == true)
+ digitalWrite(pin_blue_LED, HIGH);
+ else
+ digitalWrite(pin_blue_LED, LOW);
+ }
+ break;
+ }
+}
+
+//Set the serial RX (yellow) LED value
+void blinkSerialRxLed(bool illuminate)
+{
+ switch (settings.selectLedUse)
+ {
+ case LEDS_RSSI:
+ if (illuminate == true)
+ digitalWrite(pin_yellow_LED, HIGH);
+ else
+ digitalWrite(pin_yellow_LED, LOW);
+ break;
+
+ case LEDS_VC:
+ if (illuminate == true)
+ digitalWrite(GREEN_LED_2, HIGH);
+ else
+ digitalWrite(GREEN_LED_2, LOW);
+ break;
+ }
+}
+
+//Blink the RX LED
+void blinkRadioRxLed(bool on)
+{
+ switch (settings.selectLedUse)
+ {
+ case LEDS_CYLON:
+ if (on)
+ digitalWrite(YELLOW_LED, LED_ON);
+ else if ((millis() - linkDownTimer) >= RADIO_USE_BLINK_MILLIS)
+ digitalWrite(YELLOW_LED, LED_OFF);
+ break;
+
+ case LEDS_MULTIPOINT:
+ case LEDS_P2P:
+ case LEDS_RADIO_USE:
+ case LEDS_VC:
+ if (on)
+ digitalWrite(GREEN_LED_1, LED_ON);
+ else if ((millis() - linkDownTimer) >= RADIO_USE_BLINK_MILLIS)
+ digitalWrite(GREEN_LED_1, LED_OFF);
+ break;
+ }
+}
+
+//BLink the TX LED
+void blinkRadioTxLed(bool on)
+{
+ switch (settings.selectLedUse)
+ {
+ case LEDS_CYLON:
+ if (on)
+ digitalWrite(BLUE_LED, LED_ON);
+ else if ((millis() - datagramTimer) >= RADIO_USE_BLINK_MILLIS)
+ digitalWrite(BLUE_LED, LED_OFF);
+ break;
+
+ case LEDS_MULTIPOINT:
+ case LEDS_P2P:
+ case LEDS_RADIO_USE:
+ case LEDS_VC:
+ if (on)
+ digitalWrite(GREEN_LED_4, LED_ON);
+ else if ((millis() - datagramTimer) >= RADIO_USE_BLINK_MILLIS)
+ digitalWrite(GREEN_LED_4, LED_OFF);
+ break;
+ }
+}
+
+//Radio LED display
+// Green1: Radio RX data received
+// Green2: Receiving HEARTBEATs (link up)
+// Green3: RSSI level
+// Green4: Radio TX data sent
+// Blue: Bad frame received
+// Yellow: Bad CRC received
+void radioLeds()
+{
+ uint32_t currentMillis;
+ static uint32_t previousBadFrames;
+ static uint32_t badFramesMillis;
+ static uint32_t previousBadCrc;
+ static uint32_t badCrcMillis;
+
+ //Turn off the RX LED to end the blink
+ blinkRadioRxLed(false);
+
+ //Turn off the TX LED to end the blink
+ blinkRadioTxLed(false);
+
+ //Update the link LED
+ digitalWrite(GREEN_LED_2, isLinked() ? LED_ON : LED_OFF);
+
+ //Update the RSSI LED
+ blinkRadioRssiLed();
+
+ //Blink the bad frames LED
+ currentMillis = millis();
+ if (badFrames != previousBadFrames)
+ {
+ previousBadFrames = badFrames;
+ badFramesMillis = currentMillis;
+ digitalWrite(BLUE_LED, LED_ON);
+ }
+ else if (badFramesMillis && ((currentMillis - badFramesMillis) >= RADIO_USE_BLINK_MILLIS))
+ {
+ badFramesMillis = 0;
+ digitalWrite(BLUE_LED, LED_OFF);
+ }
+
+ //Blink the bad CRC or duplicate frames LED
+ if (settings.enableCRC16 && (badCrc != previousBadCrc))
+ {
+ previousBadCrc = badCrc;
+ badCrcMillis = currentMillis;
+ digitalWrite(YELLOW_LED, LED_ON);
+ }
+ if ((!settings.enableCRC16) && (duplicateFrames != previousBadCrc))
+ {
+ previousBadCrc = duplicateFrames;
+ badCrcMillis = currentMillis;
+ digitalWrite(YELLOW_LED, LED_ON);
+ }
+ else if (badCrcMillis && ((currentMillis - badCrcMillis) >= RADIO_USE_BLINK_MILLIS))
+ {
+ badCrcMillis = 0;
+ digitalWrite(YELLOW_LED, LED_OFF);
+ }
+}
+
+//Blink the heartbeat LED
+void blinkHeartbeatLed(bool on)
+{
+ static unsigned long ledHeartbeatMillis;
+
+ switch (settings.selectLedUse)
+ {
+ case LEDS_MULTIPOINT:
+ case LEDS_P2P:
+ case LEDS_VC:
+ if (on)
+ {
+ digitalWrite(BLUE_LED, LED_ON);
+ ledHeartbeatMillis = millis();
+ }
+ else if ((millis() - ledHeartbeatMillis) > RADIO_USE_BLINK_MILLIS)
+ digitalWrite(BLUE_LED, LED_OFF);
+ break;
+ }
+}
+
+//Blink the channel hop LED
+void blinkChannelHopLed(bool on)
+{
+ switch (settings.selectLedUse)
+ {
+ case LEDS_MULTIPOINT:
+ case LEDS_P2P:
+ case LEDS_VC:
+ if (on)
+ digitalWrite(YELLOW_LED, LED_ON);
+ else if ((millis() - radioCallHistory[RADIO_CALL_hopChannel]) >= RADIO_USE_BLINK_MILLIS)
+ digitalWrite(YELLOW_LED, LED_OFF);
+ break;
+ }
+}
+
+//Blink the error LED
+void blinkErrorLed(const char * errorMessage)
+{
+ uint32_t currentMillis;
+ static uint32_t lastToggleMillis;
+ static uint8_t flashCount;
+
+#define ERROR_FLASHS_PER_SECOND 10
+#define DELAY_BETWEEN_MESSAGES_SECS 15
+
+ //Ouptut the error message on a regular interval
+ if (!flashCount)
+ {
+ flashCount = DELAY_BETWEEN_MESSAGES_SECS * (ERROR_FLASHS_PER_SECOND << 1);
+ if (errorMessage)
+ {
+ systemPrintln(errorMessage);
+ outputSerialData(true);
+ }
+ }
+
+ //Determine if it is time to toggle the error LED
+ currentMillis = millis();
+ if ((currentMillis - lastToggleMillis) >= (1000 / (ERROR_FLASHS_PER_SECOND << 1)))
+ {
+ //Toggle the error LED
+ lastToggleMillis = currentMillis;
+ digitalWrite(YELLOW_LED, !digitalRead(YELLOW_LED));
+ flashCount -= 1;
+ }
+}
+
+//Display the multi-point LED pattern
+void multiPointLeds()
+{
+ //Turn off the RX LED to end the blink
+ blinkRadioRxLed(false);
+
+ //Turn off the TX LED to end the blink
+ blinkRadioTxLed(false);
+
+ //Update the sync LED
+ digitalWrite(GREEN_LED_2, isMultiPointSync() ? LED_ON : LED_OFF);
+
+ //Update the RSSI LED
+ blinkRadioRssiLed();
+
+ //Update the hop LED
+ if ((millis() - radioCallHistory[RADIO_CALL_hopChannel]) >= RADIO_USE_BLINK_MILLIS)
+ digitalWrite(YELLOW_LED, LED_OFF);
+
+ //Update the HEARTBEAT LED
+ blinkHeartbeatLed(false);
+}
+
+void p2pLeds()
+{
+ //Turn off the RX LED to end the blink
+ blinkRadioRxLed(false);
+
+ //Turn off the TX LED to end the blink
+ blinkRadioTxLed(false);
+
+ //Pulse width modulate the RSSI LED (GREEN_LED_3)
+ blinkRadioRssiLed();
+
+ //Leave the LINK LED (GREEN_LED_2) off
+
+ //Update the hop LED
+ if ((millis() - radioCallHistory[RADIO_CALL_hopChannel]) >= RADIO_USE_BLINK_MILLIS)
+ digitalWrite(YELLOW_LED, LED_OFF);
+
+ //Update the HEARTBEAT LED
+ blinkHeartbeatLed(false);
+}
+
+//Display the VC LED pattern
+void vcLeds()
+{
+ uint32_t currentMillis;
+ static uint32_t blinkSyncMillis;
+
+ //Turn off the RX LED to end the blink
+ blinkRadioRxLed(false);
+
+ //Turn off the TX LED to end the blink
+ blinkRadioTxLed(false);
+
+ //Pulse width modulate the RSSI LED (GREEN_LED_3)
+ currentMillis = millis();
+ if (virtualCircuitList[VC_SERVER].vcState)
+ blinkRadioRssiLed();
+
+#define VC_SYNC_BLINK_RATE (1000 / 4)
+
+ //Turn on the RSSI LED
+ else if (((currentMillis - blinkSyncMillis) >= (VC_SYNC_BLINK_RATE >> 1))
+ && (digitalRead(GREEN_LED_3) == LED_OFF))
+ digitalWrite(GREEN_LED_3, LED_ON);
+
+ //Turn off the RSSI LED
+ else if ((!virtualCircuitList[VC_SERVER].vcState)
+ && (((currentMillis - blinkSyncMillis) >= VC_SYNC_BLINK_RATE))
+ && (digitalRead(GREEN_LED_3) == LED_ON))
+ {
+ digitalWrite(GREEN_LED_3, LED_OFF);
+ blinkSyncMillis = currentMillis;
+ }
+
+ //Serial RX displayed on the LINK LED (GREEN_LED_2) by blinkSerialRxLed
+
+ //Update the hop LED
+ if ((millis() - radioCallHistory[RADIO_CALL_hopChannel]) >= RADIO_USE_BLINK_MILLIS)
+ digitalWrite(YELLOW_LED, LED_OFF);
+
+ //Update the HEARTBEAT LED
+ blinkHeartbeatLed(false);
+}
+
+//Update the cylon LEDs
+void updateCylonLEDs()
+{
+ //Display the cylon pattern on the RSSI LEDs
+ blinkRadioRssiLed();
+
+ //Use the blue and yellow LEDS to indicate radio activity during training
+ //Turn off the RX LED to end the blink
+ blinkRadioRxLed(false);
+
+ //Turn off the TX LED to end the blink
+ blinkRadioTxLed(false);
+}
+
+//Acknowledge the button press
+void buttonLeds(uint32_t pressedMilliseconds)
+{
+ const uint32_t blinkTime = 1000 / 4; //Blink 4 times per second
+ uint8_t on;
+ const uint32_t onTime = blinkTime / 2;
+ uint8_t seconds;
+
+ //Display the number of seconds the button has been pushed
+ seconds = pressedMilliseconds / 1000;
+ setRSSI((pressedMilliseconds >= trainButtonFactoryResetTime) ? 15 : seconds);
+
+ if (!inCommandMode)
+ {
+ //Determine the blink state
+ on = (pressedMilliseconds % blinkTime) >= onTime;
+
+ //Determine which LED to blink
+ if (pressedMilliseconds >= trainButtonServerTime)
+ {
+ //Blink the blue LED
+ digitalWrite(BLUE_LED, on);
+ digitalWrite(YELLOW_LED, 0);
+ }
+ else if (pressedMilliseconds >= trainButtonClientTime)
+ //Blink the yellow LED
+ digitalWrite(YELLOW_LED, on);
+ }
+}
+
+//Update the LED values depending upon the selected display
+//This is the only function that touches the LEDs
+void updateLeds()
+{
+ static uint8_t previousLedUse;
+
+ //When changing patterns, start with the LEDs off
+ if (previousLedUse != settings.selectLedUse)
+ {
+ previousLedUse = settings.selectLedUse;
+ digitalWrite(GREEN_LED_1, LED_OFF);
+ digitalWrite(GREEN_LED_2, LED_OFF);
+ digitalWrite(GREEN_LED_3, LED_OFF);
+ digitalWrite(GREEN_LED_4, LED_OFF);
+ digitalWrite(BLUE_LED, LED_OFF);
+ digitalWrite(YELLOW_LED, LED_OFF);
+ }
+
+ //Display the LEDs
+ switch (settings.selectLedUse)
+ {
+ //Set LEDs according to RSSI level
+ default:
+ //Display the RSSI LED pattern
+ case LEDS_RSSI:
+ blinkRadioRssiLed();
+ break;
+
+ //Display the multipoint LED pattern
+ case LEDS_MULTIPOINT:
+ multiPointLeds();
+ break;
+
+ //Display the point-to-point LED pattern
+ case LEDS_P2P:
+ p2pLeds();
+ break;
+
+ //Display the multipoint LED pattern
+ case LEDS_VC:
+ vcLeds();
+ break;
+
+ //Display the cylon LED pattern
+ case LEDS_CYLON:
+ updateCylonLEDs();
+ break;
+
+ //Display the radio use LED pattern
+ case LEDS_RADIO_USE:
+ radioLeds();
+ break;
+
+ //Turn off all the LEDs
+ case LEDS_ALL_OFF:
+ break;
+
+ //Turn on the blue LED for testing
+ case LEDS_BLUE_ON:
+ digitalWrite(BLUE_LED, LED_ON);
+ break;
+
+ //Turn on the yellow LED for testing
+ case LEDS_YELLOW_ON:
+ digitalWrite(YELLOW_LED, LED_ON);
+ break;
+
+ //Turn on the green 1 LED for testing
+ case LEDS_GREEN_1_ON:
+ digitalWrite(GREEN_LED_1, LED_ON);
+ break;
+
+ //Turn on the green 2 LED for testing
+ case LEDS_GREEN_2_ON:
+ digitalWrite(GREEN_LED_2, LED_ON);
+ break;
+
+ //Turn on the green 3 LED for testing
+ case LEDS_GREEN_3_ON:
+ digitalWrite(GREEN_LED_3, LED_ON);
+ break;
+
+ //Turn on the green 4 LED for testing
+ case LEDS_GREEN_4_ON:
+ digitalWrite(GREEN_LED_4, LED_ON);
+ break;
+
+ //Turn on all the LEDs for testing
+ case LEDS_ALL_ON:
+ digitalWrite(GREEN_LED_1, LED_ON);
+ digitalWrite(GREEN_LED_2, LED_ON);
+ digitalWrite(GREEN_LED_3, LED_ON);
+ digitalWrite(GREEN_LED_4, LED_ON);
+ digitalWrite(BLUE_LED, LED_ON);
+ digitalWrite(YELLOW_LED, LED_ON);
+ break;
+ }
+}
+
+//Case independent string comparison
+int stricmp(const char * str1, const char * str2)
+{
+ char char1;
+ char char2;
+
+ //Do a case insensitive comparison between the two strings
+ do {
+ char1 = toupper(*str1++);
+ char2 = toupper(*str2++);
+ } while (char1 && (char1 == char2));
+
+ //Return the difference between the two strings
+ return char1 - char2;
+}
+
+//Case independent string comparison with specified maximum length
+int strnicmp(const char * str1, const char * str2, int length)
+{
+ char char1;
+ char char2;
+
+ //Do a case insensitive comparison between the two strings
+ do {
+ char1 = toupper(*str1++);
+ char2 = toupper(*str2++);
+ } while (char1 && (char1 == char2) && --length);
+
+ //Return the difference between the two strings
+ return char1 - char2;
+}
+
+//Display the RSSI, SNR and frequency error values
+void printPacketQuality()
+{
+ if (settings.printPacketQuality == true)
+ {
+ systemPrintln();
+ systemPrint("R:");
+ systemPrint(rssi);
+ systemPrint("\tS:");
+ systemPrint(radio.getSNR());
+ systemPrint("\tfE:");
+ systemPrint(radio.getFrequencyError());
+ systemPrintln();
+ }
+}
+
+//Toggle a pin. Used for logic analyzer debugging.
+void triggerFrequency(uint16_t frequency)
+{
+ digitalWrite(pin_trigger, LOW);
+ delayMicroseconds(frequency);
+ digitalWrite(pin_trigger, HIGH);
+}
+
+//Verify the VC_STATE_TYPE enums against the vcStateNames table
+const char * verifyVcStateNames()
+{
+ bool valid;
+
+ //Verify the length of the vcStateNames table
+ valid = (VC_STATE_MAX == (sizeof(vcStateNames) / sizeof(vcStateNames[0])));
+ if (!valid)
+ return "ERROR: Fix difference between VC_STATE_TYPE and vcStateNames";
+ return NULL;
+}
+
+//Verify the enums .vs. name tables, stop on failure to force software fix
+void verifyTables()
+{
+ const char * errorMessage;
+
+ do
+ {
+ //Verify that the state table contains all of the states in increasing order
+ errorMessage = verifyRadioStateTable();
+ if (errorMessage)
+ break;
+
+ //Verify that the datagram type table contains all of the datagram types
+ errorMessage = verifyRadioDatagramType();
+ if (errorMessage)
+ break;
+
+ //Verify the VC state name table
+ errorMessage = verifyVcStateNames();
+ if (errorMessage)
+ break;
+
+ //Verify the RADIO_CALLS enum against the radioCallName
+ errorMessage = verifyRadioCallNames();
+ } while (0);
+
+ //Handle the error
+ if (errorMessage)
+ waitForever(errorMessage);
+}
diff --git a/Firmware/LoRaSerial/Train.ino b/Firmware/LoRaSerial/Train.ino
new file mode 100644
index 00000000..ec076ba5
--- /dev/null
+++ b/Firmware/LoRaSerial/Train.ino
@@ -0,0 +1,203 @@
+//Select the training protocol
+void selectTraining()
+{
+ if (settings.server)
+ beginTrainingServer();
+ else
+ beginTrainingClient();
+}
+
+//Generate new netID/AES key to share
+//We assume the user needs to maintain their settings (airSpeed, numberOfChannels, freq min/max, bandwidth/spread/hop)
+//but need to be on a different netID/AES key.
+void generateRandomKeysID(Settings * radioSettings)
+{
+ if ((settings.debug == true) || (settings.debugTraining == true))
+ {
+ systemPrintln("Generate New Training Settings");
+ outputSerialData(true);
+ }
+
+ //Seed random number based on RF noise. We use Arduino random() because platform specific generation does not matter
+ randomSeed(radio.randomByte());
+
+ //Generate new NetID
+ radioSettings->netID = random(0, 256); //Inclusive, exclusive
+
+ //Generate new AES Key. User may not be using AES but we still need both radios to have the same key in case they do enable AES.
+ for (int x = 0 ; x < 16 ; x++)
+ radioSettings->encryptionKey[x] = random(0, 256); //Inclusive, exclusive
+
+ //We do not generate new AES Initial Values here. Those are generated during generateHopTable() based on the unit's settings.
+
+ if ((settings.debug == true) || (settings.debugTraining == true))
+ {
+ systemPrint("Select new NetID: ");
+ systemPrintln(radioSettings->netID);
+
+ systemPrint("Select new Encryption Key:");
+ for (uint8_t i = 0 ; i < 16 ; i++)
+ {
+ systemPrint(" ");
+ systemPrint(radioSettings->encryptionKey[i], HEX);
+ }
+ systemPrintln();
+ outputSerialData(true);
+ }
+}
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Client/Server Training
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Start the training in client mode
+void beginTrainingClient()
+{
+ //Common initialization
+ commonTrainingInitialization();
+
+ //Transmit FIND_PARTNER to the training server
+ if (xmitDatagramTrainingFindPartner() == true)
+ //Set the next state
+ changeState(RADIO_TRAIN_WAIT_TX_FIND_PARTNER_DONE);
+ else
+ changeState(RADIO_TRAIN_WAIT_RX_RADIO_PARAMETERS);
+}
+
+//Start the training in server mode
+void beginTrainingServer()
+{
+ petWDT();
+ trainingServerRunning = true;
+
+ //Display the values to be used for the client/server training
+ systemPrintln("Server training parameters");
+ systemPrint(" Training netID: ");
+ systemPrintln(settings.netID);
+ systemPrint(" Training key: ");
+ displayEncryptionKey(settings.trainingKey);
+ systemPrintln();
+
+ //Common initialization
+ commonTrainingInitialization();
+ settings.server = true; //52: Operate as the training server
+
+ systemPrintln("Server radio protocol parameters");
+ systemPrint(" netID: ");
+ systemPrintln(trainingSettings.netID);
+ systemPrint(" Encryption key: ");
+ displayEncryptionKey(trainingSettings.encryptionKey);
+ systemPrintln();
+ outputSerialData(true);
+
+ //Start the receive operation
+ returnToReceiving();
+
+ //Set the next state
+ changeState(RADIO_TRAIN_WAIT_FOR_FIND_PARTNER);
+}
+
+//Perform the common training initialization
+void commonTrainingInitialization()
+{
+ //Use common radio settings between the client and server for training
+ settings = defaultSettings;
+ settings.dataScrambling = true; //Scramble the data
+ settings.enableCRC16 = true; //Use CRC-16
+ settings.encryptData = true; //Enable packet encryption
+ memcpy(&settings.encryptionKey, &trainingSettings.trainingKey, AES_KEY_BYTES); //Common encryption key
+ settings.frequencyHop = false; //Stay on the training frequency
+ settings.maxResends = 1; //Don't waste time retransmitting
+ settings.netID = 'T'; //NetID for training
+ settings.operatingMode = MODE_MULTIPOINT; //Use datagrams
+ settings.radioBroadcastPower_dbm = 14; //Minimum, assume radios are near each other
+ settings.selectLedUse = LEDS_CYLON; //Display the CYLON pattern on the LEDs
+ settings.verifyRxNetID = true; //Disable netID checking
+
+ //Determine the components of the frame header and trailer
+ selectHeaderAndTrailerBytes();
+
+ //Debug training if requested
+ if (trainingSettings.debugTraining)
+ {
+ settings.selectLedUse = trainingSettings.selectLedUse;
+ //Ignore copyDebug
+ settings.debug = trainingSettings.debug;
+ settings.debugDatagrams = trainingSettings.debugDatagrams;
+ settings.debugHeartbeat = trainingSettings.debugHeartbeat;
+ settings.debugNvm = trainingSettings.debugNvm;
+ settings.debugRadio = trainingSettings.debugRadio;
+ settings.debugReceive = trainingSettings.debugReceive;
+ settings.debugSerial = trainingSettings.debugSerial;
+ settings.debugStates = trainingSettings.debugStates;
+ settings.debugSync = trainingSettings.debugSync;
+ settings.debugTraining = trainingSettings.debugTraining;
+ settings.debugTransmit = trainingSettings.debugTransmit;
+ settings.displayRealMillis = trainingSettings.displayRealMillis;
+ settings.printAckNumbers = trainingSettings.printAckNumbers;
+ settings.printChannel = trainingSettings.printChannel;
+ settings.printFrequency = trainingSettings.printFrequency;
+ settings.printLinkUpDown = trainingSettings.printLinkUpDown;
+ settings.printPacketQuality = trainingSettings.printPacketQuality;
+ settings.printPktData = trainingSettings.printPktData;
+ settings.printRfData = trainingSettings.printRfData;
+ settings.printTimestamp = trainingSettings.printTimestamp;
+ settings.printTxErrors = trainingSettings.printTxErrors;
+
+ //Ignore copyTriggers
+ settings.triggerEnable = trainingSettings.triggerEnable;
+ settings.triggerEnable2 = trainingSettings.triggerEnable2;
+ settings.triggerWidth = trainingSettings.triggerWidth;
+ settings.triggerWidthIsMultiplier = trainingSettings.triggerWidthIsMultiplier;
+ }
+
+ //Reset cylon variables
+ startCylonLEDs();
+
+ petWDT();
+
+ generateHopTable(); //Generate frequency table based on current settings
+
+ //Select the training frequency, a multiple of channels down from the maximum
+ petWDT();
+ float channelSpacing = (settings.frequencyMax - settings.frequencyMin) / (float)(settings.numberOfChannels + 2);
+ float trainFrequency = settings.frequencyMax - (channelSpacing * (FIRMWARE_VERSION_MAJOR % settings.numberOfChannels));
+ originalChannel = channels[0]; //Remember the original channel
+ channels[0] = trainFrequency; //Inject this frequency into the channel table
+
+ //Use only the first channel of the previously allocated channel table
+ petWDT();
+ configureRadio(); //Setup radio with settings
+}
+
+//Upon successful exchange of parameters, switch to the new radio settings
+void endClientServerTraining(uint8_t event)
+{
+ triggerEvent(event);
+ settings = trainingSettings; //Return to original radio settings
+
+ if (settings.debugTraining)
+ {
+ displayParameters(0, settings.copyDebug || settings.copyTriggers);
+ outputSerialData(true);
+ }
+
+ if (settings.server == false)
+ {
+ //Record the new client settings
+ petWDT();
+ recordSystemSettings();
+
+ systemPrint("Link trained from ");
+ systemPrintUniqueID(trainingPartnerID);
+ systemPrintln();
+
+ outputSerialData(true);
+ }
+
+ //Done with training
+ trainingServerRunning = false;
+
+ //Reboot the radio with the new parameters
+ commandReset();
+}
diff --git a/Firmware/LoRaSerial/Virtual_Circuit_Protocol.h b/Firmware/LoRaSerial/Virtual_Circuit_Protocol.h
new file mode 100644
index 00000000..bf59bc8c
--- /dev/null
+++ b/Firmware/LoRaSerial/Virtual_Circuit_Protocol.h
@@ -0,0 +1,199 @@
+#ifndef __VIRTUAL_CIRCUIT_PROTOCOL_H__
+#define __VIRTUAL_CIRCUIT_PROTOCOL_H__
+
+//------------------------------------------------------------------------------
+// Constants
+//------------------------------------------------------------------------------
+
+//Define the virtual circuit address byte
+#define VCAB_NUMBER_BITS 5
+#define MAX_VC (1 << VCAB_NUMBER_BITS)
+#define VCAB_NUMBER_MASK (MAX_VC - 1)
+#define VCAB_CHANNEL_BITS (8 - VCAB_NUMBER_BITS)
+#define VCAB_CHANNEL_MASK ((1 << VCAB_CHANNEL_BITS) - 1)
+
+//Communications over the virtual circuit are broken down into the following
+//address spaces:
+//
+// 0 - Data communications
+// 1 - Remote commands
+// 2 - 3rd party commands
+// 3 - Reserved
+// 4 - Reserved
+// 5 - 3rd Party PC responses
+// 6 - Remote responses
+// 7 - Special virtual circuits
+
+//The following addresses are reserved for data communications: 0 - VCAB_NUMBER_MASK
+//Address zero is reserved for the server
+#define VC_SERVER 0
+
+//Address space 7 is reserved for the following special addresses:
+
+#define VC_RSVD_SPECIAL_VCS ((int8_t)(VCAB_CHANNEL_MASK << VCAB_NUMBER_BITS))
+#define VC_BROADCAST ((int8_t)(VC_RSVD_SPECIAL_VCS | VCAB_NUMBER_MASK))
+#define VC_COMMAND (VC_BROADCAST - 1) //Command input and command response
+#define VC_UNASSIGNED (VC_COMMAND - 1)
+#define VC_IGNORE_TX (VC_UNASSIGNED - 1)
+
+//Source and destinations reserved for the local host
+#define PC_COMMAND VC_RSVD_SPECIAL_VCS //Command input and command response
+#define PC_LINK_STATUS (PC_COMMAND + 1) //Asynchronous link status output
+#define PC_DATA_ACK (PC_LINK_STATUS + 1)//Indicate data delivery success
+#define PC_DATA_NACK (PC_DATA_ACK + 1) //Indicate data delivery failure
+#define PC_SERIAL_RECONNECT (PC_DATA_NACK + 1) //Disconnect/reconnect the serial port over LoRaSerial CPU reset
+#define PC_COMMAND_COMPLETE (PC_SERIAL_RECONNECT + 1)//Command complete
+
+//Address space 1 and 6 are reserved for the host PC interface to support remote
+//command processing. The radio removes these bits and converts them to the
+//appropriate datagram type. Upon reception of one of these messages the bit is
+//added back into the VC header and the message is delivered to the host PC.
+//As a result, any host may send commands to any other host!
+#define MIN_RX_NOT_ALLOWED VC_RSVD_SPECIAL_VCS
+#define PC_REMOTE_RESPONSE ((int8_t)(6 << VCAB_NUMBER_BITS))
+#define THIRD_PARTY_RESP ((int8_t)(5 << VCAB_NUMBER_BITS))
+//Address spaces 3 - 4 are not currently defined
+#define MIN_TX_NOT_ALLOWED ((int8_t)(3 << VCAB_NUMBER_BITS)) //Marker only
+#define THIRD_PARTY_COMMAND ((int8_t)(2 << VCAB_NUMBER_BITS))
+#define PC_REMOTE_COMMAND ((int8_t)(1 << VCAB_NUMBER_BITS))
+
+//Field offsets in the VC HEARTBEAT frame
+#define VC_HB_UNIQUE_ID 0
+#define VC_HB_MILLIS (VC_HB_UNIQUE_ID + UNIQUE_ID_BYTES)
+#define VC_HB_CHANNEL_TIMER (VC_HB_MILLIS + sizeof(uint32_t))
+#define VC_HB_CHANNEL (VC_HB_CHANNEL_TIMER + sizeof(uint16_t))
+#define VC_HB_END (VC_HB_CHANNEL + sizeof(uint8_t))
+
+#define VC_LINK_BREAK_MULTIPLIER 3 //Number of missing HEARTBEAT timeouts
+
+//ASCII characters
+#define START_OF_VC_SERIAL 0x02 //From ASCII table - Start of Text
+
+//------------------------------------------------------------------------------
+// Protocol Exchanges
+//------------------------------------------------------------------------------
+/*
+ Host Interaction using Virtual-Circuits
+
+ Host A LoRa A LoRa B Host B
+
+ All output goes to serial .
+ .
+ +++ ----> .
+ <---- OK
+ .
+ .
+ .
+ <---- Command responses
+ <---- Debug message
+
+ Mode: VC ---->
+ <---- OK
+
+ (VC debug) <---- Debug message
+
+ CMD: AT&W ---->
+ (VC command) <---- OK
+
+ CMD: LINK_RESET ---->
+ HEARTBEAT -2 ---->
+ HEARTBEAT # <---- From server
+
+ (VC status) <---- Link self up
+
+ HEARTBEAT # ---->
+
+ (VC status) <---- Link A up Link A Up ----> (link status)
+
+ (VC debug) <---- Debug message
+
+ <---- HEARTBEAT B
+ (VC status) <---- Link B Up
+
+ (VC debug) <---- Debug message
+
+ MSG: Data for B ---->
+ Data for B ---->
+ <---- ACK
+ Data for B ----> MSG: Data for B
+ <---- MSG: Resp for A
+ <---- Resp for A
+ ACK ---->
+ MSG: Resp for A <---- Resp for A
+
+*/
+//------------------------------------------------------------------------------
+// Types
+//------------------------------------------------------------------------------
+
+typedef struct _VC_RADIO_MESSAGE_HEADER
+{
+ uint8_t length; //Length in bytes of the VC message
+ int8_t destVc; //Destination VC
+ int8_t srcVc; //Source VC
+} VC_RADIO_MESSAGE_HEADER;
+
+#define VC_RADIO_HEADER_BYTES (sizeof(VC_RADIO_MESSAGE_HEADER)) //Length of the radio VC header in bytes
+
+typedef struct _VC_SERIAL_MESSAGE_HEADER
+{
+ uint8_t start; //START_OF_HEADING
+ VC_RADIO_MESSAGE_HEADER radio;
+} VC_SERIAL_MESSAGE_HEADER;
+
+#define VC_SERIAL_HEADER_BYTES (sizeof(VC_SERIAL_MESSAGE_HEADER)) //Length of the serial VC header in bytes
+
+typedef struct _VC_STATE_MESSAGE
+{
+ uint8_t vcState; //VC state
+} VC_STATE_MESSAGE;
+
+typedef enum
+{
+ VC_STATE_LINK_DOWN = 0, //0: HEARTBEATs not received
+ VC_STATE_LINK_ALIVE, //1: Receiving HEARTBEATs, waiting for UNKNOWN_ACKS
+ VC_STATE_SEND_UNKNOWN_ACKS, //2: ATC command received, sending UNKNOWN_ACKS
+ VC_STATE_WAIT_SYNC_ACKS, //3: UNKNOWN_ACKS sent, waiting for SYNC_ACKS
+ VC_STATE_WAIT_ZERO_ACKS, //4: SYNC_ACKS sent, waiting for ZERO_ACKS
+ VC_STATE_CONNECTED, //5: ZERO_ACKS received, ACKs cleared, ready to send data
+
+ //Insert new states before this line
+ VC_STATE_MAX
+} VC_STATE_TYPE;
+
+typedef struct _VC_DATA_ACK_NACK_MESSAGE
+{
+ uint8_t msgDestVc; //Message destination VC
+} VC_DATA_ACK_NACK_MESSAGE;
+
+#define VC_CMD_SUCCESS 0
+#define VC_CMD_ERROR 1
+
+typedef struct _VC_COMMAND_COMPLETE_MESSAGE
+{
+ uint8_t cmdStatus; //Command status
+} VC_COMMAND_COMPLETE_MESSAGE;
+
+//------------------------------------------------------------------------------
+// Macros
+//------------------------------------------------------------------------------
+
+#define DATA_BYTES(vc_message_length) (vc_message_length - VC_RADIO_HEADER_BYTES)
+#define DATA_BUFFER(data) (data + VC_RADIO_HEADER_BYTES)
+#define GET_CHANNEL_NUMBER(vc) (vc & (VCAB_CHANNEL_MASK << VCAB_NUMBER_BITS))
+
+//------------------------------------------------------------------------------
+// Constants
+//------------------------------------------------------------------------------
+
+//Only one instance of this table is necessary
+#ifdef ADD_VC_STATE_NAMES_TABLE
+const char * const vcStateNames[] =
+{ // 0 1
+ "LINK-DOWN", "LINK-ALIVE",
+ // 2 3 4 5
+ "UNKNOWN-ACKS", "SYNC-ACKS", "ZERO-ACKS", "CONNECTED",
+};
+#endif //ADD_VC_STATE_NAMES_TABLE
+
+#endif //__VIRTUAL_CIRCUIT_PROTOCOL_H__
diff --git a/Firmware/LoRaSerial_Firmware/build.h b/Firmware/LoRaSerial/build.h
similarity index 100%
rename from Firmware/LoRaSerial_Firmware/build.h
rename to Firmware/LoRaSerial/build.h
diff --git a/Firmware/LoRaSerial/settings.h b/Firmware/LoRaSerial/settings.h
new file mode 100644
index 00000000..15b090a2
--- /dev/null
+++ b/Firmware/LoRaSerial/settings.h
@@ -0,0 +1,612 @@
+typedef enum
+{
+ RADIO_RESET = 0,
+
+ //Point-To-Point: Bring up the link
+ RADIO_P2P_LINK_DOWN,
+ RADIO_P2P_WAIT_TX_FIND_PARTNER_DONE,
+ RADIO_P2P_WAIT_SYNC_CLOCKS,
+ RADIO_P2P_WAIT_TX_SYNC_CLOCKS_DONE,
+ RADIO_P2P_WAIT_ZERO_ACKS,
+ RADIO_P2P_WAIT_TX_ZERO_ACKS_DONE,
+
+ //Point-to-Point: Link up, data exchange
+ RADIO_P2P_LINK_UP,
+ RADIO_P2P_LINK_UP_WAIT_TX_DONE,
+
+ //Server-client discovery
+ RADIO_DISCOVER_BEGIN,
+ RADIO_DISCOVER_SCANNING,
+ RADIO_DISCOVER_WAIT_TX_FIND_PARTNER_DONE,
+ RADIO_DISCOVER_STANDBY,
+
+ //Multi-Point: Datagrams
+ RADIO_MP_STANDBY,
+ RADIO_MP_WAIT_TX_DONE,
+
+ //Training client states
+ RADIO_TRAIN_WAIT_TX_FIND_PARTNER_DONE,
+ RADIO_TRAIN_WAIT_RX_RADIO_PARAMETERS,
+ RADIO_TRAIN_WAIT_TX_PARAM_ACK_DONE,
+
+ //Training server states
+ RADIO_TRAIN_WAIT_FOR_FIND_PARTNER,
+ RADIO_TRAIN_WAIT_TX_RADIO_PARAMS_DONE,
+
+ //Virtual-Circuit states
+ RADIO_VC_WAIT_SERVER,
+ RADIO_VC_WAIT_TX_DONE,
+ RADIO_VC_WAIT_RECEIVE,
+
+ RADIO_MAX_STATE,
+} RadioStates;
+
+RadioStates radioState = RADIO_RESET;
+
+#define P2P_LINK_BREAK_MULTIPLIER 3
+
+typedef struct _RADIO_STATE_ENTRY
+{
+ RadioStates state;
+ bool rxState;
+ const char * name;
+ const char * description;
+} RADIO_STATE_ENTRY;
+
+const RADIO_STATE_ENTRY radioStateTable[] =
+{
+ {RADIO_RESET, 0, "RESET", NULL}, // 0
+
+ //Point-to-Point link handshake
+ // State RX Name Description
+ {RADIO_P2P_LINK_DOWN, 1, "P2P_LINK_DOWN", "P2P: [No Link] Waiting for FIND_PARTNER"}, // 1
+ {RADIO_P2P_WAIT_TX_FIND_PARTNER_DONE, 0, "P2P_WAIT_TX_FIND_PARTNER_DONE", "P2P: [No Link] Wait FIND_PARTNER TX Done"},// 2
+ {RADIO_P2P_WAIT_SYNC_CLOCKS, 1, "P2P_WAIT_SYNC_CLOCKS", "P2P: [No Link] Waiting for SYNC_CLOCKS"}, // 3
+ {RADIO_P2P_WAIT_TX_SYNC_CLOCKS_DONE, 0, "P2P_WAIT_TX_SYNC_CLOCKS_DONE", "P2P: [No Link] Wait SYNC_CLOCKS TX Done"}, // 4
+ {RADIO_P2P_WAIT_ZERO_ACKS, 1, "P2P_WAIT_ZERO_ACKS", "P2P: [No Link] Waiting for ZERO_ACKS"}, // 5
+ {RADIO_P2P_WAIT_TX_ZERO_ACKS_DONE, 0, "P2P_WAIT_TX_ZERO_ACKS_DONE", "P2P: [No Link] Wait ZERO_ACKS TX Done"}, // 6
+
+ //Point-to-Point, link up, data exchange
+ // State RX Name Description
+ {RADIO_P2P_LINK_UP, 1, "P2P_LINK_UP", "P2P: Receiving Standby"}, // 7
+ {RADIO_P2P_LINK_UP_WAIT_TX_DONE, 0, "P2P_LINK_UP_WAIT_TX_DONE", "P2P: Waiting TX done"}, // 8
+
+ //Server-client discovery
+ // State RX Name Description
+ {RADIO_DISCOVER_BEGIN, 0, "DISCOVER_BEGIN", "Disc: Setup for scanning"}, // 9
+ {RADIO_DISCOVER_SCANNING, 0, "DISCOVER_SCANNING", "Disc: Scanning for servers"}, //10
+ {RADIO_DISCOVER_WAIT_TX_FIND_PARTNER_DONE, 0, "DISCOVER_WAIT_TX_FIND_PARTNER_DONE", "Disc: Wait for FIND_PARTNER to xmit"}, //11
+ {RADIO_DISCOVER_STANDBY, 0, "RADIO_DISCOVER_STANDBY", "Disc: Wait for Server HB"}, //12
+
+ //Multi-Point data exchange
+ // State RX Name Description
+ {RADIO_MP_STANDBY, 1, "MP_STANDBY", "MP: Wait for TX or RX"}, //13
+ {RADIO_MP_WAIT_TX_DONE, 0, "MP_WAIT_TX_DONE", "MP: Waiting for TX done"}, //14
+
+ //Training client states
+ // State RX Name Description
+ {RADIO_TRAIN_WAIT_TX_FIND_PARTNER_DONE, 0, "TRAIN_WAIT_TX_FIND_PARTNER_DONE", "Train: Wait TX training FIND_PARTNER done"}, //15
+ {RADIO_TRAIN_WAIT_RX_RADIO_PARAMETERS, 1, "TRAIN_WAIT_RX_RADIO_PARAMETERS", "Train: Wait for radio parameters"}, //16
+ {RADIO_TRAIN_WAIT_TX_PARAM_ACK_DONE, 0, "TRAIN_WAIT_TX_PARAM_ACK_DONE", "Train: Wait for TX param ACK done"}, //17
+
+ //Training server states
+ // State RX Name Description
+ {RADIO_TRAIN_WAIT_FOR_FIND_PARTNER, 1, "TRAIN_WAIT_FOR_FIND_PARTNER", "Train: Wait for training FIND_PARTNER"}, //18
+ {RADIO_TRAIN_WAIT_TX_RADIO_PARAMS_DONE, 0, "TRAIN_WAIT_TX_RADIO_PARAMS_DONE", "Train: Wait for TX params done"}, //19
+
+ //Virtual circuit states
+ // State RX Name Description
+ {RADIO_VC_WAIT_SERVER, 1, "VC_WAIT_SERVER", "VC: Wait for the server"}, //20
+ {RADIO_VC_WAIT_TX_DONE, 0, "VC_WAIT_TX_DONE", "VC: Wait for TX done"}, //21
+ {RADIO_VC_WAIT_RECEIVE, 1, "VC_WAIT_RECEIVE", "VC: Wait for receive"}, //22
+};
+
+//Possible types of packets received
+typedef enum
+{
+ //Sync frequencies, HEARTBEAT timing and zero ACKs
+ //P2P: Between the two LoRaSerial radios
+ //VC: Between the server radio and a client radio
+ DATAGRAM_FIND_PARTNER = 0, // 0
+ DATAGRAM_SYNC_CLOCKS, // 1
+ DATAGRAM_ZERO_ACKS, // 2
+
+ //Point-to-Point data exchange
+ DATAGRAM_DATA, // 3
+ DATAGRAM_DATA_ACK, // 4
+ DATAGRAM_HEARTBEAT, // 5
+ DATAGRAM_REMOTE_COMMAND, // 6
+ DATAGRAM_REMOTE_COMMAND_RESPONSE, // 7
+
+ //Multi-Point data exchange
+ DATAGRAM_DATAGRAM, // 8
+
+ //Multi-Point training exchange
+ DATAGRAM_TRAINING_FIND_PARTNER, // 9
+ DATAGRAM_TRAINING_PARAMS, //10
+ DATAGRAM_TRAINING_ACK, //11
+
+ //Virtual-Circuit (VC) exchange
+ DATAGRAM_VC_HEARTBEAT, //12
+ DATAGRAM_VC_UNKNOWN_ACKS, //13 Synchronize ACKs client VC to client VC
+ DATAGRAM_VC_SYNC_ACKS, //14
+ DATAGRAM_VC_ZERO_ACKS, //15
+
+ //Add new datagram types before this line
+ MAX_DATAGRAM_TYPE,
+
+ //Add new protocol datagrams above this line
+
+ //Common datagram types
+ DATAGRAM_BAD,
+ DATAGRAM_CRC_ERROR,
+ DATAGRAM_NETID_MISMATCH,
+ DATAGRAM_DUPLICATE,
+ DATAGRAM_NOT_MINE,
+} PacketType;
+
+const char * const radioDatagramType[] =
+{ // 0 1 2
+ "FIND_PARTNER", "ACK-1", "ACK-2",
+ // 3 4 5 6 7
+ "DATA", "DATA-ACK", "HEARTBEAT", "RMT-CMD", "RMT_RESP",
+ // 8
+ "DATAGRAM",
+ // 9 10 11
+ "TRAINING_FIND_PARTNER", "TRAINING_PARAMS", "TRAINING_ACK",
+ // 12
+ "VC_HEARTBEAT",
+ // 13 14 15
+ "VC_UNKNOWN_ACKS", "VC_SYNC_ACKS", "VC_ZERO_ACKS",
+};
+
+typedef struct _VC_FLAGS
+{
+ bool valid : 1; //Unique ID is valid
+ bool wasConnected : 1; //The VC was previously connected
+} VC_FLAGS;
+
+typedef struct _VIRTUAL_CIRCUIT
+{
+ uint8_t uniqueId[UNIQUE_ID_BYTES];
+ unsigned long firstHeartbeatMillis; //Time VC link came up
+ unsigned long lastTrafficMillis; //Last time a frame was received
+ unsigned long timerMillis; //Last time the timer was started, after handshake or ACK
+
+ //Link quality metrics
+ uint32_t framesSent; //myVc --> VC, Total number of frames sent
+ uint32_t framesReceived; //myVc <-- VC, Total number of frames received
+ uint32_t messagesSent; //myVc --> VC, Total number of messages sent
+ uint32_t messagesReceived; //myVc <-- VC, Total number of messages received
+ uint32_t badLength; //myVc <-- VC, Total number of bad lengths received
+ uint32_t linkFailures; //myVc <-> VC, Total number of link failures
+
+ //Link management
+
+ VC_FLAGS flags;
+ uint8_t vcState; //State of VC
+
+ /* ACK number management
+
+ System A System B
+ (in destVc) (in srcVc)
+
+ txAckNumber
+ |
+ V
+ Tx DATA Frame -----------------------> Rx DATA Frame
+ |
+ V
+ AckNumber == rmtTxAckNumber
+ |
+ | yes
+ V
+ rxAckNumber = rmtTxAckNumber++
+ |
+ V
+ Rx DATA_Ack Frame <--------------------- Tx DATA_ACK Frame
+ |
+ V
+ ackNumber == txAckNumber
+ |
+ | yes
+ V
+ txAckNumber++
+ */
+
+ uint8_t rmtTxAckNumber; //Next expected ACK # from remote system in DATA frame,
+ //incremented upon match to received DATA frame ACK number,
+ //indicates frame was received and processed
+ //Duplicate frame if received ACK # == (rmtTxAckNumber -1)
+ uint8_t rxAckNumber; //Received ACK # of the most recent acknowledged DATA frame,
+ //does not get incremented, used to ACK the data frame
+ uint8_t txAckNumber; //# of next ACK to be sent by the local system in DATA frame,
+ //incremented when successfully acknowledged via DATA_ACK frame
+} VIRTUAL_CIRCUIT;
+
+#define ADD_VC_STATE_NAMES_TABLE
+#include "Virtual_Circuit_Protocol.h"
+
+enum
+{ //#, Width - Computed with:
+ // triggerWidth = 25
+ // triggerUseWidthAsMultiplier = true
+ // triggerEnable = 0xffffffff
+
+ TRIGGER_BAD_PACKET,
+ TRIGGER_CHANNEL_TIMER_ISR,
+ TRIGGER_CRC_ERROR,
+ TRIGGER_RECEIVE_IN_PROCESS,
+ TRIGGER_DUMMY_READ,
+ TRIGGER_FREQ_CHANGE,
+ TRIGGER_HANDSHAKE_COMPLETE,
+ TRIGGER_HANDSHAKE_SEND_FIND_PARTNER_COMPLETE,
+ TRIGGER_HANDSHAKE_SEND_SYNC_CLOCKS_COMPLETE,
+ TRIGGER_HANDSHAKE_SYNC_CLOCKS_TIMEOUT,
+ TRIGGER_HANDSHAKE_ZERO_ACKS_TIMEOUT,
+ TRIGGER_HOP_TIMER_START,
+ TRIGGER_HOP_TIMER_STOP,
+ TRIGGER_MP_PACKET_RECEIVED,
+ TRIGGER_MP_SCAN,
+ TRIGGER_MP_TX_DATA,
+ TRIGGER_NETID_MISMATCH,
+ TRIGGER_RADIO_RESET,
+ TRIGGER_RETRANSMIT,
+ TRIGGER_RETRANSMIT_FAIL,
+ TRIGGER_RTR_255BYTE,
+ TRIGGER_RTR_SHORT_PACKET,
+ TRIGGER_RX_ACK,
+ TRIGGER_RX_COMMAND,
+ TRIGGER_RX_COMMAND_RESPONSE,
+ TRIGGER_RX_DATA,
+ TRIGGER_RX_DATAGRAM,
+ TRIGGER_RX_FIND_PARTNER,
+ TRIGGER_RX_HEARTBEAT,
+ TRIGGER_RX_SPI_DONE,
+ TRIGGER_RX_SYNC_CLOCKS,
+ TRIGGER_RX_VC_HEARTBEAT,
+ TRIGGER_RX_VC_SYNC_ACKS,
+ TRIGGER_RX_VC_UNKNOWN_ACKS,
+ TRIGGER_RX_VC_ZERO_ACKS,
+ TRIGGER_RX_YIELD,
+ TRIGGER_RX_ZERO_ACKS,
+ TRIGGER_SYNC_CHANNEL_TIMER,
+ TRIGGER_TRAINING_CLIENT_RX_PARAMS,
+ TRIGGER_TRAINING_CLIENT_TX_ACK_DONE,
+ TRIGGER_TRAINING_CLIENT_TX_FIND_PARTNER_DONE,
+ TRIGGER_TRAINING_SERVER_RX,
+ TRIGGER_TRAINING_SERVER_RX_ACK,
+ TRIGGER_TRAINING_SERVER_TX_PARAMS_DONE,
+ TRIGGER_TRANSACTION_COMPLETE,
+ TRIGGER_TRANSMIT_CANCELED,
+ TRIGGER_TX_ACK,
+ TRIGGER_TX_COMMAND,
+ TRIGGER_TX_COMMAND_RESPONSE,
+ TRIGGER_TX_DATA,
+ TRIGGER_TX_DATAGRAM,
+ TRIGGER_TX_DONE,
+ TRIGGER_TX_DUPLICATE_ACK,
+ TRIGGER_TX_FIND_PARTNER,
+ TRIGGER_TX_HEARTBEAT,
+ TRIGGER_TX_LOAD_CHANNEL_TIMER_VALUE,
+ TRIGGER_TX_SPI_DONE,
+ TRIGGER_TX_SYNC_CLOCKS,
+ TRIGGER_TX_VC_HEARTBEAT,
+ TRIGGER_TX_VC_SYNC_ACKS,
+ TRIGGER_TX_VC_UNKNOWN_ACKS,
+ TRIGGER_TX_VC_ZERO_ACKS,
+ TRIGGER_TX_YIELD,
+ TRIGGER_TX_ZERO_ACKS,
+ TRIGGER_UNKNOWN_PACKET,
+};
+
+//Control where to print command output
+typedef enum
+{
+ PRINT_TO_SERIAL = 0,
+ PRINT_TO_RF,
+} PrinterEndpoints;
+PrinterEndpoints printerEndpoint = PRINT_TO_SERIAL;
+
+//Select the operating mode
+typedef enum
+{
+ MODE_MULTIPOINT = 0,
+ MODE_POINT_TO_POINT,
+ MODE_VIRTUAL_CIRCUIT,
+} OPERATING_MODE;
+
+typedef struct _CONTROL_U8
+{
+ PacketType datagramType: 4;
+ uint8_t ackNumber : 2;
+ uint8_t requestYield : 1;
+ uint8_t ignoreFrame : 1;
+} CONTROL_U8;
+
+typedef bool (* VALIDATION_ROUTINE)(void * value, uint32_t valMin, uint32_t valMax);
+
+typedef struct _COMMAND_ENTRY
+{
+ char letter;
+ char requireAll;
+ bool forceRadioReset;
+ uint32_t minValue;
+ uint32_t maxValue;
+ uint8_t digits;
+ uint8_t type;
+ VALIDATION_ROUTINE validate;
+ const char * name;
+ void * setting;
+} COMMAND_ENTRY;
+
+typedef enum
+{
+ LEDS_MULTIPOINT = 0, // 0: Green1: RX, Green2: Sync, Green3: RSSI, Green4: TX
+ // Blue: Hop, Yellow: HEARTBEAT RX/TX
+ LEDS_P2P, // 1: Green: RSSI, Blue: Serial TX, Yellow: Serial RX
+ LEDS_VC, // 2; Green1: RX, Green2: Sync, Green3: RSSI, Green4: TX
+ // Blue: Hop, Yellow: HEARTBEAT RX/TX
+ LEDS_RADIO_USE, // 3: Green1: RX, Green2: Link, Green3: RSSI, Green4: TX
+ // Blue: Bad frames, Yellow: Bad CRC
+ LEDS_RSSI, // 4: Green: RSSI, Blue: Serial TX, Yellow: Serial RX
+ LEDS_BUTTON_PRESS,// 5: Green: Seconds, Yellow: Client, Blue: Server
+ LEDS_RESERVED_2, // 6
+ LEDS_CYLON, // 7: Display the cylon pattern on the green LEDs, others off
+
+ //Testing
+ LEDS_ALL_OFF, // 8: All LEDs off
+ LEDS_BLUE_ON, // 9: Blue: ON, other: OFF
+ LEDS_YELLOW_ON, //10; Yellow: ON, other: OFF
+ LEDS_GREEN_1_ON, //11; Green 1: ON, other: OFF
+ LEDS_GREEN_2_ON, //12; Green 2: ON, other: OFF
+ LEDS_GREEN_3_ON, //13; Green 3: ON, other: OFF
+ LEDS_GREEN_4_ON, //14: Green 4: ON, other: OFF
+ LEDS_ALL_ON, //15: All LEDs on
+
+ //Add user LED types from 255 working down
+} LEDS_USE_TYPE;
+
+typedef struct _CLOCK_SYNC_DATA
+{
+ int16_t msToNextHopRemote;
+ uint16_t frameAirTimeMsec;
+ uint16_t msToNextHop;
+ int16_t lclHopTimeMsec;
+ int16_t adjustment;
+ int8_t delayedHopCount;
+ bool timeToHop;
+} CLOCK_SYNC_DATA;
+
+//These are all the settings that can be set on Serial Terminal Radio. It's recorded to NVM.
+typedef struct struct_settings {
+ uint16_t sizeOfSettings = 0; //sizeOfSettings **must** be the first entry and must be int
+ uint16_t strIdentifier = LRS_IDENTIFIER; // strIdentifier **must** be the second entry
+
+ //----------------------------------------
+ //Radio parameters
+ //----------------------------------------
+
+ float frequencyMin = 902.0; //MHz
+ float frequencyMax = 928.0; //MHz
+ float radioBandwidth = 500.0; //kHz 125/250/500 generally. We need 500kHz for higher data.
+ uint32_t txToRxUsec = 657; //TX transactionComplete to RX transactionComplete in microseconds
+
+ bool frequencyHop = true; //Hop between frequencies to avoid dwelling on any one channel for too long
+ uint8_t numberOfChannels = 50; //Divide the min/max freq band into this number of channels and hop between.
+ uint16_t maxDwellTime = 400; //Max number of ms before hopping (if enabled). Useful for configuring radio to be within regulator limits (FCC = 400ms max)
+
+#if (ENABLE_DEVELOPER == true)
+#define TX_POWER_DB 14
+#else //ENABLE_DEVELOPER
+#define TX_POWER_DB 30
+#endif //ENABLE_DEVELOPER
+ uint8_t radioBroadcastPower_dbm = TX_POWER_DB; //Transmit power in dBm. Max is 30dBm (1W), min is 14dBm (25mW).
+ uint8_t radioCodingRate = 8; //5 to 8. Higher coding rates ensure less packets dropped.
+ uint8_t radioSpreadFactor = 9; //6 to 12. Use higher factor for longer range.
+ uint8_t radioSyncWord = 18; //18 = 0x12 is default for custom/private networks. Different sync words does *not* guarantee a remote radio will not get packet.
+
+ uint16_t radioPreambleLength = 8; //Number of symbols. Different lengths does *not* guarantee a remote radio privacy. 8 to 11 works. 8 to 15 drops some. 8 to 20 is silent.
+ bool autoTuneFrequency = false; //Based on the last packets frequency error, adjust our next transaction frequency
+
+ //----------------------------------------
+ //Radio protocol parameters
+ //----------------------------------------
+
+ uint8_t operatingMode = MODE_POINT_TO_POINT; //Receiving unit will check netID and ACK. If set to false, receiving unit doesn't check netID or ACK.
+
+ uint8_t selectLedUse = LEDS_RSSI; //Select LED use
+ bool server = false; //Default to being a client, enable server for multipoint, VC and training
+ uint8_t netID = 192; //Both radios must share a network ID
+ bool verifyRxNetID = true; //Verify RX netID value when not operating in point-to-point mode
+
+ uint8_t encryptionKey[AES_KEY_BYTES] = { 0x37, 0x78, 0x21, 0x41, 0xA6, 0x65, 0x73, 0x4E, 0x44, 0x75, 0x67, 0x2A, 0xE6, 0x30, 0x83, 0x08 };
+
+ bool encryptData = true; //AES encrypt each packet
+ bool dataScrambling = false; //Use IBM Data Whitening to reduce DC bias
+ bool enableCRC16 = true; //Append CRC-16 to packet, check CRC-16 upon receive
+ uint8_t framesToYield = 3; //If remote requests it, supress transmission for this number of max packet frames
+
+ uint16_t heartbeatTimeout = 5000; //ms before sending HEARTBEAT to see if link is active
+ uint16_t overheadTime = 10; //ms added to ack and datagram times before ACK timeout occurs
+
+ uint8_t maxResends = 0; //Attempt resends up to this number, 0 = infinite retries
+
+ //----------------------------------------
+ //Serial parameters
+ //----------------------------------------
+
+ bool copySerial = false; //Copy the serial parameters to the training client
+ bool invertCts = false; //Invert the input of CTS
+ bool invertRts = false; //Invert the output of RTS
+
+ uint32_t serialSpeed = 57600; //Default to 57600bps to match RTK Surveyor default firmware
+
+ uint16_t serialTimeoutBeforeSendingFrame_ms = 50; //Send partial buffer if time expires
+ bool echo = false; //Print locally inputted serial
+ bool flowControl = false; //Enable the use of CTS/RTS flow control signals
+#if (ENABLE_DEVELOPER == true)
+#define WAIT_SERIAL_DEFAULT true
+#else //ENABLE_DEVELOPER
+#define WAIT_SERIAL_DEFAULT false
+#endif //ENABLE_DEVELOPER
+ bool usbSerialWait = WAIT_SERIAL_DEFAULT; //Wait for USB serial initialization
+
+ //----------------------------------------
+ //Training parameters
+ //----------------------------------------
+
+ uint8_t clientFindPartnerRetryInterval = 3; //Number of seconds before retransmiting the client FIND_PARTNER
+
+ uint8_t trainingKey[AES_KEY_BYTES] = { 0x53, 0x70, 0x61, 0x72, 0x6b, 0x46, 0x75, 0x6E, 0x54, 0x72, 0x61, 0x69, 0x6e, 0x69, 0x6e, 0x67 };
+
+ uint8_t trainingTimeout = 1; //Timeout in minutes to complete the training
+
+ //----------------------------------------
+ //Trigger parameters
+ //----------------------------------------
+
+ bool copyTriggers = false; //Copy the trigger parameters to the training client
+ uint8_t triggerWidth = 25; //Trigger width in microSeconds or multipler for trigger width
+ bool triggerWidthIsMultiplier = true; //Use the trigger width as a multiplier
+
+ uint32_t triggerEnable = 0; //Determine which triggers are enabled: 31 - 0
+ uint32_t triggerEnable2 = 0; //Determine which triggers are enabled: 63 - 32
+
+
+ //----------------------------------------
+ //Debug parameters
+ //----------------------------------------
+
+ bool copyDebug = false; //Copy the debug parameters to the training client
+ bool debug = false; //Print basic events: ie, radio state changes
+ bool debugDatagrams = false; //Print the datagrams
+ bool debugHeartbeat = false; //Print the HEARTBEAT timing values
+
+ bool debugNvm = false; //Debug NVM operation
+ bool debugRadio = false; //Print radio info
+ bool debugReceive = false; //Print receive processing
+ bool debugSerial = false; //Debug the serial input
+
+ bool debugStates = false; //Print state changes
+ bool debugSync = false; //Print clock sync processing
+ bool debugTraining = false; //Print training info
+ bool debugTransmit = false; //Print transmit processing
+
+ bool displayRealMillis = false; //true = Display the millis value without offset, false = use offset
+ bool printAckNumbers = false; //Print the ACK numbers
+ bool printChannel = false; //Print the channel number
+ bool printFrequency = false; //Print the updated frequency
+
+ bool printLinkUpDown = false; //Print the link up and link down messages
+ bool printPacketQuality = false; //Print RSSI, SNR, and freqError for received packets
+ bool printPktData = false; //Print data, before encryption and after decryption
+ bool printRfData = false; //Print RX and TX data
+
+ bool printTimestamp = false; //Print a timestamp: days hours:minutes:seconds.milliseconds
+ bool printTxErrors = false; //Print any transmit errors
+
+ //Add new parameters immediately before this line
+ //-- Add commands to set the parameters
+ //-- Add parameters to routine updateRadioParameters
+} Settings;
+
+//Monitor which devices on the device are on or offline.
+struct struct_online {
+ bool radio = false;
+ bool eeprom = false;
+} online;
+
+#include //Click here to get the library: http://librarymanager/All#RadioLib v5.5.0
+
+typedef void (* ARCH_BEGIN_BOARD)();
+typedef void (* ARCH_BEGIN_SERIAL)(uint16_t serialSpeed);
+typedef void (* ARCH_BEGIN_WDT)();
+typedef void (* ARCH_EEPROM_BEGIN)();
+typedef void (* ARCH_EEPROM_COMMIT)();
+typedef void (* ARCH_PET_WDT)();
+typedef Module * (* ARCH_RADIO)();
+typedef bool (* ARCH_SERIAL_AVAILABLE)();
+typedef void (* ARCH_SERIAL_FLUSH)();
+typedef uint8_t (* ARCH_SERIAL_READ)();
+typedef void (* ARCH_SERIAL_WRITE)(uint8_t value);
+typedef void (* ARCH_SYSTEM_RESET)();
+typedef void (* ARCH_UNIQUE_ID)(uint8_t * unique128_BitID);
+
+typedef struct _ARCH_TABLE
+{
+ ARCH_BEGIN_BOARD beginBoard; //Initialize the board
+ ARCH_BEGIN_SERIAL beginSerial; //Finish initializing the serial port
+ ARCH_BEGIN_WDT beginWDT; //Initialize the watchdog timer
+ ARCH_EEPROM_BEGIN eepromBegin; //Start an EEPROM operation
+ ARCH_EEPROM_COMMIT eepromCommit;//Done with the EEPROM operation
+ ARCH_PET_WDT petWDT; //Reset the expiration time for the WDT
+ ARCH_RADIO radio; //Initialize the radio
+ ARCH_SERIAL_AVAILABLE serialAvailable; //Determine if serial data is available
+ ARCH_SERIAL_FLUSH serialFlush; //Flush the serial port
+ ARCH_SERIAL_READ serialRead; //Read a byte from the serial port
+ ARCH_SERIAL_WRITE serialWrite; //Print the specified character
+ ARCH_SYSTEM_RESET systemReset; //Reset the system
+ ARCH_UNIQUE_ID uniqueID; //Get the 128 bit unique ID value
+} ARCH_TABLE;
+
+typedef struct _U8_TO_STRING
+{
+ uint8_t value;
+ const char * string;
+} U8_TO_STRING;
+
+typedef struct _I16_TO_STRING
+{
+ int16_t value;
+ const char * string;
+} I16_TO_STRING;
+
+//Declare the radio call types
+typedef enum
+{
+ RADIO_CALL_configureRadio = 0,
+ RADIO_CALL_setRadioFrequency,
+ RADIO_CALL_returnToReceiving,
+ RADIO_CALL_calcAirTimeUsec,
+ RADIO_CALL_xmitDatagramP2PFindPartner,
+ RADIO_CALL_xmitDatagramP2PSyncClocks,
+ RADIO_CALL_xmitDatagramP2PZeroAcks,
+ RADIO_CALL_xmitDatagramP2PCommand,
+ RADIO_CALL_xmitDatagramP2PCommandResponse,
+ RADIO_CALL_xmitDatagramP2PData,
+ RADIO_CALL_xmitDatagramP2PHeartbeat,
+ RADIO_CALL_xmitDatagramP2PAck,
+ RADIO_CALL_xmitDatagramMpData,
+ RADIO_CALL_xmitDatagramMpHeartbeat,
+ RADIO_CALL_xmitDatagramTrainingFindPartner,
+ RADIO_CALL_xmitDatagramTrainingAck,
+ RADIO_CALL_xmitDatagramTrainRadioParameters,
+ RADIO_CALL_xmitVcDatagram,
+ RADIO_CALL_xmitVcHeartbeat,
+ RADIO_CALL_xmitVcAckFrame,
+ RADIO_CALL_xmitVcUnknownAcks,
+ RADIO_CALL_xmitVcSyncAcks,
+ RADIO_CALL_xmitVcZeroAcks,
+ RADIO_CALL_rcvDatagram,
+ RADIO_CALL_transmitDatagram,
+ RADIO_CALL_retransmitDatagram,
+ RADIO_CALL_startChannelTimer,
+ RADIO_CALL_stopChannelTimer,
+ RADIO_CALL_syncChannelTimer,
+ RADIO_CALL_setHeartbeatShort,
+ RADIO_CALL_setHeartbeatLong,
+ RADIO_CALL_setHeartbeatMultipoint,
+ RADIO_CALL_setVcHeartbeatTimer,
+ RADIO_CALL_hopChannel,
+
+ //Insert new values before this line
+ RADIO_CALL_transactionCompleteISR,
+ RADIO_CALL_hopISR,
+ RADIO_CALL_channelTimerHandler,
+#ifdef RADIOLIB_LOW_LEVEL
+ RADIO_CALL_readSX1276Register,
+ RADIO_CALL_printSX1276Registers,
+#endif //RADIOLIB_LOW_LEVEL
+ RADIO_CALL_MAX
+} RADIO_CALLS;
diff --git a/Firmware/LoRaSerial_Firmware/Begin.ino b/Firmware/LoRaSerial_Firmware/Begin.ino
deleted file mode 100644
index 1bdb6389..00000000
--- a/Firmware/LoRaSerial_Firmware/Begin.ino
+++ /dev/null
@@ -1,85 +0,0 @@
-//Based on hardware features, determine which hardware this is
-void beginBoard()
-{
- //Initialize the board specific hardware
- arch.beginBoard();
-
- //Dashbord Blink LEDs
- for (int x = 0 ; x < 3 ; x++)
- {
- digitalWrite(pin_rssi1LED, HIGH);
- digitalWrite(pin_rssi2LED, HIGH);
- digitalWrite(pin_rssi3LED, HIGH);
- digitalWrite(pin_rssi4LED, HIGH);
- digitalWrite(pin_txLED, HIGH);
- digitalWrite(pin_rxLED, HIGH);
- delay(50);
-
- digitalWrite(pin_rssi1LED, LOW);
- digitalWrite(pin_rssi2LED, LOW);
- digitalWrite(pin_rssi3LED, LOW);
- digitalWrite(pin_rssi4LED, LOW);
- digitalWrite(pin_txLED, LOW);
- digitalWrite(pin_rxLED, LOW);
- delay(50);
- }
-}
-
-void beginLoRa()
-{
- radio = arch.radio();
-
- float centerFreq = (settings.frequencyMax - settings.frequencyMin) / 2;
- centerFreq += settings.frequencyMin;
-
- int state = radio.begin(centerFreq); //Doesn't matter what freq we start at
- if (state != RADIOLIB_ERR_NONE)
- {
- systemPrint("Radio init failed with code: ");
- systemPrintln(state);
- while (1)
- {
- petWDT();
- delay(100);
- }
- }
-
- changeState(RADIO_RESET);
-}
-
-void beginButton()
-{
- if (pin_trainButton != 255)
- {
- trainBtn = new Button(pin_trainButton); //Create the button
- trainBtn->begin();
- }
-}
-
-//Delay with pets of WDT when needed
-void delayWDT(uint16_t delayAmount)
-{
- unsigned long startTime = millis();
- while (millis() - startTime < delayAmount)
- {
- delay(1);
- petWDT();
- }
-}
-
-void beginSerial(uint16_t serialSpeed)
-{
- Serial.begin(serialSpeed);
- arch.beginSerial(serialSpeed);
-}
-
-void petWDT()
-{
- //Petting the dog takes a long time so its only done after we've passed the
- //half way point
- if (millis() - lastPet > petTimeoutHalf)
- {
- lastPet = millis();
- arch.petWDT();
- }
-}
diff --git a/Firmware/LoRaSerial_Firmware/Commands.ino b/Firmware/LoRaSerial_Firmware/Commands.ino
deleted file mode 100644
index 641c6f86..00000000
--- a/Firmware/LoRaSerial_Firmware/Commands.ino
+++ /dev/null
@@ -1,716 +0,0 @@
-//To add a new ATSxx command:
-//Add an entry to the "commands" table below
-
-//To add a new commnd prefix such as AT or RT
-//Add an entry to the "prefix" table below
-
-//----------------------------------------
-// Data structures
-//----------------------------------------
-
-enum {
- TYPE_BOOL = 0,
- TYPE_FLOAT,
- TYPE_KEY,
- TYPE_SPEED_AIR,
- TYPE_SPEED_SERIAL,
- TYPE_U8,
- TYPE_U16,
- TYPE_U32,
-} TYPES;
-
-typedef bool (* VALIDATION_ROUTINE)(void * value, uint32_t valMin, uint32_t valMax);
-
-typedef struct _COMMAND_ENTRY
-{
- uint8_t number;
- int32_t minValue;
- int32_t maxValue;
- uint8_t digits;
- uint8_t type;
- VALIDATION_ROUTINE validate;
- const char * name;
- void * setting;
-} COMMAND_ENTRY;
-
-typedef bool (* COMMAND_ROUTINE)(const char * commandString);
-typedef struct
-{
- const char * prefix;
- COMMAND_ROUTINE processCommand;
-} COMMAND_PREFIX;
-
-//----------------------------------------
-// Command prefix routines
-//----------------------------------------
-
-bool commandAT(const char * commandString)
-{
- //'AT'
- if (commandLength == 2)
- reportOK();
-
- //ATI, ATO, ATZ commands
- else if (commandLength == 3)
- {
- switch (commandString[2])
- {
- case ('?'): //Display the command help
- systemPrintln("Command summary:");
- systemPrintln(" AT? - Print the command summary");
- systemPrintln(" ATF - Enter training mode and return to factory defaults");
- systemPrintln(" ATI - Display the radio version");
- systemPrintln(" ATI? - Display the information commands");
- systemPrintln(" ATIn - Display system information");
- systemPrintln(" ATO - Exit command mode");
- systemPrintln(" ATSn=xxx - Set parameter n's value to xxx");
- systemPrintln(" ATSn? - Print parameter n's current value");
- systemPrintln(" ATT - Enter training mode");
- systemPrintln(" ATX - Stop the training server");
- systemPrintln(" ATZ - Reboot the radio");
- break;
- case ('F'): //Enter training mode and return to factory defaults
- reportOK();
- beginDefaultTraining();
- break;
- case ('I'):
- //Shows the radio version
- reportOK();
- systemPrint("SparkFun LoRaSerial ");
- systemPrint(platformPrefix);
- systemPrint(" v");
- systemPrint(FIRMWARE_VERSION_MAJOR);
- systemPrint(".");
- systemPrintln(FIRMWARE_VERSION_MINOR);
- break;
- case ('O'): //Exit command mode
- if (printerEndpoint == PRINT_TO_RF)
- {
- //If we are pointed at the RF link, send ok and wait for response ACK before applying settings
- confirmDeliveryBeforeRadioConfig = true;
- reportOK();
- }
- else
- {
- //Apply settings and return
- generateHopTable(); //Generate freq with new settings
- configureRadio(); //Apply any new settings
-
- setRSSI(0); //Turn off LEDs
- if (settings.pointToPoint == true)
- changeState(RADIO_NO_LINK_RECEIVING_STANDBY);
- else
- changeState(RADIO_BROADCASTING_RECEIVING_STANDBY);
-
- inCommandMode = false; //Return to printing normal RF serial data
-
- reportOK();
- }
- break;
- case ('T'): //Enter training mode
- reportOK();
- beginTraining();
- break;
- case ('Z'): //Reboots the radio
- reportOK();
- systemFlush();
- systemReset();
- break;
- default:
- return false;
- }
- }
-
- //ATIx commands
- else if (commandString[2] == 'I' && commandLength == 4)
- {
- uint32_t uniqueID[4];
-
- switch (commandString[3])
- {
- case ('?'): //ATI? - Display the information commands
- systemPrintln(" ATI0 - Show user settable parameters");
- systemPrintln(" ATI1 - Show board variant");
- systemPrintln(" ATI2 - Show firmware version");
- systemPrintln(" ATI3 - Display RSSI value");
- systemPrintln(" ATI4 - Get random byte from RSSI");
- systemPrintln(" ATI5 - Show max possible bytes per second");
- systemPrintln(" ATI6 - Display AES key");
- systemPrintln(" ATI7 - Show current FHSS channel");
- systemPrintln(" ATI8 - Display unique ID");
- break;
- case ('0'): //ATI0 - Show user settable parameters
- displayParameters();
- break;
- case ('1'): //ATI1 - Show board variant
- systemPrint("SparkFun LoRaSerial ");
- systemPrint(platformPrefix);
- systemPrint("\r\n");
- break;
- case ('2'): //ATI2 - Show firmware version
- systemPrint(FIRMWARE_VERSION_MAJOR);
- systemPrint(".");
- systemPrintln(FIRMWARE_VERSION_MINOR);
- break;
- case ('3'): //ATI3 - Display latest RSSI
- systemPrintln(radio.getRSSI());
- break;
- case ('4'): //ATI4 - Get random byte from RSSI
- systemPrintln(radio.randomByte());
- break;
- case ('5'): //ATI5 - Show max possible bytes per second
- systemPrintln(calcMaxThroughput());
- break;
- case ('6'): //ATI6 - Display AES key
- for (uint8_t i = 0 ; i < 16 ; i++)
- systemPrint(settings.encryptionKey[i], HEX);
- systemPrintln();
- break;
- case ('7'): //ATI7 - Show current FHSS channel
- systemPrintln(radio.getFHSSChannel());
- break;
- case ('8'): //ATI8 - Display the unique ID
- arch.uniqueID(uniqueID);
- systemPrintUniqueID(uniqueID);
- systemPrintln();
- break;
- default:
- return false;
- }
- }
-
- //AT&x commands
- else if (commandString[2] == '&')
- {
- //&W, &F, &T, and &T=RSSI/TDM
- if (commandLength == 4)
- {
- switch (commandString[3])
- {
- case ('W'): //AT&W - Write parameters to the flash memory
- {
- recordSystemSettings();
- reportOK();
- }
- break;
- case ('F'): //AT&F - Restore default parameters
- {
- settings = defaultSettings; //Overwrite all current settings with defaults
- recordSystemSettings();
- reportOK();
- }
- break;
- default:
- return false;
- }
- }
- else
- {
- //RSSI
- if (strcmp_P(commandString, PSTR("AT&T=RSSI")) == 0) //Enable packet quality reporting
- {
- settings.displayPacketQuality = true;
- reportOK();
- }
- else
- return false;
- }
- }
- else
- return false;
- return true;
-}
-
-//Send the AT command over RF link
-bool sendRemoteCommand(const char * commandString)
-{
- //We cannot send a command if not linked
- if (isLinked() == false)
- return false;
-
- //Move this command into the transmit buffer
- for (int x = 0 ; x < commandLength ; x++)
- {
- commandTXBuffer[commandTXHead++] = commandString[x];
- commandTXHead %= sizeof(commandTXBuffer);
- }
- return true;
-}
-
-//----------------------------------------
-// Command prefix table
-//----------------------------------------
-
-const COMMAND_PREFIX prefixTable[] = {
- {"ATS", commandSet},
- {"AT", commandAT},
- {"RT", sendRemoteCommand},
-};
-
-const int prefixCount = sizeof(prefixTable) / sizeof(prefixTable[0]);
-
-//----------------------------------------
-// Command processing routine
-//----------------------------------------
-
-//Check to see if a valid command has been received
-void checkCommand()
-{
- char * commandString;
- int index;
- int prefixLength;
- bool success;
-
- systemPrintln();
-
- //Verify the command length
- commandString = trimCommand(); //Remove any leading whitespace
- commandString[commandLength] = '\0'; //Terminate buffer
- if (commandLength < 2) //Too short
- reportERROR();
-
- //Locate the correct processing routine for the command prefix
- success = false;
- for (index = 0; index < prefixCount; index++)
- {
- //Locate the prefix
- prefixLength = strlen(prefixTable[index].prefix);
- if (strncmp(commandString, prefixTable[index].prefix, prefixLength) != 0)
- continue;
-
- //Process the command
- success = prefixTable[index].processCommand(commandString);
- break;
- }
-
- //Print the command failure
- if (!success)
- reportERROR();
-
- commandLength = 0; //Get ready for next command
-}
-
-void reportOK()
-{
- systemPrintln("OK");
-}
-
-void reportERROR()
-{
- systemPrintln("ERROR");
-}
-
-//Remove any preceeding or following whitespace chars
-char * trimCommand()
-{
- char * commandString = commandBuffer;
-
- while (isspace(*commandString))
- {
- commandString++;
- commandLength--;
- }
- return commandString;
-}
-
-//----------------------------------------
-// Data validation routines
-//----------------------------------------
-
-bool valBandwidth (void * value, uint32_t valMin, uint32_t valMax)
-{
- double doubleSettingValue = *(double *)value;
-
- if ((settings.airSpeed != 0) && (doubleSettingValue != 0))
- {
- systemPrintln("AirSpeed is overriding");
- return false;
- }
-
- //Some doubles get rounded incorrectly
- return ((settings.airSpeed != 0)
- || ((doubleSettingValue * 100) == 1040)
- || (doubleSettingValue == 15.6)
- || ((doubleSettingValue * 100) == 2080)
- || (doubleSettingValue == 31.25)
- || (doubleSettingValue == 41.7)
- || (doubleSettingValue == 62.5)
- || (doubleSettingValue == 125.0)
- || (doubleSettingValue == 250.0)
- || (doubleSettingValue == 500.0));
-}
-
-bool valFreqMax (void * value, uint32_t valMin, uint32_t valMax)
-{
- double doubleSettingValue = *(double *)value;
-
- return ((doubleSettingValue >= settings.frequencyMin) && (doubleSettingValue <= (double)valMax));
-}
-
-bool valFreqMin (void * value, uint32_t valMin, uint32_t valMax)
-{
- double doubleSettingValue = *(double *)value;
-
- return ((doubleSettingValue >= (double)valMin) && (doubleSettingValue <= settings.frequencyMax));
-}
-
-bool valInt (void * value, uint32_t valMin, uint32_t valMax)
-{
- int settingValue = *(uint32_t *)value;
-
- return ((settingValue >= valMin) && (settingValue <= valMax));
-}
-
-bool valKey (void * value, uint32_t valMin, uint32_t valMax)
-{
- int length;
- char * str = (char *)value;
- char * strEnd;
-
- //Validate the length of the encryption key
- length = strlen(str);
- if (length != (2 * sizeof(settings.encryptionKey)))
- return false;
-
- //Validate the characters in the encryption key
- strEnd = &str[length];
- if (strlen(str) == length)
- {
- while (str < strEnd)
- {
- if (charToHex(*str) < 0)
- break;
- str++;
- }
- if (str >= strEnd)
- return true;
- }
- return false;
-}
-
-bool valOverride (void * value, uint32_t valMin, uint32_t valMax)
-{
- int settingValue = *(uint32_t *)value;
-
- if (settings.airSpeed != 0)
- {
- systemPrintln("AirSpeed is overriding");
- return false;
- }
-
- return ((settingValue >= valMin) && (settingValue <= valMax));
-}
-
-bool valSpeedAir (void * value, uint32_t valMin, uint32_t valMax)
-{
- bool valid;
- uint32_t settingValue = *(uint32_t *)value;
-
- valid = ((settingValue == 0)
- || (settingValue == 40)
- || (settingValue == 150)
- || (settingValue == 400)
- || (settingValue == 1200)
- || (settingValue == 2400)
- || (settingValue == 4800)
- || (settingValue == 9600)
- || (settingValue == 19200)
- || (settingValue == 28800)
- || (settingValue == 38400));
- if (valid && (settings.airSpeed == 0) && (settingValue != 0))
- systemPrintln("Warning: AirSpeed override of bandwidth, spread factor, and coding rate");
- return valid;
-}
-
-bool valSpeedSerial (void * value, uint32_t valMin, uint32_t valMax)
-{
- uint32_t settingValue = *(uint32_t *)value;
-
- return ((settingValue == 2400)
- || (settingValue == 4800)
- || (settingValue == 9600)
- || (settingValue == 14400)
- || (settingValue == 19200)
- || (settingValue == 38400)
- || (settingValue == 57600)
- || (settingValue == 115200));
-}
-
-//----------------------------------------
-// Command table
-//----------------------------------------
-
-const COMMAND_ENTRY commands[] =
-{//#, min, max, digits, type, validation, name, setting addr
- {0, 0, 0, 0, TYPE_SPEED_SERIAL, valSpeedSerial, "SerialSpeed", &settings.serialSpeed},
- {1, 0, 0, 0, TYPE_SPEED_AIR, valSpeedAir, "AirSpeed", &settings.airSpeed},
- {2, 0, 255, 0, TYPE_U8, valInt, "netID", &settings.netID},
- {3, 0, 1, 0, TYPE_BOOL, valInt, "PointToPoint", &settings.pointToPoint},
- {4, 0, 1, 0, TYPE_BOOL, valInt, "EncryptData", &settings.encryptData},
-
- {5, 0, 0, 0, TYPE_KEY, valKey, "EncryptionKey", &settings.encryptionKey},
- {6, 0, 1, 0, TYPE_BOOL, valInt, "DataScrambling", &settings.dataScrambling},
- {7, 14, 30, 0, TYPE_U8, valInt, "TxPower", &settings.radioBroadcastPower_dbm},
- {8, 902, 0, 3, TYPE_FLOAT, valFreqMin, "FrequencyMin", &settings.frequencyMin},
- {9, 0, 928, 3, TYPE_FLOAT, valFreqMax, "FrequencyMax", &settings.frequencyMax},
-
- {10, 1, 255, 0, TYPE_U8, valInt, "NumberOfChannels", &settings.numberOfChannels},
- {11, 0, 1, 0, TYPE_BOOL, valInt, "FrequencyHop", &settings.frequencyHop},
- {12, 10, 65535, 0, TYPE_U16, valInt, "MaxDwellTime", &settings.maxDwellTime},
- {13, 0, 0, 2, TYPE_FLOAT, valBandwidth, "Bandwidth", &settings.radioBandwidth},
- {14, 6, 12, 0, TYPE_U8, valOverride, "SpreadFactor", &settings.radioSpreadFactor},
-
- {15, 5, 8, 0, TYPE_U8, valOverride, "CodingRate", &settings.radioCodingRate},
- {16, 0, 255, 0, TYPE_U8, valInt, "SyncWord", &settings.radioSyncWord},
- {17, 6, 65535, 0, TYPE_U16, valInt, "PreambleLength", &settings.radioPreambleLength},
- {18, 16, 254, 0, TYPE_U8, valInt, "FrameSize", &settings.frameSize},
- {19, 10, 2000, 0, TYPE_U16, valInt, "FrameTimeout", &settings.serialTimeoutBeforeSendingFrame_ms},
-
- {20, 0, 1, 0, TYPE_BOOL, valInt, "Debug", &settings.debug},
- {21, 0, 1, 0, TYPE_BOOL, valInt, "Echo", &settings.echo},
- {22, 250, 65535, 0, TYPE_U16, valInt, "HeartBeatTimeout", &settings.heartbeatTimeout},
- {23, 0, 1, 0, TYPE_BOOL, valInt, "FlowControl", &settings.flowControl},
- {24, 0, 1, 0, TYPE_BOOL, valInt, "AutoTune", &settings.autoTuneFrequency},
-
- {25, 0, 1, 0, TYPE_BOOL, valInt, "DisplayPacketQuality", &settings.displayPacketQuality},
- {26, 0, 255, 0, TYPE_U8, valInt, "MaxResends", &settings.maxResends},
- {27, 0, 1, 0, TYPE_BOOL, valInt, "SortParametersByName", &settings.sortParametersByName},
- {28, 0, 1, 0, TYPE_BOOL, valInt, "PrintParameterName", &settings.printParameterName},
- {29, 0, 1, 0, TYPE_BOOL, valInt, "PrintFrequency", &settings.printFrequency},
-
- {30, 0, 1, 0, TYPE_BOOL, valInt, "DebugRadio", &settings.debugRadio},
- {31, 0, 1, 0, TYPE_BOOL, valInt, "DebugStates", &settings.debugStates},
- {32, 0, 1, 0, TYPE_BOOL, valInt, "DebugTraining", &settings.debugTraining},
- {33, 0, 1, 0, TYPE_BOOL, valInt, "DebugTrigger", &settings.debugTrigger},
- {34, 0, 1, 0, TYPE_BOOL, valInt, "UsbSerialWait", &settings.usbSerialWait},
-
- {35, 0, 1, 0, TYPE_BOOL, valInt, "PrintRfData", &settings.printRfData},
- {36, 0, 1, 0, TYPE_BOOL, valInt, "PrintPktData", &settings.printPktData},
- {37, 0, 1, 0, TYPE_BOOL, valInt, "VerifyRxNetID", &settings.verifyRxNetID},
- {38, 1, 255, 0, TYPE_U8, valInt, "TriggerWidth", &settings.triggerWidth},
- {39, 0, 1, 0, TYPE_BOOL, valInt, "TriggerWidthIsMultiplier", &settings.triggerWidthIsMultiplier},
-
- {40, 0, 0xffffffff, 0, TYPE_U32, valInt, "TriggerEnable: 31-0", &settings.triggerEnable},
- {41, 0, 0xffffffff, 0, TYPE_U32, valInt, "TriggerEnable: 63-32", &settings.triggerEnable},
- {42, 0, 1, 0, TYPE_BOOL, valInt, "DebugReceive", &settings.debugReceive},
- {43, 0, 1, 0, TYPE_BOOL, valInt, "DebugTransmit", &settings.debugTransmit},
- {44, 0, 1, 0, TYPE_BOOL, valInt, "PrintTxErrors", &settings.printTxErrors},
-
- {45, 0, 1, 0, TYPE_BOOL, valInt, "UseV2", &settings.useV2},
- {46, 0, 1, 0, TYPE_BOOL, valInt, "PrintTimestamp", &settings.printTimestamp},
-
- //Define any user parameters starting at 255 decrementing towards 0
-};
-
-const int commandCount = sizeof(commands) / sizeof(commands[0]);
-
-//----------------------------------------
-// ATSxx routines
-//----------------------------------------
-
-const char * commandGetNumber(const char * buffer, uint32_t * value)
-{
- int number;
-
- //Assume an invalid number
- number = -1;
- if ((*buffer >= '0') && (*buffer <= '9'))
- {
- //Get the number
- number = 0;
- while ((*buffer >= '0') && (*buffer <= '9'))
- number = (number * 10) + *buffer++ - '0';
- }
-
- //Return the command number and the pointer to the next character
- *value = number;
- return buffer;
-}
-
-void commandDisplay(uint8_t number, bool printName)
-{
- const COMMAND_ENTRY * command;
- const COMMAND_ENTRY * commandEnd;
-
- //Locate the command
- command = &commands[0];
- commandEnd = &commands[commandCount];
- while (command < commandEnd)
- if (command->number == number)
- break;
- else
- command++;
-
- //Verify the command number
- if (command >= commandEnd)
- return;
-
- //Print the setting name
- if (printName)
- {
- systemPrint(command->name);
- systemPrint("=");
- }
-
- //Print the setting value
- switch (command->type)
- {
- case TYPE_BOOL:
- systemPrint((uint8_t)(*(bool *)(command->setting)));
- break;
- case TYPE_FLOAT:
- systemPrint(*((float *)(command->setting)), command->digits);
- break;
- case TYPE_KEY:
- displayEncryptionKey((uint8_t *)(command->setting));
- break;
- case TYPE_U8:
- systemPrint(*(uint8_t *)(command->setting));
- break;
- case TYPE_U16:
- systemPrint(*(uint16_t *)(command->setting));
- break;
- case TYPE_SPEED_AIR:
- case TYPE_SPEED_SERIAL:
- case TYPE_U32:
- systemPrint(*(uint32_t *)(command->setting));
- break;
- }
- systemPrintln();
-}
-
-//Set or display the command
-bool commandSet(const char * commandString)
-{
- const char * buffer;
- const COMMAND_ENTRY * command;
- double doubleSettingValue;
- int index;
- uint32_t number;
- uint32_t settingValue;
- bool valid;
-
- do {
- //Validate the command number
- buffer = commandGetNumber(&commandString[3], &number);
- for (index = 0; index < commandCount; index++)
- if (number == commands[index].number)
- break;
- if (index >= commandCount)
- break;
- command = &commands[index];
-
- //Is this a display request
- if (strcmp(buffer, "?") == 0)
- {
- commandDisplay(command->number, settings.printParameterName);
- return true;
- }
-
- //Make sure the command has the proper syntax
- if (*buffer++ != '=')
- break;
-
- //Get the value
- doubleSettingValue = strtod(buffer, NULL);
- settingValue = doubleSettingValue;
-
- //Validate and set the value
- switch (command->type)
- {
- case TYPE_BOOL:
- valid = command->validate((void *)&settingValue, command->minValue, command->maxValue);
- if (valid)
- *(bool *)(command->setting) = (bool)settingValue;
- break;
- case TYPE_FLOAT:
- valid = command->validate((void *)&doubleSettingValue, command->minValue, command->maxValue);
- if (valid)
- *((float *)(command->setting)) = doubleSettingValue;
- break;
- case TYPE_KEY:
- valid = command->validate((void *)buffer, command->minValue, command->maxValue);
- if (valid)
- for (int x = 0; x < (2 * sizeof(settings.encryptionKey)); x += 2)
- settings.encryptionKey[x / 2] = charHexToDec(buffer[x], buffer[x + 1]);
- break;
- case TYPE_SPEED_AIR:
- case TYPE_SPEED_SERIAL:
- case TYPE_U32:
- valid = command->validate((void *)&settingValue, command->minValue, command->maxValue);
- if (valid)
- *(uint32_t *)(command->setting) = settingValue;
- break;
- case TYPE_U8:
- valid = command->validate((void *)&settingValue, command->minValue, command->maxValue);
- if (valid)
- *(uint8_t *)(command->setting) = (uint8_t)settingValue;
- break;
- case TYPE_U16:
- valid = command->validate((void *)&settingValue, command->minValue, command->maxValue);
- if (valid)
- *(uint16_t *)(command->setting) = (uint16_t)settingValue;
- break;
- }
- if (valid == false)
- break;
-
- //Display the parameter if requested
- if (settings.printParameterName)
- commandDisplay(command->number, true);
-
- //The parameter was successfully set
- reportOK();
- return true;
- } while (0);
-
- //Report the error
- return false;
-}
-
-//Display the encryption key
-void displayEncryptionKey(uint8_t * key)
-{
- for (uint8_t index = 0 ; index < sizeof(settings.encryptionKey) ; index++)
- systemPrint(key[index], HEX);
-}
-
-//Show current settings in user friendly way
-void displayParameters()
-{
- int index;
- uint8_t sortOrder[commandCount];
- uint8_t temp;
- int x;
-
- //Set the default sort order
- for (index = 0; index < commandCount; index++)
- sortOrder[index] = index;
-
- //Perform a bubble sort if requested
- if (settings.sortParametersByName)
- for (index = 0; index < commandCount; index++)
- for (x = index + 1; x < commandCount; x++)
- if (stricmp(commands[sortOrder[index]].name, commands[sortOrder[x]].name) > 0)
- {
- temp = sortOrder[index];
- sortOrder[index] = sortOrder[x];
- sortOrder[x] = temp;
- }
-
- //Print the parameters
- for (index = 0; index < commandCount; index++)
- {
- petWDT(); //Printing may take longer than WDT at 9600, so pet the WDT.
-
- if (printerEndpoint == PRINT_TO_RF)
- systemPrint("R"); //If someone is asking for our settings over RF, respond with 'R' style settings
- else
- systemPrint("A");
-
- systemPrint("TS");
- systemPrint(commands[sortOrder[index]].number);
- systemPrint(":");
- commandDisplay(commands[sortOrder[index]].number, true);
- }
-}
diff --git a/Firmware/LoRaSerial_Firmware/LoRaSerial_Firmware.ino b/Firmware/LoRaSerial_Firmware/LoRaSerial_Firmware.ino
deleted file mode 100644
index 8a6fd9a0..00000000
--- a/Firmware/LoRaSerial_Firmware/LoRaSerial_Firmware.ino
+++ /dev/null
@@ -1,230 +0,0 @@
-/*
- December 15th, 2021
- SparkFun Electronics
- Nathan Seidle
-
- This firmware runs the core of the SparkFun LoRaSerial Radio product.
- Primarily designed to run on a ATSAMD21G18A with the ebyte 1W LoRa Radio based on the SX1276.
-
- This radio is designed to operate at the physical layer of LoRa sending data directly to an end point
- as opposed to something like LoRaWAN that operates on the data and network layers. For this reason
- LoRaSerial is not intended to operate on LoRaWAN.
-
- The system requests an ACK for certain packet types.
-
- Each packet contains data plus a NetID (byte) and Control byte.
- For transmissions at SpreadFactor 6 the packet length is set to 250 bytes and an additional byte is
- transmitted before NetID that repsents the actual data length within the packet.
-
- The max packet size for the SX127x is 255 bytes. With the NetID and control bytes removed, we have
- 253 bytes available for data (252 when spread factor is 6).
-
- The AT command structure is based on the SiK Ardupilot radio.
-
- For a graphical view of the system state machine see: https://lucid.app/lucidchart/7293b4a6-690a-493e-a3f6-92bf47025fb1/edit?invitationId=inv_9476a070-5ba9-40e6-b89f-9c0d22af9855
-
- Build notes:
- RadioLib should have RADIOLIB_FIX_ERRATA_SX127X turned on (uncommented)
-
- Processors supported:
- SAMD21
- ESP32
-
- For other processors the following unique features must be considered:
- Interrupt capable pins for DIO0/1
- Processor reset (command ATZ)
- EEPROM read/write/commit
- ~14k RAM for serial RX/TX and radio buffers
-
- Compiled with Arduino v1.8.15
-*/
-
-const int FIRMWARE_VERSION_MAJOR = 1;
-const int FIRMWARE_VERSION_MINOR = 1;
-
-#define RADIOLIB_LOW_LEVEL //Enable access to the module functions
-//#define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes
-
-//Define the LoRaSerial board identifier:
-// This is an int which is unique to this variant of the LoRaSerial hardware which allows us
-// to make sure that the settings in EEPROM are correct for this version of the LoRaSerial
-// (sizeOfSettings is not necessarily unique and we want to avoid problems when swapping from one variant to another)
-// It is the sum of:
-// the major firmware version * 0x10
-// the minor firmware version
-#define LRS_IDENTIFIER (FIRMWARE_VERSION_MAJOR * 0x10 + FIRMWARE_VERSION_MINOR)
-
-#define MAX_PACKET_SIZE 255 //Limited by SX127x
-
-#include "settings.h"
-#include "build.h"
-
-//Hardware connections
-//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
-//These pins are set in beginBoard()
-uint8_t pin_rst = 255;
-uint8_t pin_cs = 255;
-uint8_t pin_txen = 255;
-uint8_t pin_rxen = 255;
-uint8_t pin_dio0 = 255;
-uint8_t pin_dio1 = 255;
-uint8_t pin_rts = 255;
-uint8_t pin_cts = 255;
-uint8_t pin_txLED = 255;
-uint8_t pin_rxLED = 255;
-uint8_t pin_trainButton = 255;
-uint8_t pin_rssi1LED = 255;
-uint8_t pin_rssi2LED = 255;
-uint8_t pin_rssi3LED = 255;
-uint8_t pin_rssi4LED = 255;
-uint8_t pin_boardID = 255;
-
-uint8_t pin_trigger = 255;
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-
-//Radio Library
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-#include //Click here to get the library: http://librarymanager/All#RadioLib v5.1.2
-SX1276 radio = NULL; //We can't instantiate here because we don't yet know what pin numbers to use
-
-float *channels;
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-
-//Encryption
-//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
-#include //From: https://github.com/rweather/arduinolibs
-#include
-#include
-GCM gcm;
-
-uint8_t AESiv[12] = {0}; //Set during hop table generation
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-
-//Buttons - Interrupt driven and debounce
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-#include // http://librarymanager/All#JC_Button
-Button *trainBtn = NULL; //We can't instantiate the button here because we don't yet know what pin number to use
-
-const int trainButtonTime = 2000; //ms press and hold before entering training
-const int trainWithDefaultsButtonTime = 5000; //ms press and hold before entering training
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-
-//Global variables - Serial
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-//Buffer to store bytes incoming from serial before broadcasting over LoRa
-uint8_t serialReceiveBuffer[1024 * 4]; //Bytes received from UART waiting to be RF transmitted. Buffer up to 1s of bytes at 4k
-uint8_t serialTransmitBuffer[1024 * 4]; //Bytes received from RF waiting to be printed out UART. Buffer up to 1s of bytes at 4k
-
-uint16_t txHead = 0;
-uint16_t txTail = 0;
-uint16_t rxHead = 0;
-uint16_t rxTail = 0;
-
-uint8_t commandRXBuffer[700]; //Bytes received from remote, waiting for printing or AT parsing
-uint8_t commandTXBuffer[700]; //Bytes waiting to be transmitted to the remote unit
-uint16_t commandTXHead = 0;
-uint16_t commandTXTail = 0;
-uint16_t commandRXHead = 0;
-uint16_t commandRXTail = 0;
-
-unsigned long lastByteReceived_ms = 0; //Track when last transmission was. Send partial buffer once time has expired.
-
-char platformPrefix[25]; //Used for printing platform specific device name, ie "SAMD21 1W 915MHz"
-uint8_t escapeCharsReceived = 0; //Used to enter command mode
-unsigned long lastEscapeReceived_ms = 0; //Tracks end of serial traffic
-const long minEscapeTime_ms = 2000; //Serial traffic must stop this amount before an escape char is recognized
-
-uint16_t petTimeoutHalf = 0; //Half the amount of time before WDT. Helps reduce amount of time spent petting.
-unsigned long lastPet = 0; //Remebers time of last WDT pet.
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-
-//Global variables - Radio
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-uint8_t outgoingPacket[MAX_PACKET_SIZE]; //Contains the current data in route to receiver
-uint8_t packetSize = 0; //Tracks how much data + control trailer
-uint16_t packetAirTime = 0; //Recalc'd with each new packet transmission
-uint16_t controlPacketAirTime = 0; //Recalc'd with each change of settings
-uint8_t packetSent = 0; //Increases each time packet is sent
-unsigned long packetTimestamp = 0;
-uint16_t packetsLost = 0; //Used to determine if radio link is down
-uint16_t packetsResent = 0; //Keep metrics of link quality
-uint16_t totalPacketsLost = 0; //Keep metrics of link quality
-
-uint8_t lastPacket[MAX_PACKET_SIZE]; //Contains the last data received. Used for duplicate testing.
-uint8_t lastPacketSize = 0; //Tracks the last packet size we received
-unsigned long lastPacketReceived = 0; //Controls link LED in broadcast mode
-unsigned long lastLinkBlink = 0; //Controls link LED in broadcast mode
-
-#define MAX_LOST_PACKET_BEFORE_LINKLOST 2
-bool sentFirstPing = false; //Force a ping to link at POR
-
-volatile bool transactionComplete = false; //Used in dio0ISR
-volatile bool timeToHop = true; //Used in dio1ISR
-bool expectingAck = false; //Used by various send packet functions
-
-float frequencyCorrection = 0; //Adjust receive freq based on the last packet received freqError
-
-unsigned long lastTrainBlink = 0; //Controls LED during training
-
-Settings originalSettings; //Create a duplicate of settings during training so that we can resort as needed
-uint8_t trainNetID; //New netID passed during training
-uint8_t trainEncryptionKey[16]; //New AES key passed during training
-
-bool inCommandMode = false; //Normal data is prevented from entering serial output when in command mode
-char commandBuffer[100]; //Received serial gets stored into buffer until \r or \n is received
-uint8_t commandLength = 0;
-
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-
-//Global variables
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-long startTime = 0; //Used for air time of TX frames
-long stopTime = 0;
-
-bool confirmDeliveryBeforeRadioConfig = false; //Goes true when we have remotely configured a radio
-
-int trainCylonNumber = 0b0001;
-int trainCylonDirection = -1;
-
-const Settings defaultSettings;
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-
-//Architecture variables
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-#include "Arch_ESP32.h"
-#include "Arch_SAMD.h"
-//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
-
-void setup()
-{
- beginSerial(57600); //Default for debug messages before board begins
-
- loadSettings(); //Load settings from EEPROM
-
- beginSerial(settings.serialSpeed);
-
- verifyRadioStateTable(); //Verify that the state table contains all of the states in increasing order
-
- systemPrintln("LRS");
-
- beginBoard(); //Determine what hardware platform we are running on
-
- beginLoRa(); //Start radio
-
- beginButton(); //Start watching the train button
-
- arch.beginWDT(); //Start watchdog timer
-
- systemPrintln("LRS Setup Complete");
-}
-
-void loop()
-{
- petWDT();
-
- updateButton();
-
- updateSerial(); //Store incoming and print outgoing
-
- updateRadioState(); //Ping/ack/send packets as needed
-}
diff --git a/Firmware/LoRaSerial_Firmware/NVM.ino b/Firmware/LoRaSerial_Firmware/NVM.ino
deleted file mode 100644
index 218d48c9..00000000
--- a/Firmware/LoRaSerial_Firmware/NVM.ino
+++ /dev/null
@@ -1,57 +0,0 @@
-void loadSettings()
-{
- arch.eepromBegin();
-
- //Check to see if EEPROM is blank
- uint32_t testRead = 0;
- if (EEPROM.get(0, testRead) == 0xFFFFFFFF)
- {
- //systemPrintln("EEPROM is blank. Default settings applied.");
- recordSystemSettings(); //Record default settings to EEPROM. At power on, settings are in default state
- }
-
- //Check that the current settings struct size matches what is stored in EEPROM
- //Misalignment happens when we add a new feature or setting
- uint16_t tempSize = 0;
- EEPROM.get(0, tempSize); //Load the sizeOfSettings
- if (tempSize != sizeof(settings))
- {
- //systemPrintln("Settings wrong size. Default settings applied.");
- recordSystemSettings(); //Record default settings to EEPROM. At power on, settings are in default state
- }
-
- //Check that the strIdentifier is correct
- uint16_t tempIdentifier = 0;
- EEPROM.get(sizeof(tempSize), tempIdentifier); //Load the identifier from the EEPROM location after sizeOfSettings (int)
- if (tempIdentifier != LRS_IDENTIFIER)
- {
- //systemPrint("Settings are not valid for this variant of LoRaSerial. Default settings applied.");
- recordSystemSettings(); //Record default settings to EEPROM. At power on, settings are in default state
- }
-
- //Read current settings
- EEPROM.get(0, settings);
-
- recordSystemSettings();
-}
-
-//Record the current settings struct to EEPROM
-void recordSystemSettings()
-{
- settings.sizeOfSettings = sizeof(settings);
- EEPROM.put(0, settings);
-
- arch.eepromCommit();
-}
-
-void eepromErase()
-{
- for (uint16_t i = 0 ; i < EEPROM.length() ; i++)
- {
- petWDT();
-
- EEPROM.write(i, 0);
-
- arch.eepromCommit();
- }
-}
diff --git a/Firmware/LoRaSerial_Firmware/Radio.ino b/Firmware/LoRaSerial_Firmware/Radio.ino
deleted file mode 100644
index 33b798a4..00000000
--- a/Firmware/LoRaSerial_Firmware/Radio.ino
+++ /dev/null
@@ -1,1203 +0,0 @@
-//Determine the type of packet received and print data as necessary
-//The LoRa radio handles CRC and FHSS for us so we presume the packet was meant for us
-//We check the packet netID for validity
-//If the packet is a short/ping packet, ack
-//If the packet is marked as resend, check if it's a duplicate
-//Move any data to incomingPacket buffer
-PacketType identifyPacketType()
-{
- uint8_t incomingBuffer[MAX_PACKET_SIZE];
-
- //Receive the data packet
- radio.readData(incomingBuffer, MAX_PACKET_SIZE);
- uint8_t receivedBytes = radio.getPacketLength();
-
- /*
- +-------------------------+------------+--------+---------+
- | | Optional | | |
- | data | SF6 length | NET ID | Control |
- | 0 - n bytes | 8 bits | 8 bits | 8 bits |
- +-------------------------+------------+--------+---------+
- | |
- |<-------------------- receivedBytes -------------------->|
- */
-
- //Display the received data bytes
- if (settings.printRfData || settings.debugReceive)
- {
- petWDT();
- systemPrintln("----------");
- systemPrint("RX: Data ");
- systemPrint(receivedBytes);
- systemPrint(" (0x");
- systemPrint(receivedBytes, HEX);
- systemPrintln(") bytes");
- petWDT();
- if (settings.printRfData && receivedBytes)
- dumpBuffer(incomingBuffer, receivedBytes);
- }
-
- if (settings.dataScrambling == true)
- radioComputeWhitening(incomingBuffer, receivedBytes);
-
- if (settings.encryptData == true)
- decryptBuffer(incomingBuffer, receivedBytes);
-
- //All packets must include the 2-byte control header
- if (receivedBytes < 2)
- {
- //Display the packet contents
- if (settings.printPktData || settings.debugReceive)
- {
- petWDT();
- systemPrint("RX: Bad packet");
- systemPrint(receivedBytes);
- systemPrint(" (0x");
- systemPrint(receivedBytes, HEX);
- systemPrintln(") bytes");
- petWDT();
- if (settings.printRfData && receivedBytes)
- dumpBuffer(incomingBuffer, receivedBytes);
- }
- return (PACKET_BAD);
- }
-
- /*
- +-------------------------+------------+--------+---------+
- | | Optional | | |
- | data | SF6 length | NET ID | Control |
- | n bytes | 8 bits | 8 bits | 8 bits |
- +-------------------------+------------+--------+---------+
- | |
- |<---------- receivedBytes ----------->|
- */
-
- //Pull out control header
- uint8_t receivedNetID = incomingBuffer[receivedBytes - 2];
- *(uint8_t *)&receiveTrailer = incomingBuffer[receivedBytes - 1];
- receivedBytes -= 2; //Remove control bytes
-
- //Display the control header
- if (settings.debugReceive)
- {
- petWDT();
- systemPrint("RX: NetID ");
- systemPrint(receivedNetID);
- systemPrint(" (0x");
- systemPrint(receivedNetID, HEX);
- systemPrintln(")");
-
- petWDT();
- systemPrint("RX: Control");
- systemPrint(" 0x");
- systemPrintln(*(uint8_t *)&receiveTrailer, HEX);
- if (*(uint8_t *)&receiveTrailer)
- {
- if (receiveTrailer.resend) systemPrintln(" 0x01: resend");
- if (receiveTrailer.ack) systemPrintln(" 0x02: ack");
- if (receiveTrailer.remoteCommand) systemPrintln(" 0x04: remoteCommand");
- if (receiveTrailer.remoteCommandResponse) systemPrintln(" 0x08: remoteCommandResponse");
- if (receiveTrailer.train) systemPrintln(" 0x10: train");
- }
- petWDT();
- }
-
- /*
- +-------------------------+------------+
- | | Optional |
- | data | SF6 length |
- | n bytes | 8 bits |
- +-------------------------+------------+
- | |
- |<---------- receivedBytes ----------->|
- */
-
- //SF6 requires an implicit header which means there is no dataLength in the header
- //Instead, we manually store it after the data and before NetID
- if (settings.radioSpreadFactor == 6)
- {
- //We've either received a control packet (2 bytes) or a data packet
- if (receivedBytes)
- {
- receivedBytes -= 1; //Remove the manual packetSize byte from consideration
- receivedBytes = incomingBuffer[receivedBytes]; //Obtain actual packet data length
- }
- }
-
- /*
- +-------------------------+
- | data |
- | n bytes |
- +-------------------------+
- | |
- |<---- receivedBytes ---->|
- */
-
- //Display the packet contents
- if (settings.printPktData || settings.debugReceive)
- {
- petWDT();
- systemPrint("RX: Packet data ");
- systemPrint(receivedBytes);
- systemPrint(" (0x");
- systemPrint(receivedBytes, HEX);
- systemPrintln(") bytes");
- petWDT();
- if (settings.printPktData && receivedBytes)
- dumpBuffer(incomingBuffer, receivedBytes);
- }
-
- if ((receivedNetID != settings.netID)
- && ((settings.pointToPoint == true) || (settings.verifyRxNetID == true)))
- {
- if (settings.debugReceive)
- {
- petWDT();
- systemPrint("RX: netID ");
- systemPrint(receivedNetID);
- systemPrint(" expecting ");
- systemPrintln(settings.netID);
- }
- return (PACKET_NETID_MISMATCH);
- }
-
- //----------
- //Handle ACKs and duplicate packets
- //----------
-
- if ((receiveTrailer.ack == 1)
- && (receiveTrailer.remoteCommand == 0)
- && (receiveTrailer.remoteCommandResponse == 0))
- {
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Ack packet");
- }
- return (PACKET_ACK);
- }
-
- if (receiveTrailer.resend == 1)
- {
- //We've received a packet that is marked as a retransmit
- //Determine if this is a duplicate of a previous packet
- if (receivedBytes == lastPacketSize)
- {
- //Check packet contents
- if (memcmp(lastPacket, incomingBuffer, lastPacketSize) == 0)
- {
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Duplicate received. Acking again.");
- }
- return (PACKET_DUPLICATE); //It's a duplicate. Ack then ignore
- }
- }
- else
- {
- //We've received a resend but it's different from the lastPacket
- //Go ahead and print it
- }
- }
-
- //----------
- //Handle control packets
- //----------
-
- //We have empty data packet, this is a control packet used for pinging/scanning
- if (receivedBytes == 0)
- {
- //If this packet is marked as training data, someone is sending training ping
- if (receiveTrailer.train == 1)
- {
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Training Control Packet");
- }
- return (PACKET_TRAINING_PING);
- }
-
- //If this packet is marked as a remote command, it's either an ack or a zero length packet (not known)
- if (receiveTrailer.remoteCommand == 1)
- {
- if (receiveTrailer.ack == 1)
- {
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Command Ack");
- }
- return (PACKET_COMMAND_ACK);
- }
-
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Unknown Command");
- }
- return (PACKET_BAD);
- }
-
- //If this packet is marked as a remote command response, it's either an ack or a zero length packet (not known)
- if (receiveTrailer.remoteCommandResponse == 1)
- {
- if (receiveTrailer.ack == 1)
- {
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Command Response Ack");
- }
- return (PACKET_COMMAND_RESPONSE_ACK);
- }
-
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Unknown Response Command");
- }
- return (PACKET_BAD);
- }
-
- //Not training, not command packet, just a ping
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Control Packet");
- }
- return (PACKET_PING);
- }
-
- //----------
- //Handle data packets
- //----------
-
- //Update lastPacket details with current packet
- memcpy(lastPacket, incomingBuffer, receivedBytes);
- lastPacketSize = receivedBytes;
-
- //If this packet is marked as training data,
- //payload contains new AES key and netID which will be processed externally
- if (receiveTrailer.train == 1)
- {
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Training Data");
- }
- return (PACKET_TRAINING_DATA);
- }
-
- if (receiveTrailer.remoteCommand == 1)
- {
- //New data from remote
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Command Data");
- }
- return (PACKET_COMMAND_DATA);
- }
-
- if (receiveTrailer.remoteCommandResponse == 1)
- {
- //New response data from remote
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Command Response Data");
- }
- return (PACKET_COMMAND_RESPONSE_DATA);
- }
-
- //Return the data to the user
- if (settings.debugReceive)
- {
- petWDT();
- systemPrintln("RX: Return user data");
- }
- return (PACKET_DATA);
-}
-
-//Apply settings to radio
-//Called after begin() and once user exits from command interface
-void configureRadio()
-{
- bool success = true;
-
- //Determine if we are using AirSpeed or custom settings
- if (settings.airSpeed != 0)
- {
- switch (settings.airSpeed)
- {
- case (0):
- //Custom settings - use settings without modification
- break;
- case (40):
- settings.radioSpreadFactor = 11;
- settings.radioBandwidth = 62.5;
- settings.radioCodingRate = 8;
- break;
- case (150):
- settings.radioSpreadFactor = 10;
- settings.radioBandwidth = 62.5;
- settings.radioCodingRate = 8;
- break;
- case (400):
- settings.radioSpreadFactor = 10;
- settings.radioBandwidth = 125;
- settings.radioCodingRate = 8;
- break;
- case (1200):
- settings.radioSpreadFactor = 9;
- settings.radioBandwidth = 125;
- settings.radioCodingRate = 8;
- break;
- case (2400):
- settings.radioSpreadFactor = 10;
- settings.radioBandwidth = 500;
- settings.radioCodingRate = 8;
- break;
- case (4800):
- settings.radioSpreadFactor = 9;
- settings.radioBandwidth = 500;
- settings.radioCodingRate = 8;
- break;
- case (9600):
- settings.radioSpreadFactor = 8;
- settings.radioBandwidth = 500;
- settings.radioCodingRate = 7;
- break;
- case (19200):
- settings.radioSpreadFactor = 7;
- settings.radioBandwidth = 500;
- settings.radioCodingRate = 7;
- break;
- case (28800):
- settings.radioSpreadFactor = 6;
- settings.radioBandwidth = 500;
- settings.radioCodingRate = 6;
- break;
- case (38400):
- settings.radioSpreadFactor = 6;
- settings.radioBandwidth = 500;
- settings.radioCodingRate = 5;
- break;
- default:
- if ((settings.debug == true) || (settings.debugRadio == true))
- {
- systemPrint("Unknown airSpeed: ");
- systemPrintln(settings.airSpeed);
- }
- break;
- }
- }
-
- if (radio.setFrequency(channels[0]) == RADIOLIB_ERR_INVALID_FREQUENCY)
- success = false;
-
- //The SX1276 and RadioLib accepts a value of 2 to 17, with 20 enabling the power amplifier
- //Measuring actual power output the radio will output 14dBm (25mW) to 27.9dBm (617mW) in constant transmission
- //So we use a lookup to convert between the user's chosen power and the radio setting
- int radioPowerSetting = covertdBmToSetting(settings.radioBroadcastPower_dbm);
- if (radio.setOutputPower(radioPowerSetting) == RADIOLIB_ERR_INVALID_OUTPUT_POWER)
- success = false;
-
- if (radio.setBandwidth(settings.radioBandwidth) == RADIOLIB_ERR_INVALID_BANDWIDTH)
- success = false;
-
- if (radio.setSpreadingFactor(settings.radioSpreadFactor) == RADIOLIB_ERR_INVALID_SPREADING_FACTOR)
- success = false;
-
- if (radio.setCodingRate(settings.radioCodingRate) == RADIOLIB_ERR_INVALID_CODING_RATE)
- success = false;
-
- if (radio.setSyncWord(settings.radioSyncWord) != RADIOLIB_ERR_NONE)
- success = false;
-
- if (radio.setPreambleLength(settings.radioPreambleLength) == RADIOLIB_ERR_INVALID_PREAMBLE_LENGTH)
- success = false;
-
- //SF6 requires an implicit header. We will transmit 255 bytes for most packets and 2 bytes for ACK packets.
- if (settings.radioSpreadFactor == 6)
- {
- if (radio.implicitHeader(255) != RADIOLIB_ERR_NONE)
- success = false;
- }
- else
- {
- if (radio.explicitHeader() != RADIOLIB_ERR_NONE)
- success = false;
- }
-
- radio.setDio0Action(dio0ISR); //Called when transmission is finished
- radio.setDio1Action(dio1ISR); //Called after a transmission has started, so we can move to next freq
-
- if (pin_rxen != 255)
- radio.setRfSwitchPins(pin_rxen, pin_txen);
-
- // HoppingPeriod = Tsym * FreqHoppingPeriod
- // Given defaults of spreadfactor = 9, bandwidth = 125, it follows Tsym = 4.10ms
- // HoppingPeriod = 4.10 * x = Yms. Can be as high as 400ms to be within regulatory limits
- uint16_t hoppingPeriod = settings.maxDwellTime / calcSymbolTime(); //Limit FHSS dwell time to 400ms max. / automatically floors number
- if (hoppingPeriod > 255) hoppingPeriod = 255; //Limit to 8 bits.
- if (settings.frequencyHop == false) hoppingPeriod = 0; //Disable
- if (radio.setFHSSHoppingPeriod(hoppingPeriod) != RADIOLIB_ERR_NONE)
- success = false;
-
- controlPacketAirTime = calcAirTime(2); //Used for response timeout during RADIO_LINKED_ACK_WAIT
- uint16_t responseDelay = controlPacketAirTime / settings.responseDelayDivisor; //Give the receiver a bit of wiggle time to respond
- controlPacketAirTime += responseDelay;
-
- if ((settings.debug == true) || (settings.debugRadio == true))
- {
- systemPrint("Freq: ");
- systemPrintln(channels[0], 3);
- systemPrint("radioBandwidth: ");
- systemPrintln(settings.radioBandwidth);
- systemPrint("radioSpreadFactor: ");
- systemPrintln(settings.radioSpreadFactor);
- systemPrint("radioCodingRate: ");
- systemPrintln(settings.radioCodingRate);
- systemPrint("radioSyncWord: ");
- systemPrintln(settings.radioSyncWord);
- systemPrint("radioPreambleLength: ");
- systemPrintln(settings.radioPreambleLength);
- systemPrint("calcSymbolTime: ");
- systemPrintln(calcSymbolTime());
- systemPrint("HoppingPeriod: ");
- systemPrintln(hoppingPeriod);
- systemPrint("controlPacketAirTime: ");
- systemPrintln(controlPacketAirTime);
- }
-
- if (success == false)
- {
- reportERROR();
- systemPrintln("Radio init failed. Check settings.");
- }
- LRS_DEBUG_PRINTLN("Radio configured");
-}
-
-//Set radio frequency
-void setRadioFrequency(bool rxAdjust)
-{
- float frequency;
-
- frequency = channels[radio.getFHSSChannel()];
- if (rxAdjust)
- frequency -= frequencyCorrection;
- if (settings.printFrequency)
- {
- systemPrint(frequency);
- systemPrintln(" MHz");
- }
- radio.setFrequency(frequency);
-}
-
-void returnToReceiving()
-{
- setRadioFrequency(settings.autoTuneFrequency);
-
- timeToHop = false;
-
- int state;
- if (settings.radioSpreadFactor > 6)
- {
- state = radio.startReceive();
- }
- else
- {
- if (expectingAck && settings.pointToPoint == true)
- {
- radio.implicitHeader(2);
- state = radio.startReceive(2); //Expect a control packet
- triggerEvent(TRIGGER_RTR_2BYTE);
- expectingAck = false; //Do not return to this receiving configuration if something goes wrong
- }
- else
- {
- radio.implicitHeader(255);
- state = radio.startReceive(255); //Expect a full data packet
- triggerEvent(TRIGGER_RTR_255BYTE);
- }
- }
-
- if (state != RADIOLIB_ERR_NONE) {
- LRS_DEBUG_PRINT("Receive failed: ");
- LRS_DEBUG_PRINTLN(state);
- }
-}
-
-//Create short packet of 2 control bytes - query remote radio for proof of life (ack)
-void sendPingPacket()
-{
- /*
- +--------+---------+
- | NET ID | Trailer |
- | 8 bits | 8 bits |
- +--------+---------+
- | |
- |<-- packetSize -->|
- */
-
- LRS_DEBUG_PRINT("TX: Ping ");
- responseTrailer.ack = 0; //This is not an ACK to a previous transmission
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 0; //This is not a training packet
- responseTrailer.remoteCommand = 0; //This is not a remote command packet
- responseTrailer.remoteCommandResponse = 0; //This is not a response to a previous remote command
-
- packetSize = 2;
- packetSent = 0; //Reset the number of times we've sent this packet
-
- //SF6 requires an implicit header which means there is no dataLength in the header
- //Because we cannot predict when a ping packet will be received, the receiver will always
- //expecting 255 bytes. Pings must be increased to 255 bytes. ACKs are still 2 bytes.
- if (settings.radioSpreadFactor == 6)
- {
- //Manually store actual data length 3 bytes from the end (before NetID)
- //Manual packet size is whatever has been processed + 1 for the manual packetSize byte
- outgoingPacket[255 - 3] = packetSize + 1;
- packetSize = 255; //We're now going to transmit 255 bytes
- }
-
- expectingAck = true; //We expect destination to ack
- sendPacket();
-}
-
-//Create packet of current data + control bytes - expect ACK from recipient
-void sendDataPacket()
-{
- /*
- +--- ... ---+--------+---------+
- | Data | NET ID | Trailer |
- | n bytes | 8 bits | 8 bits |
- +-------------+--------+---------+
- | |
- |<--------- packetSize --------->|
- */
-
- LRS_DEBUG_PRINT("TX: Data ");
- responseTrailer.ack = 0; //This is not an ACK to a previous transmission
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 0; //This is not a training packet
- responseTrailer.remoteCommand = 0; //This is not a remote command packet
- responseTrailer.remoteCommandResponse = 0; //This is not a response to a previous remote command
-
- packetSize += 2; //Make room for control bytes
- packetSent = 0; //Reset the number of times we've sent this packet
-
- //SF6 requires an implicit header which means there is no dataLength in the header
- if (settings.radioSpreadFactor == 6)
- {
- //Manually store actual data length 3 bytes from the end (before NetID)
- //Manual packet size is whatever has been processed + 1 for the manual packetSize byte
- outgoingPacket[255 - 3] = packetSize + 1;
- packetSize = 255; //We're now going to transmit 255 bytes
- }
-
- expectingAck = true; //We expect destination to ack
- sendPacket();
-}
-
-//Create packet of current data + control bytes - expect ACK from recipient
-void sendResendPacket()
-{
- /*
- +--- ... ---+--------+---------+
- | Data | NET ID | Trailer |
- | n bytes | 8 bits | 8 bits |
- +-------------+--------+---------+
- | |
- |<--------- packetSize --------->|
- */
-
- LRS_DEBUG_PRINT("TX: Resend ");
- responseTrailer.ack = 0; //This is not an ACK to a previous transmission
- responseTrailer.resend = 1; //This is a resend
- responseTrailer.train = 0; //This is not a training packet
- //responseTrailer.remoteCommand = ; //Don't modify the remoteCommand bit; we may be resending a command packet
- //responseTrailer.remoteCommandResponse = ; //Don't modify the remoteCommand bit; we may be resending a command packet
-
- //packetSize += 2; //Don't adjust the packet size
- //packetSent = 0; //Don't reset
- expectingAck = true; //We expect destination to ack
- sendPacket();
-}
-
-//Create short packet of 2 control bytes - do not expect ack
-void sendAckPacket()
-{
- /*
- +--------+---------+
- | NET ID | Trailer |
- | 8 bits | 8 bits |
- +--------+---------+
- | |
- |<-- packetSize -->|
- */
-
- LRS_DEBUG_PRINT("TX: Ack ");
- responseTrailer.ack = 1; //This is an ACK to a previous reception
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 0; //This is not a training packet
- responseTrailer.remoteCommand = 0; //This is not a remote command packet
- responseTrailer.remoteCommandResponse = 0; //This is not a response to a previous remote command
-
- packetSize = 2;
- packetSent = 0; //Reset the number of times we've sent this packet
- expectingAck = false; //We do not expect destination to ack
- sendPacket();
-}
-
-//Create short packet of 2 control bytes with train = 1
-void sendTrainingPingPacket()
-{
- /*
- +--------+---------+
- | NET ID | Trailer |
- | 8 bits | 8 bits |
- +--------+---------+
- | |
- |<-- packetSize -->|
- */
-
- LRS_DEBUG_PRINT("TX: Training Ping ");
- responseTrailer.ack = 0; //This is not an ACK to a previous transmission
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 1; //This is a training packet
- responseTrailer.remoteCommand = 0; //This is not a remote command packet
- responseTrailer.remoteCommandResponse = 0; //This is not a response to a previous remote command
-
- packetSize = 2;
- packetSent = 0; //Reset the number of times we've sent this packet
-
- //SF6 is not used during training
-
- expectingAck = true; //We expect destination to ack
- sendPacket();
-}
-
-//Create packet of AES + netID with training = 1
-void sendTrainingDataPacket()
-{
- /*
- +----------------+------------+--------+---------+
- | Encryption Key | New NET ID | NET ID | Trailer |
- | 16 bytes | 8 bits | 8 bits | 8 bits |
- +----------------+------------+--------+---------+
- | |
- |<----------------- packetSize ----------------->|
- */
-
- LRS_DEBUG_PRINT("TX: Training Data ");
- responseTrailer.ack = 0; //This is not an ACK to a previous transmission
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 1; //This is training packet
- responseTrailer.remoteCommand = 0; //This is not a remote command packet
- responseTrailer.remoteCommandResponse = 0; //This is not a response to a previous remote command
-
- packetSize = sizeof(trainEncryptionKey) + sizeof(trainNetID);
-
- for (uint8_t x = 0 ; x < sizeof(trainEncryptionKey) ; x++)
- outgoingPacket[x] = trainEncryptionKey[x];
- outgoingPacket[packetSize - 1] = trainNetID;
-
- packetSize += 2;
- packetSent = 0; //Reset the number of times we've sent this packet
-
- //During training we do not use spread factor 6
-
- expectingAck = false; //We do not expect destination to ack
- sendPacket();
-}
-
-//Create short packet of 2 control bytes - do not expect ack
-void sendCommandAckPacket()
-{
- /*
- +--------+---------+
- | NET ID | Trailer |
- | 8 bits | 8 bits |
- +--------+---------+
- | |
- |<-- packetSize -->|
- */
-
- LRS_DEBUG_PRINT("TX: Command Ack ");
- responseTrailer.ack = 1; //This is an ACK to a previous reception
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 0; //This is not a training packet
- responseTrailer.remoteCommand = 1; //This is a remote command packet
- responseTrailer.remoteCommandResponse = 0; //This is not a response to a previous command
-
- packetSize = 2;
- packetSent = 0; //Reset the number of times we've sent this packet
- expectingAck = false; //We do not expect destination to ack
- sendPacket();
-}
-
-//Create packet of serial command with remote command = 1, ack = 0
-void sendCommandDataPacket()
-{
- /*
- +---------+--------+---------+
- | Command | NET ID | Trailer |
- | n bytes | 8 bits | 8 bits |
- +---------+--------+---------+
- | |
- |<------- packetSize ------->|
- */
-
- LRS_DEBUG_PRINT("TX: Command Data ");
- responseTrailer.ack = 0; //This is not an ACK to a previous transmission.
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 0; //This is not training packet
- responseTrailer.remoteCommand = 1; //This is a remote control packet
- responseTrailer.remoteCommandResponse = 0; //This is not a response to a previous command
-
- packetSize += 2; //Make room for control bytes
- packetSent = 0; //Reset the number of times we've sent this packet
-
- //SF6 requires an implicit header which means there is no dataLength in the header
- if (settings.radioSpreadFactor == 6)
- {
- //Manually store actual data length 3 bytes from the end (before NetID)
- //Manual packet size is whatever has been processed + 1 for the manual packetSize byte
- outgoingPacket[255 - 3] = packetSize + 1;
- packetSize = 255; //We're now going to transmit 255 bytes
- }
-
- expectingAck = true; //We expect destination to ack
- sendPacket();
-}
-
-//Create short packet of 2 control bytes - do not expect ack
-void sendCommandResponseAckPacket()
-{
- /*
- +--------+---------+
- | NET ID | Trailer |
- | 8 bits | 8 bits |
- +--------+---------+
- | |
- |<-- packetSize -->|
- */
-
- LRS_DEBUG_PRINT("TX: Command Response Ack ");
- responseTrailer.ack = 1; //This is an ACK to a previous reception
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 0; //This is not a training packet
- responseTrailer.remoteCommand = 0; //This is not a remote command packet
- responseTrailer.remoteCommandResponse = 1; //This is a response to a previous command
-
- packetSize = 2;
- packetSent = 0; //Reset the number of times we've sent this packet
- expectingAck = false; //We do not expect destination to ack
- sendPacket();
-}
-
-//Create packet of serial command with remote command = 1, ack = 0
-void sendCommandResponseDataPacket()
-{
- /*
- +----------+--------+---------+
- | Response | NET ID | Trailer |
- | n bytes | 8 bits | 8 bits |
- +----------+--------+---------+
- | |
- |<-------- packetSize ------->|
- */
-
- LRS_DEBUG_PRINT("TX: Command Response Data ");
- responseTrailer.ack = 0; //This is not an ACK to a previous transmission.
- responseTrailer.resend = 0; //This is not a resend
- responseTrailer.train = 0; //This is not training packet
- responseTrailer.remoteCommand = 0; //This is a remote control packet
- responseTrailer.remoteCommandResponse = 1; //This is a response to a previous command
-
- packetSize += 2; //Make room for control bytes
- packetSent = 0; //Reset the number of times we've sent this packet
-
- //SF6 requires an implicit header which means there is no dataLength in the header
- if (settings.radioSpreadFactor == 6)
- {
- //Manually store actual data length 3 bytes from the end (before NetID)
- //Manual packet size is whatever has been processed + 1 for the manual packetSize byte
- outgoingPacket[255 - 3] = packetSize + 1;
- packetSize = 255; //We're now going to transmit 255 bytes
- }
-
- expectingAck = true; //We expect destination to ack
- sendPacket();
-}
-
-//Push the outgoing packet to the air
-void sendPacket()
-{
- /*
- +--- ... ---+------------+--------+---------+
- | | Optional | | |
- | Data | SF6 Length | NET ID | Trailer |
- | n bytes | 8 bits | 8 bits | 8 bits |
- +-------------+------------+--------+---------+
- | |
- |<--------------- packetSize ---------------->|
- */
-
- //Attach netID and control byte to end of packet
- outgoingPacket[packetSize - 2] = settings.netID;
- outgoingPacket[packetSize - 1] = *(uint8_t *)&responseTrailer;
-
- //Display the packet contents
- if (settings.printPktData || settings.debugTransmit)
- {
- petWDT();
- systemPrint("TX: Control");
- systemPrint(" 0x");
- systemPrintln(*(uint8_t *)&receiveTrailer, HEX);
- if (*(uint8_t *)&receiveTrailer)
- {
- if (receiveTrailer.resend) systemPrintln(" 0x01: resend");
- if (receiveTrailer.ack) systemPrintln(" 0x02: ack");
- if (receiveTrailer.remoteCommand) systemPrintln(" 0x04: remoteCommand");
- if (receiveTrailer.remoteCommandResponse) systemPrintln(" 0x08: remoteCommandResponse");
- if (receiveTrailer.train) systemPrintln(" 0x10: train");
- }
- petWDT();
- systemPrint("TX: Packet data ");
- systemPrint(packetSize);
- systemPrint(" (0x");
- systemPrint(packetSize, HEX);
- systemPrintln(") bytes");
- petWDT();
- if (settings.printPktData)
- dumpBuffer(outgoingPacket, packetSize);
- }
-
- //Apply AES and whitening only to new packets, not resends
- if (responseTrailer.resend == 0)
- {
- if (settings.encryptData == true)
- encryptBuffer(outgoingPacket, packetSize);
-
- if (settings.dataScrambling == true)
- radioComputeWhitening(outgoingPacket, packetSize);
- }
-
- //Display the transmitted packet bytes
- if (settings.printPktData || settings.debugTransmit)
- {
- petWDT();
- systemPrint("TX: Data ");
- systemPrint(packetSize);
- systemPrint(" (0x");
- systemPrint(packetSize, HEX);
- systemPrintln(") bytes");
- petWDT();
- if (settings.printPktData)
- dumpBuffer(outgoingPacket, packetSize);
- }
-
- //If we are trainsmitting at high data rates the receiver is often not ready for new data. Pause for a few ms (measured with logic analyzer).
- if (settings.airSpeed == 28800 || settings.airSpeed == 38400)
- delay(2);
-
- setRadioFrequency(false); //Return home before every transmission
-
- //Display the transmit frequency
- if (settings.debugTransmit)
- {
- systemPrint("TX: Transmitting @ ");
- systemPrint(channels[radio.getFHSSChannel()], 3);
- systemPrintln(" MHz");
- }
-
- int state = radio.startTransmit(outgoingPacket, packetSize);
- if (state == RADIOLIB_ERR_NONE)
- {
- if (timeToHop) hopChannel();
-
- packetAirTime = calcAirTime(packetSize); //Calculate packet air size while we're transmitting in the background
- uint16_t responseDelay = packetAirTime / settings.responseDelayDivisor; //Give the receiver a bit of wiggle time to respond
- packetAirTime += responseDelay;
-
- packetSent++;
-
- if (settings.debugTransmit)
- {
- systemPrint("TX: PacketAirTime ");
- systemPrintln(packetAirTime);
- systemPrint("TX: responseDelay: ");
- systemPrintln(responseDelay);
- }
-
- if (timeToHop) hopChannel();
- }
- else
- {
- if (settings.debugTransmit || settings.printTxErrors)
- systemPrintln("Error: TX");
- }
-
- packetTimestamp = millis(); //Move timestamp even if error
-}
-
-//ISR when DIO0 goes low
-//Called when transmission is complete or when RX is received
-void dio0ISR(void)
-{
- transactionComplete = true;
-}
-
-//ISR when DIO1 goes low
-//Called when FhssChangeChannel interrupt occurs (at regular HoppingPeriods)
-void dio1ISR(void)
-{
- timeToHop = true;
-}
-
-//Given spread factor, bandwidth, coding rate and number of bytes, return total Air Time in ms for packet
-uint16_t calcAirTime(uint8_t bytesToSend)
-{
- float tSym = calcSymbolTime();
- float tPreamble = (settings.radioPreambleLength + 4.25) * tSym;
- float p1 = (8 * bytesToSend - 4 * settings.radioSpreadFactor + 28 + 16 * 1 - 20 * 0) / (4.0 * (settings.radioSpreadFactor - 2 * 0));
- p1 = ceil(p1) * settings.radioCodingRate;
- if (p1 < 0) p1 = 0;
- uint16_t payloadBytes = 8 + p1;
- float tPayload = payloadBytes * tSym;
- float tPacket = tPreamble + tPayload;
-
- return ((uint16_t)ceil(tPacket));
-}
-
-//Given spread factor and bandwidth, return symbol time
-float calcSymbolTime()
-{
- float tSym = pow(2, settings.radioSpreadFactor) / settings.radioBandwidth;
- return (tSym);
-}
-
-//Given spread factor, bandwidth, coding rate and frame size, return most bytes we can push per second
-uint16_t calcMaxThroughput()
-{
- uint8_t mostFramesPerSecond = 1000 / calcAirTime(settings.frameSize);
- uint16_t mostBytesPerSecond = settings.frameSize * mostFramesPerSecond;
-
- return (mostBytesPerSecond);
-}
-
-uint16_t myRandSeed;
-bool myRandBit;
-
-//Generate unique hop table based on radio settings
-void generateHopTable()
-{
- if (channels != NULL) free(channels);
- channels = (float *)malloc(settings.numberOfChannels * sizeof(float));
-
- float channelSpacing = (settings.frequencyMax - settings.frequencyMin) / (float)(settings.numberOfChannels + 2);
-
- //Keep away from edge of available spectrum
- float operatingMinFreq = settings.frequencyMin + (channelSpacing / 2);
-
- //Pre populate channel list
- for (int x = 0 ; x < settings.numberOfChannels ; x++)
- channels[x] = operatingMinFreq + (x * channelSpacing);
-
- //Feed random number generator with our specific platform settings
- //Use settings that must be identical to have a functioning link.
- //For example, we do not use coding rate because two radios can communicate with different coding rate values
- myRandSeed = settings.airSpeed + settings.netID + settings.pointToPoint + settings.encryptData
- + settings.dataScrambling
- + (uint16_t)settings.frequencyMin + (uint16_t)settings.frequencyMax
- + settings.numberOfChannels + settings.frequencyHop + settings.maxDwellTime
- + (uint16_t)settings.radioBandwidth + settings.radioSpreadFactor;
-
- if (settings.encryptData == true)
- {
- for (uint8_t x = 0 ; x < sizeof(settings.encryptionKey) ; x++)
- myRandSeed += settings.encryptionKey[x];
- }
-
- //'Randomly' shuffle list based on our specific seed
- shuffle(channels, settings.numberOfChannels);
-
- //Set new initial values for AES using settings based random seed
- for (uint8_t x = 0 ; x < 12 ; x++)
- AESiv[x] = myRand();
-
- if ((settings.debug == true) || (settings.debugRadio == true))
- {
- systemPrint("channelSpacing: ");
- systemPrintln(channelSpacing, 3);
-
- systemPrintln("Channel table:");
- for (int x = 0 ; x < settings.numberOfChannels ; x++)
- {
- systemPrint(x);
- systemPrint(": ");
- systemPrint(channels[x], 3);
- systemPrintln();
- }
-
- systemPrint("AES IV:");
- for (uint8_t i = 0 ; i < 12 ; i++)
- {
- systemPrint(" 0x");
- systemPrint(AESiv[i], HEX);
- }
- systemPrintln();
- }
-}
-
-//Array shuffle from http://benpfaff.org/writings/clc/shuffle.html
-void shuffle(float *array, uint8_t n)
-{
- for (uint8_t i = 0; i < n - 1; i++)
- {
- uint8_t j = myRand() % n;
- float t = array[j];
- array[j] = array[i];
- array[i] = t;
- }
-}
-
-//Simple lfsr randomizer. Needed because we cannot guarantee how random()
-//will respond on different Arduino platforms. ie Uno acts diffrently from ESP32.
-//We don't need 'truly random', we need repeatable across platforms.
-uint16_t myRand()
-{
- myRandBit = ((myRandSeed >> 0) ^ (myRandSeed >> 2) ^ (myRandSeed >> 3) ^ (myRandSeed >> 5) ) & 1;
- return myRandSeed = (myRandSeed >> 1) | (myRandBit << 15);
-}
-
-//If we have lost too many packets
-//or have not had a successful heart beat within a determined amount of time
-//the link is considered lost
-bool linkLost()
-{
- if (packetsLost > MAX_LOST_PACKET_BEFORE_LINKLOST)
- return (true);
- return (false);
-}
-
-//Move to the next channel
-//This is called when the FHSS interrupt is received
-//at the beginning and during of a transmission or reception
-void hopChannel()
-{
- radio.clearFHSSInt();
- timeToHop = false;
-
- if (settings.autoTuneFrequency == true)
- {
- if (radioState == RADIO_LINKED_RECEIVING_STANDBY || radioState == RADIO_LINKED_ACK_WAIT
- || radioState == RADIO_BROADCASTING_RECEIVING_STANDBY) //Only adjust frequency on RX. Not TX.
- radio.setFrequency(channels[radio.getFHSSChannel()] - frequencyCorrection);
- else
- radio.setFrequency(channels[radio.getFHSSChannel()]);
- }
- else
- radio.setFrequency(channels[radio.getFHSSChannel()]);
-}
-
-//Returns true if the radio indicates we have an ongoing reception
-//Bit 0: Signal Detected indicates that a valid LoRa preamble has been detected
-//Bit 1: Signal Synchronized indicates that the end of Preamble has been detected, the modem is in lock
-//Bit 3: Header Info Valid toggles high when a valid Header (with correct CRC) is detected
-bool receiveInProcess()
-{
- uint8_t radioStatus = radio.getModemStatus();
- if ((radioStatus & 0b1) == 1) return (true); //If bit 0 is set, forget the other bits, there is a receive in progress
- return (false); //No receive in process
-
- //If bit 0 is cleared, there is likely no receive in progress, but we need to confirm it
- //The radio will clear this bit before the radio triggers the receiveComplete ISR so we often have a race condition.
-
- //If we are using FHSS then check channel freq. This is reset to 0 upon receive completion.
- //If radio has jumped back to channel 0 then we can confirm a transaction is complete.
- if (settings.frequencyHop == true)
- {
- if (radio.getFHSSChannel() == 0)
- return (false); //Receive not in process
-
- if (transactionComplete == false)
- return (true); //Receive still in process
- }
- else
- {
- //If we're not using FHSS, use small delay.
- delay(5); //Small wait before checking RX complete ISR again
- if (transactionComplete == false)
- return (true); //Receive still in process
- }
-
- return (false); //No receive in process
-
- //if ((radioStatus & 0b1) == 0) return (false); //If bit 0 is cleared, there is no receive in progress
- //return (true); //If bit 0 is set, forget the other bits, there is a receive in progress
-}
-
-//Convert the user's requested dBm to what the radio should be set to, to hit that power level
-//3 is lowest allowed setting using SX1276+RadioLib
-uint8_t covertdBmToSetting(uint8_t userSetting)
-{
- switch (userSetting)
- {
- case 14: return (2); break;
- case 15: return (3); break;
- case 16: return (4); break;
- case 17: return (5); break;
- case 18: return (6); break;
- case 19: return (7); break;
- case 20: return (7); break;
- case 21: return (8); break;
- case 22: return (9); break;
- case 23: return (10); break;
- case 24: return (11); break;
- case 25: return (12); break;
- case 26: return (13); break;
- case 27: return (20); break;
- case 28: return (20); break;
- case 29: return (20); break;
- case 30: return (20); break;
- default: return (3); break;
- }
-}
-
-#ifdef RADIOLIB_LOW_LEVEL
-uint8_t readSX1276Register(uint8_t reg)
-{
- return radio._mod->SPIreadRegister(reg);
-}
-
-//Print the SX1276 LoRa registers
-void printSX1276Registers ()
-{
- //Define the valid LoRa registers
- const uint8_t valid_regs [16] =
- {
- 0xc2, 0xff, 0xff, 0xff, 0x7f, 0x97, 0xcb, 0x0e,
- 0x07, 0x28, 0x00, 0x08, 0x1e, 0x00, 0x01, 0x00
- };
-
- systemPrint("Registers:");
- for (uint8_t i = 0; i < (sizeof(valid_regs) * 8); i++)
- {
- //Only read and print the valid registers
- if (valid_regs[i >> 3] & (1 << (i & 7)))
- {
- systemPrint(" 0x");
- systemPrint(i, HEX);
- systemPrint(": 0x");
- systemPrintln(readSX1276Register(i), HEX);
- }
- }
-}
-
-#endif //RADIOLIB_LOW_LEVEL
diff --git a/Firmware/LoRaSerial_Firmware/Serial.ino b/Firmware/LoRaSerial_Firmware/Serial.ino
deleted file mode 100644
index e4d5fa65..00000000
--- a/Firmware/LoRaSerial_Firmware/Serial.ino
+++ /dev/null
@@ -1,286 +0,0 @@
-//Return number of bytes sitting in the serial receive buffer
-uint16_t availableRXBytes()
-{
- if (rxHead >= rxTail) return (rxHead - rxTail);
- return (sizeof(serialReceiveBuffer) - rxTail + rxHead);
-}
-
-//Return number of bytes sitting in the serial transmit buffer
-uint16_t availableTXBytes()
-{
- if (inCommandMode == true) return (0); //If we are in command mode, block printing of data from the TXBuffer
-
- if (txHead >= txTail) return (txHead - txTail);
- return (sizeof(serialTransmitBuffer) - txTail + txHead);
-}
-
-//Return number of bytes sitting in the serial receive buffer
-uint16_t availableRXCommandBytes()
-{
- if (commandRXHead >= commandRXTail) return (commandRXHead - commandRXTail);
- return (sizeof(commandRXBuffer) - commandRXTail + commandRXHead);
-}
-
-//Return number of bytes sitting in the serial transmit buffer
-uint16_t availableTXCommandBytes()
-{
- if (commandTXHead >= commandTXTail) return (commandTXHead - commandTXTail);
- return (sizeof(commandTXBuffer) - commandTXTail + commandTXHead);
-}
-
-//See if there's any serial from the remote radio that needs printing
-//Record any characters to the receive buffer
-//Scan for escape characters
-void updateSerial()
-{
- //Forget printing if there are ISRs to attend to
- if (transactionComplete == false && timeToHop == false)
- {
- if (availableTXBytes())
- {
- if (isCTS())
- {
- txLED(true); //Turn on LED during serial transmissions
-
- //Print data to both ports
- for (int x = 0 ; x < availableTXBytes() ; x++)
- {
- //Take a break if there are ISRs to attend to
- petWDT();
- if (transactionComplete == true) break;
- if (timeToHop == true) hopChannel();
- if (isCTS() == false) break;
-
- // int bytesToSend = availableTXBytes();
- //
- // if (txTail + bytesToSend > sizeof(serialTransmitBuffer))
- // bytesToSend = sizeof(serialTransmitBuffer) - txTail;
- //
- // //TODO this may introduce delays when we should be checking ISRs
- // Serial.write(&serialTransmitBuffer[txTail], bytesToSend);
- // Serial1.write(&serialTransmitBuffer[txTail], bytesToSend);
- // txTail += bytesToSend;
- // txTail %= sizeof(serialTransmitBuffer);
-
- systemWrite(serialTransmitBuffer[txTail]);
- systemFlush(); //Prevent serial hardware from blocking more than this one write
-
- txTail++;
- txTail %= sizeof(serialTransmitBuffer);
- }
-
- txLED(false); //Turn off LED
- }
- }
- }
-
- //Look for local incoming serial
- while (arch.serialAvailable() && transactionComplete == false)
- {
- rxLED(true); //Turn on LED during serial reception
-
- //Take a break if there are ISRs to attend to
- petWDT();
- if (timeToHop == true) hopChannel();
-
- //Handle RTS
- if (availableRXBytes() == sizeof(serialReceiveBuffer) - 1)
- {
- //Buffer full!
- if (pin_rts != 255 && settings.flowControl == true)
- digitalWrite(pin_rts, LOW); //Don't give me more
- }
- else
- {
- if (pin_rts != 255 && settings.flowControl == true)
- digitalWrite(pin_rts, HIGH); //Ok to send more
- }
-
- byte incoming = systemRead();
-
- //Process serial into either rx buffer or command buffer
- if (inCommandMode == true)
- {
- if (incoming == '\r' && commandLength > 0)
- {
- printerEndpoint = PRINT_TO_SERIAL;
- checkCommand(); //Process command buffer
- }
- else if (incoming == '\n')
- ; //Do nothing
- else
- {
- if (incoming == 8)
- {
- if (commandLength > 0)
- {
- //Remove this character from the command buffer
- commandLength--;
-
- //Erase the previous character
- systemWrite(incoming);
- systemWrite(' ');
- systemWrite(incoming);
- }
- else
- systemWrite(7);
- }
- else
- {
- systemWrite(incoming); //Always echo during command mode
-
- //Move this character into the command buffer
- commandBuffer[commandLength++] = toupper(incoming);
- commandLength %= sizeof(commandBuffer);
- }
- }
- }
- else
- {
- //Check general serial stream for command characters
- if (incoming == settings.escapeCharacter)
- {
- //Ignore escape characters received within 2 seconds of serial traffic
- //Allow escape characters received within first 2 seconds of power on
- if (millis() - lastByteReceived_ms > minEscapeTime_ms || millis() < minEscapeTime_ms)
- {
- escapeCharsReceived++;
- if (escapeCharsReceived == settings.maxEscapeCharacters)
- {
- if (settings.echo == true)
- systemWrite(incoming);
-
- systemPrintln("\r\nOK");
-
- inCommandMode = true; //Allow AT parsing. Prevent received RF data from being printed.
-
- escapeCharsReceived = 0;
- lastByteReceived_ms = millis();
- return; //Avoid recording this incoming command char
- }
- }
- else //This is just a character in the stream, ignore
- {
- lastByteReceived_ms = millis();
- escapeCharsReceived = 0; //Update timeout check for escape char and partial frame
- }
- }
- else
- {
- lastByteReceived_ms = millis();
- escapeCharsReceived = 0; //Update timeout check for escape char and partial frame
- }
-
- if (settings.echo == true)
- systemWrite(incoming);
-
- //We must always read in characters to avoid causing the host computer blocking USB from sending more
- //If the buffer is full, we will overwrite oldest data first
- serialReceiveBuffer[rxHead++] = incoming; //Push char to holding buffer
- rxHead %= sizeof(serialReceiveBuffer);
- } //End process rx buffer
-
- rxLED(false); //Turn off LED
-
- } //End Serial.available()
-
- //Process any remote commands sitting in buffer
- if (availableRXCommandBytes() && inCommandMode == false)
- {
- commandLength = availableRXCommandBytes();
-
- for (int x = 0 ; x < commandLength ; x++)
- {
- commandBuffer[x] = commandRXBuffer[commandRXTail++];
- commandRXTail %= sizeof(commandRXBuffer);
- }
-
- if (commandBuffer[0] == 'R') //Error check
- {
- commandBuffer[0] = 'A'; //Convert this RT command to an AT command for local consumption
- printerEndpoint = PRINT_TO_RF; //Send prints to RF link
- checkCommand(); //Parse the command buffer
-
- //We now have the commandTXBuffer loaded. But we need to send an remoteCommandResponse. Use the printerEndpoint within the State machine.
- }
- else
- {
- LRS_DEBUG_PRINT("Corrupt remote command received");
- }
- }
-}
-
-//Returns true if CTS is asserted (high = host says it's ok to send data)
-bool isCTS()
-{
- if (pin_cts == 255) return (true); //CTS not implmented on this board
- if (settings.flowControl == false) return (true); //CTS turned off
- if (digitalRead(pin_cts) == HIGH) return (true);
- return (false);
-}
-
-//If we have data to send, get the packet ready
-//Return true if new data is ready to be sent
-bool processWaitingSerial()
-{
- //Push any available data out
- if (availableRXBytes() >= settings.frameSize)
- {
- LRS_DEBUG_PRINTLN("Sending max frame");
- readyOutgoingPacket();
- return (true);
- }
-
- //Check if we should send out a partial frame
- else if (availableRXBytes() > 0 && (millis() - lastByteReceived_ms) >= settings.serialTimeoutBeforeSendingFrame_ms)
- {
- LRS_DEBUG_PRINTLN("Sending partial frame");
- readyOutgoingPacket();
- return (true);
- }
- return (false);
-}
-
-//Send a portion of the serialReceiveBuffer to outgoingPacket
-void readyOutgoingPacket()
-{
- uint16_t bytesToSend = availableRXBytes();
- if (bytesToSend > settings.frameSize) bytesToSend = settings.frameSize;
-
- //SF6 requires an implicit header which means there is no dataLength in the header
- if (settings.radioSpreadFactor == 6)
- {
- if (bytesToSend > 255 - 3) bytesToSend = 255 - 3; //We are going to transmit 255 bytes no matter what
- }
-
- packetSize = bytesToSend;
-
- //Move this portion of the circular buffer into the outgoingPacket
- for (uint8_t x = 0 ; x < packetSize ; x++)
- {
- outgoingPacket[x] = serialReceiveBuffer[rxTail++];
- rxTail %= sizeof(serialReceiveBuffer);
- }
-}
-
-//Send a portion of the commandTXBuffer to outgoingPacket
-void readyOutgoingCommandPacket()
-{
- uint16_t bytesToSend = availableTXCommandBytes();
- if (bytesToSend > settings.frameSize) bytesToSend = settings.frameSize;
-
- //SF6 requires an implicit header which means there is no dataLength in the header
- if (settings.radioSpreadFactor == 6)
- {
- if (bytesToSend > 255 - 3) bytesToSend = 255 - 3; //We are going to transmit 255 bytes no matter what
- }
-
- packetSize = bytesToSend;
-
- //Move this portion of the circular buffer into the outgoingPacket
- for (uint8_t x = 0 ; x < packetSize ; x++)
- {
- outgoingPacket[x] = commandTXBuffer[commandTXTail++];
- commandTXTail %= sizeof(commandTXBuffer);
- }
-}
diff --git a/Firmware/LoRaSerial_Firmware/States.ino b/Firmware/LoRaSerial_Firmware/States.ino
deleted file mode 100644
index 8afbab49..00000000
--- a/Firmware/LoRaSerial_Firmware/States.ino
+++ /dev/null
@@ -1,921 +0,0 @@
-void updateRadioState()
-{
- uint8_t radioSeed;
-
- switch (radioState)
- {
- default:
- {
- systemPrintln("Unknown state");
- }
- break;
-
- //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
- // Reset
- //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
-
- case RADIO_RESET:
- radioSeed = radio.randomByte(); //Puts radio into standy-by state
- randomSeed(radioSeed);
- if ((settings.debug == true) || (settings.debugRadio == true))
- {
- systemPrint("RadioSeed: ");
- systemPrintln(radioSeed);
- }
-
- generateHopTable(); //Generate frequency table based on randomByte
-
- configureRadio(); //Generate freq table, setup radio, go to receiving, change state to standby
-
- //Start receiving
- returnToReceiving();
-
- //Start the link between the radios
- if (settings.pointToPoint == true)
- changeState(RADIO_NO_LINK_RECEIVING_STANDBY);
- else
- changeState(RADIO_BROADCASTING_RECEIVING_STANDBY);
- break;
-
- //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
-
- case RADIO_NO_LINK_RECEIVING_STANDBY:
- {
- if (transactionComplete == true) //If dio0ISR has fired, a packet has arrived
- {
- transactionComplete = false; //Reset ISR flag
- changeState(RADIO_NO_LINK_RECEIVED_PACKET);
- }
-
- else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
- hopChannel();
-
- //Check to see if we need to send a ping
- else if ( (millis() - packetTimestamp) > (unsigned int)(settings.heartbeatTimeout + random(0, 1000)) //Avoid pinging each other at same time
- || sentFirstPing == false) //Immediately send pings at POR
- {
- if (receiveInProcess() == false)
- {
- triggerEvent(TRIGGER_NOLINK_SEND_PING);
- sentFirstPing = true;
- sendPingPacket();
- transactionComplete = false; //Reset ISR flag
- changeState(RADIO_NO_LINK_TRANSMITTING);
- }
- else
- LRS_DEBUG_PRINTLN("NO_LINK_RECEIVING_STANDBY: RX In Progress");
- }
- }
- break;
-
- case RADIO_NO_LINK_TRANSMITTING:
- {
- if (transactionComplete == true) //If dio0ISR has fired, we are done transmitting
- {
- transactionComplete = false; //Reset ISR flag
-
- if (expectingAck == false)
- {
- triggerEvent(TRIGGER_NOLINK_SEND_ACK_PACKET);
- //We're done transmitting our ack packet
- //Yay! Return to normal communication
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level. We will soon be linked.
- returnToReceiving();
- changeState(RADIO_LINKED_RECEIVING_STANDBY);
- }
- else
- {
- returnToReceiving();
- changeState(RADIO_NO_LINK_ACK_WAIT);
- }
- }
- else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
- hopChannel();
- }
- break;
-
- case RADIO_NO_LINK_ACK_WAIT:
- {
- if (transactionComplete == true) //If dio0ISR has fired, a packet has arrived
- {
- transactionComplete = false; //Reset ISR flag
- changeState(RADIO_NO_LINK_RECEIVED_PACKET);
- }
-
- else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
- hopChannel();
-
- else if ((millis() - packetTimestamp) > (packetAirTime + controlPacketAirTime)) //Wait for xmit of packet and ACK response
- {
- //Give up. No ACK recevied.
- randomSeed(radio.randomByte()); //Reseed the random delay between heartbeats
- triggerEvent(TRIGGER_NOLINK_NO_ACK_GIVEUP);
- returnToReceiving();
- changeState(RADIO_NO_LINK_RECEIVING_STANDBY);
- }
- }
- break;
-
- case RADIO_NO_LINK_RECEIVED_PACKET:
- {
- PacketType packetType = identifyPacketType(); //Look at the packet we just received
-
- if (packetType == PACKET_BAD || packetType == PACKET_NETID_MISMATCH)
- {
- returnToReceiving(); //Ignore
- changeState(RADIO_NO_LINK_RECEIVING_STANDBY);
- }
- else if (packetType == PACKET_ACK)
- {
- //Yay! Return to normal communication
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level
- returnToReceiving();
- changeState(RADIO_LINKED_RECEIVING_STANDBY);
- }
- else if (packetType == PACKET_DUPLICATE)
- {
- sendAckPacket(); //It's a duplicate. Ack then ignore.
- changeState(RADIO_NO_LINK_TRANSMITTING);
- }
- else if (packetType == PACKET_PING)
- {
- triggerEvent(TRIGGER_NOLINK_IDENT_PACKET);
- updateRSSI(); //Adjust LEDs to RSSI level. We will soon be linked.
- sendAckPacket(); //Someone is pinging us
- changeState(RADIO_NO_LINK_TRANSMITTING);
- }
- else if (packetType == PACKET_DATA)
- {
- ; //No data packets allowed when not linked
- }
- }
- break;
-
- //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
-
- case RADIO_LINKED_RECEIVING_STANDBY:
- {
- if (linkLost())
- {
- setRSSI(0);
-
- //Return to home channel and begin linking process
- returnToReceiving();
- changeState(RADIO_NO_LINK_RECEIVING_STANDBY);
- }
-
- else if (transactionComplete == true) //If dio0ISR has fired, a packet has arrived
- {
- triggerEvent(TRIGGER_LINK_PACKET_RECEIVED);
- transactionComplete = false; //Reset ISR flag
- changeState(RADIO_LINKED_RECEIVED_PACKET);
- }
-
- else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
- hopChannel();
-
- else if ((millis() - packetTimestamp) > (unsigned int)(settings.heartbeatTimeout + random(0, 1000))) //Avoid pinging each other at same time
- {
- if (receiveInProcess() == false)
- {
- randomSeed(radio.randomByte()); //Takes 10ms. Reseed the random delay between heartbeats
- triggerEvent(TRIGGER_LINK_SEND_PING);
- sendPingPacket();
- changeState(RADIO_LINKED_TRANSMITTING);
- }
- else
- LRS_DEBUG_PRINTLN("RECEIVING_STANDBY: RX In Progress");
- }
-
- else //Process any waiting serial or commands
- {
- //If the radio is available, send any data in the serial buffer over the radio
- if (receiveInProcess() == false)
- {
- if (availableRXBytes()) //If we have bytes
- {
- if (processWaitingSerial() == true) //If we've hit a frame size or frame-timed-out
- {
- triggerEvent(TRIGGER_LINK_DATA_PACKET);
- sendDataPacket();
- changeState(RADIO_LINKED_TRANSMITTING);
- }
- }
- else if (availableTXCommandBytes()) //If we have command bytes to send out
- {
- //Load command bytes into outgoing packet
- readyOutgoingCommandPacket();
-
- triggerEvent(TRIGGER_LINK_DATA_PACKET);
-
- //Serial.print("Sending Command/Response: ");
- //for (int x = 0 ; x < packetSize ; x++)
- // Serial.write(outgoingPacket[x]);
- //Serial.println();
-
- //We now have the commandTXBuffer loaded. But we need to send an remoteCommandResponse if we are pointed at PRINT_TO_RF.
- if (printerEndpoint == PRINT_TO_RF)
- {
- //If printerEndpoint is PRINT_TO_RF we know the last commandTXBuffer was filled with a response to a command
- sendCommandResponseDataPacket();
- }
- else
- {
- //This packet was generated with sendRemoteCommand() and is a command packet
- sendCommandDataPacket();
- }
-
- if (availableTXCommandBytes() == 0)
- printerEndpoint = PRINT_TO_SERIAL; //Once the response is received, we need to print it to serial
-
- changeState(RADIO_LINKED_TRANSMITTING);
- }
- }
- } //End processWaitingSerial
- }
- break;
-
- case RADIO_LINKED_TRANSMITTING:
- {
- if (transactionComplete == true) //If dio0ISR has fired, we are done transmitting
- {
- transactionComplete = false; //Reset ISR flag
-
- if (expectingAck == true)
- {
- returnToReceiving();
- changeState(RADIO_LINKED_ACK_WAIT);
- }
- else
- {
- triggerEvent(TRIGGER_LINK_SENT_ACK_PACKET);
- returnToReceiving();
- changeState(RADIO_LINKED_RECEIVING_STANDBY);
- }
- }
- else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
- hopChannel();
- }
- break;
-
- case RADIO_LINKED_ACK_WAIT:
- {
- if (transactionComplete == true) //If dio0ISR has fired, a packet has arrived
- {
- transactionComplete = false; //Reset ISR flag
- changeState(RADIO_LINKED_RECEIVED_PACKET);
- }
-
- else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
- hopChannel();
-
- //Check to see if we need to retransmit
- if ((millis() - packetTimestamp) > (packetAirTime + controlPacketAirTime)) //Wait for xmit of packet and ACK response
- {
- if (packetSent > settings.maxResends)
- {
- LRS_DEBUG_PRINTLN("Packet Lost");
- packetsLost++;
- totalPacketsLost++;
- returnToReceiving();
- changeState(RADIO_LINKED_RECEIVING_STANDBY);
- }
- else
- {
- if (receiveInProcess() == false)
- {
- triggerEvent(TRIGGER_LINK_PACKET_RESEND);
- packetsResent++;
- sendResendPacket();
- changeState(RADIO_LINKED_TRANSMITTING);
- }
- else
- {
- LRS_DEBUG_PRINTLN("ACK_WAIT: RX In Progress");
- triggerEvent(TRIGGER_RX_IN_PROGRESS);
- }
- }
- }
- }
- break;
-
- case RADIO_LINKED_RECEIVED_PACKET:
- {
- PacketType packetType = identifyPacketType(); //Look at the packet we just received
-
- if (packetType == PACKET_ACK || packetType == PACKET_COMMAND_ACK || packetType == PACKET_COMMAND_RESPONSE_ACK)
- {
- //This packet is an ack. Return to receiving.
- triggerEvent(TRIGGER_ACK_PROCESSED); //Trigger for transmission timing
-
- if (settings.displayPacketQuality == true)
- {
- systemPrintln();
- systemPrint("R:");
- systemPrint(radio.getRSSI());
- systemPrint("\tS:");
- systemPrint(radio.getSNR());
- systemPrint("\tfE:");
- systemPrint(radio.getFrequencyError());
- systemPrintln();
- }
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- returnToReceiving();
- changeState(RADIO_LINKED_RECEIVING_STANDBY);
- }
- else if (packetType == PACKET_DUPLICATE)
- {
- //It's a duplicate. Ack then throw data away.
- triggerEvent(TRIGGER_LINK_DUPLICATE_PACKET);
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- sendAckPacket();
- changeState(RADIO_LINKED_TRANSMITTING);
- }
- else if (packetType == PACKET_PING)
- {
- //Someone is pinging us. Ack back.
- triggerEvent(TRIGGER_LINK_CONTROL_PACKET);
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- sendAckPacket();
- changeState(RADIO_LINKED_TRANSMITTING);
- }
- else if (packetType == PACKET_DATA)
- {
- //Pull data from packet and move into outbound serial buffer
- if (settings.displayPacketQuality == true)
- {
- systemPrintln();
- systemPrint("R:");
- systemPrint(radio.getRSSI());
- systemPrint("\tS:");
- systemPrint(radio.getSNR());
- systemPrint("\tfE:");
- systemPrint(radio.getFrequencyError());
- systemPrintln();
- }
-
- //Move this packet into the tx buffer
- //We cannot directly print here because Serial.print is blocking
- for (int x = 0 ; x < lastPacketSize ; x++)
- {
- serialTransmitBuffer[txHead++] = lastPacket[x];
- txHead %= sizeof(serialTransmitBuffer);
- }
-
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- sendAckPacket(); //Transmit ACK
- changeState(RADIO_LINKED_TRANSMITTING);
- }
-
- else if (packetType == PACKET_COMMAND_DATA)
- {
- //Serial.print("Received Command Data: ");
- //for (int x = 0 ; x < lastPacketSize ; x++)
- // Serial.write(lastPacket[x]);
- //Serial.println();
-
- //Move this packet into the command RX buffer
- for (int x = 0 ; x < lastPacketSize ; x++)
- {
- commandRXBuffer[commandRXHead++] = lastPacket[x];
- commandRXHead %= sizeof(commandRXBuffer);
- }
-
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- sendCommandAckPacket(); //Transmit ACK
- changeState(RADIO_LINKED_TRANSMITTING);
- }
-
- else if (packetType == PACKET_COMMAND_RESPONSE_DATA)
- {
- //Print received data. This is blocking but we do not use the serialTransmitBuffer because we're in command mode (and it's not much data to print).
- for (int x = 0 ; x < lastPacketSize ; x++)
- Serial.write(lastPacket[x]);
-
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- sendCommandResponseAckPacket(); //Transmit ACK
- changeState(RADIO_LINKED_TRANSMITTING);
- }
- else if (packetType == PACKET_COMMAND_RESPONSE_ACK)
- {
- //If we are waiting for ack before radio config, apply settings
- if (confirmDeliveryBeforeRadioConfig == true)
- {
- confirmDeliveryBeforeRadioConfig = false;
-
- //Apply settings
- generateHopTable(); //Generate freq with new settings
- configureRadio(); //Apply any new settings
-
- setRSSI(0); //Turn off RSSI LEDs
- changeState(RADIO_RESET);
- }
- else //It was just an ACK
- {
- packetsLost = 0; //Reset, used for linkLost testing
- updateRSSI(); //Adjust LEDs to RSSI level
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- returnToReceiving();
- changeState(RADIO_LINKED_RECEIVING_STANDBY);
- }
- }
- else //packetType == PACKET_BAD, packetType == PACKET_NETID_MISMATCH
- {
- //Packet type not supported in this state
- triggerEvent(TRIGGER_LINK_BAD_PACKET);
- returnToReceiving();
- changeState(RADIO_LINKED_RECEIVING_STANDBY);
- }
- }
- break;
-
- //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
-
- case RADIO_BROADCASTING_RECEIVING_STANDBY:
- {
- if (transactionComplete == true) //If dio0ISR has fired, a packet has arrived
- {
- triggerEvent(TRIGGER_BROADCAST_PACKET_RECEIVED);
- transactionComplete = false; //Reset ISR flag
- changeState(RADIO_BROADCASTING_RECEIVED_PACKET);
- }
-
- else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
- hopChannel();
-
- else //Process waiting serial
- {
- //If the radio is available, send any data in the serial buffer over the radio
- if (receiveInProcess() == false)
- {
- if (availableRXBytes()) //If we have bytes
- {
- if (processWaitingSerial() == true) //If we've hit a frame size or frame-timed-out
- {
- triggerEvent(TRIGGER_BROADCAST_DATA_PACKET);
- sendDataPacket();
- changeState(RADIO_BROADCASTING_TRANSMITTING);
- }
- }
- }
- } //End processWaitingSerial
-
- //Toggle 2 LEDs if we have recently transmitted
- if (millis() - packetTimestamp < 5000)
- {
- if (millis() - lastLinkBlink > 250) //Blink at 4Hz
- {
- lastLinkBlink = millis();
- if (digitalRead(pin_rssi2LED) == HIGH)
- setRSSI(0b0001);
- else
- setRSSI(0b0010);
- }
- }
- else if (millis() - lastPacketReceived < 5000)
- {
- updateRSSI(); //Adjust LEDs to RSSI level
- }
-
- //Turn off RSSI after 5 seconds of no activity
- else
- setRSSI(0);
-
- }
- break;
-
- case RADIO_BROADCASTING_TRANSMITTING:
- {
- if (transactionComplete == true) //If dio0ISR has fired, we are done transmitting
- {
- transactionComplete = false; //Reset ISR flag
- returnToReceiving();
- changeState(RADIO_BROADCASTING_RECEIVING_STANDBY); //No ack response when in broadcasting mode
- setRSSI(0b0001);
- }
-
- else if (timeToHop == true) //If the dio1ISR has fired, move to next frequency
- hopChannel();
- }
- break;
- case RADIO_BROADCASTING_RECEIVED_PACKET:
- {
- PacketType packetType = identifyPacketType(); //Look at the packet we just received
-
- if (packetType == PACKET_ACK)
- {
- //We should not be receiving ack packets, but if we do, just ignore
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- returnToReceiving();
- changeState(RADIO_BROADCASTING_RECEIVING_STANDBY);
- }
- else if (packetType == PACKET_DUPLICATE || packetType == PACKET_PING)
- {
- //We should not be receiving control packets, but if we do, just ignore
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- returnToReceiving(); //No response when in broadcasting mode
- changeState(RADIO_BROADCASTING_RECEIVING_STANDBY);
- }
- else if (packetType == PACKET_DATA)
- {
- if (settings.displayPacketQuality == true)
- {
- systemPrintln();
- systemPrint("R:");
- systemPrint(radio.getRSSI());
- systemPrint("\tS:");
- systemPrint(radio.getSNR());
- systemPrint("\tfE:");
- systemPrint(radio.getFrequencyError());
- systemPrintln();
- }
-
- //Move this packet into the tx buffer
- //We cannot directly print here because Serial.print is blocking
- for (int x = 0 ; x < lastPacketSize ; x++)
- {
- serialTransmitBuffer[txHead++] = lastPacket[x];
- txHead %= sizeof(serialTransmitBuffer);
- }
-
- updateRSSI(); //Adjust LEDs to RSSI level
- frequencyCorrection += radio.getFrequencyError() / 1000000.0;
- returnToReceiving(); //No response when in broadcasting mode
- changeState(RADIO_BROADCASTING_RECEIVING_STANDBY);
-
- lastPacketReceived = millis(); //Update timestamp for Link LED
- }
- else //PACKET_BAD, PACKET_NETID_MISMATCH
- {
- //This packet type is not supported in this state
- returnToReceiving();
- changeState(RADIO_BROADCASTING_RECEIVING_STANDBY);
- }
-
- }
- break;
-
- //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
-
- /*
- beginTraining beginDefaultTraining
- | Save current settings | Save default settings
- V |
- +<-------------------------------’
- |
- V
- moveToTrainingFreq
- |
- V
- RADIO_TRAINING_TRANSMITTING
- |
- V
- RADIO_TRAINING_ACK_WAIT --------------.
- | |
- V |
- RADIO_TRAINING_RECEIVING_HERE_FIRST |
- | |
- +<----------------------------’
- |
- V
- RADIO_TRAINING_RECEIVED_PACKET
- |
- V
- endTraining
- */
-
- case RADIO_TRAINING_TRANSMITTING:
- {
- if (transactionComplete == true) //If dio0ISR has fired, we are done transmitting
- {
- transactionComplete = false; //Reset ISR flag
- returnToReceiving();
- changeState(RADIO_TRAINING_ACK_WAIT);
- }
- }
- break;
- case RADIO_TRAINING_ACK_WAIT:
- {
- //If we receive an ACK, absorb training data
- if (transactionComplete == true) //If dio0ISR has fired, a packet has arrived
- {
- transactionComplete = false; //Reset ISR flag
- changeState(RADIO_TRAINING_RECEIVED_PACKET);
- }
-
- //If timeout, create new link data and return to receive, and wait for training ping from remote
- if ((millis() - packetTimestamp) > (packetAirTime + controlPacketAirTime)) //Wait for xmit of packet and ACK response
- {
- triggerEvent(TRIGGER_TRAINING_NO_ACK);
- generateTrainingSettings();
- returnToReceiving();
- changeState(RADIO_TRAINING_RECEIVING_HERE_FIRST);
- }
- }
- break;
- case RADIO_TRAINING_RECEIVING_HERE_FIRST:
- {
- //Wait for ping. Once received, transmit training data
- if (transactionComplete == true) //If dio0ISR has fired, a packet has arrived
- {
- transactionComplete = false; //Reset ISR flag
- changeState(RADIO_TRAINING_RECEIVED_PACKET);
- }
- updateCylonLEDs();
- }
- break;
-
- case RADIO_TRAINING_RECEIVED_PACKET:
- {
- PacketType packetType = identifyPacketType(); //Look at the packet we just received
-
- if (packetType == PACKET_TRAINING_PING)
- {
- triggerEvent(TRIGGER_TRAINING_CONTROL_PACKET);
- packetsLost = 0; //Reset, used for linkLost testing
- sendTrainingDataPacket(); //Someone is pinging us, send training data back
-
- //Wait for transmission to complete before ending training
- while (transactionComplete == false) //If dio0ISR has fired, a packet has arrived
- {
- if ((millis() - packetTimestamp) > (packetAirTime + controlPacketAirTime)) //Wait for xmit of packet and ACK response
- {
- LRS_DEBUG_PRINTLN("Timeout");
- break;
- }
- }
- LRS_DEBUG_PRINTLN("Ending Training");
-
- endTraining(false); //We do not have data to apply to settings
- }
-
- else if (packetType == PACKET_TRAINING_DATA)
- {
- //The waiting node has responded with a data packet
- //Absorb training data and then return to normal operation
- triggerEvent(TRIGGER_TRAINING_DATA_PACKET);
- packetsLost = 0; //Reset, used for linkLost testing
- endTraining(true); //Apply data from packet to settings
- }
-
- //During training, only training packets are valid
- else //PACKET_BAD, PACKET_NETID_MISMATCH, PACKET_ACK, PACKET_PING, PACKET_DATA
- {
- triggerEvent(TRIGGER_TRAINING_BAD_PACKET);
- returnToReceiving();
- changeState(RADIO_TRAINING_RECEIVING_HERE_FIRST);
- }
- }
- break;
- }
-}
-
-//Return true if the radio is in a linked state
-//This is used for determining if we can do remote AT commands or not
-bool isLinked()
-{
- if (radioState == RADIO_LINKED_RECEIVING_STANDBY
- || radioState == RADIO_LINKED_TRANSMITTING
- || radioState == RADIO_LINKED_ACK_WAIT
- || radioState == RADIO_LINKED_RECEIVED_PACKET
- )
- return (true);
-
- return (false);
-}
-
-const RADIO_STATE_ENTRY radioStateTable[] =
-{
- {RADIO_RESET, "RESET", NULL}, // 0
-
- //V1
- // State Name Description
- {RADIO_NO_LINK_RECEIVING_STANDBY, "NO_LINK_RECEIVING_STANDBY", "[No Link] Receiving Standby"},// 1
- {RADIO_NO_LINK_TRANSMITTING, "NO_LINK_TRANSMITTING", "[No Link] Transmitting"}, // 2
- {RADIO_NO_LINK_ACK_WAIT, "NO_LINK_ACK_WAIT", "[No Link] Ack Wait"}, // 3
- {RADIO_NO_LINK_RECEIVED_PACKET, "NO_LINK_RECEIVED_PACKET", "[No Link] Received Packet"}, // 4
- {RADIO_LINKED_RECEIVING_STANDBY, "LINKED_RECEIVING_STANDBY", "Receiving Standby "}, // 5
- {RADIO_LINKED_TRANSMITTING, "LINKED_TRANSMITTING", "Transmitting "}, // 6
- {RADIO_LINKED_ACK_WAIT, "LINKED_ACK_WAIT", "Ack Wait "}, // 7
- {RADIO_LINKED_RECEIVED_PACKET, "LINKED_RECEIVED_PACKET", "Received Packet "}, // 8
- {RADIO_BROADCASTING_RECEIVING_STANDBY, "BROADCASTING_RECEIVING_STANDBY", "B-Receiving Standby "}, // 9
- {RADIO_BROADCASTING_TRANSMITTING, "BROADCASTING_TRANSMITTING", "B-Transmitting "}, //10
- {RADIO_BROADCASTING_RECEIVED_PACKET, "BROADCASTING_RECEIVED_PACKET", "B-Received Packet "}, //11
- {RADIO_TRAINING_RECEIVING_HERE_FIRST, "TRAINING_RECEIVING_HERE_FIRST", "[Training] RX Here First"}, //12
- {RADIO_TRAINING_TRANSMITTING, "TRAINING_TRANSMITTING", "[Training] TX"}, //13
- {RADIO_TRAINING_ACK_WAIT, "TRAINING_ACK_WAIT", "[Training] Ack Wait"}, //14
- {RADIO_TRAINING_RECEIVED_PACKET, "TRAINING_RECEIVED_PACKET", "[Training] RX Packet"}, //15
-};
-
-void verifyRadioStateTable()
-{
- int expectedState;
- int i;
- int index;
- int j;
- unsigned int lastPrint;
- int maxDescriptionLength;
- int maxNameLength;
- bool missing;
- int * order;
- int tableEntries;
- int temp;
-
- //Verify that all the entries are in the state table
- tableEntries = sizeof(radioStateTable) / sizeof(radioStateTable[0]);
- for (index = 0; index < tableEntries; index++)
- {
- //Validate the current table entry
- if (index == radioStateTable[index].state)
- continue;
-
- //Wait for the USB serial port
- if (!settings.usbSerialWait)
- while (!Serial);
-
- //An invalid entry was found
- //Try to build a valid table
- order = (int *)malloc(tableEntries * sizeof(*order));
- if (!order)
- {
- systemPrintln("ERROR - Failed to allocate the order table from the heap!");
- while (1);
- }
-
- //Assume the table is in the correct order
- maxDescriptionLength = 0;
- maxNameLength = 0;
- for (index = 0; index < tableEntries; index++)
- {
- order[index] = index;
- if (radioStateTable[index].state < RADIO_MAX_STATE)
- {
- if (maxNameLength < strlen(radioStateTable[index].name))
- maxNameLength = strlen(radioStateTable[index].name);
- if (radioStateTable[index].description
- && (maxDescriptionLength < strlen(radioStateTable[index].description)))
- maxDescriptionLength = strlen(radioStateTable[index].description);
- }
- }
-
- //Bubble sort the entries
- for (index = 0; index < tableEntries; index++)
- {
- for (i = index + 1; i < tableEntries; i++)
- {
- if (radioStateTable[order[i]].state < radioStateTable[order[index]].state)
- {
- //Swap the two values
- temp = order[i];
- order[i] = order[index];
- order[index] = temp;
- }
- }
- }
-
- //Determine if there are missing states
- missing = false;
- for (index = 0; index < tableEntries; index++)
- {
- if (radioStateTable[order[i]].state != index)
- {
- missing = true;
- break;
- }
- }
-
- //Display the request
- systemPrintln("Please replace radioStateTable in States.ino with the following table:");
- if (missing)
- systemPrintln("Please update the table with the missing states");
- systemPrintln();
-
- //Display the new table
- systemPrintln("const RADIO_STATE_ENTRY radioStateTable[] =");
- systemPrintln("{");
- systemPrintln(" // State Name Description");
- expectedState = 0;
- for (index = 0; index < tableEntries; index++)
- {
- //Remove bad states from the table
- if (radioStateTable[order[index]].state >= RADIO_MAX_STATE)
- break;
- if (radioStateTable[order[index]].state > expectedState)
- {
- //Print the missing entries
- systemPrint("Missing state");
- if ((expectedState + 1) < radioStateTable[order[index]].state)
- {
- systemPrint("s ");
- systemPrint(expectedState);
- systemPrint(" - ");
- systemPrintln(radioStateTable[order[index]].state - 1);
- }
- else
- {
- systemPrint(" ");
- systemPrintln(expectedState);
- }
- while (radioStateTable[order[index]].state > expectedState)
- {
- systemPrint(" {");
- systemPrint(", ");
- for (i = 0; i < (6 + maxNameLength); i++)
- systemPrint(" ");
- systemPrint("\"\", ");
- for (i = 0; i < maxNameLength; i++)
- systemPrint(" ");
- systemPrint("\"\"},");
- for (i = 0; i < maxDescriptionLength; i++)
- systemPrint(" ");
- systemPrint("//");
- if (expectedState < 10)
- systemPrint(" ");
- systemPrintln(expectedState++);
- }
- }
-
- //Print the state
- systemPrint(" {RADIO_");
- systemPrint(radioStateTable[order[index]].name);
- systemPrint(", ");
-
- //Align the name column
- for (i = strlen(radioStateTable[order[index]].name); i < maxNameLength; i++)
- systemPrint(" ");
-
- //Print the name
- systemPrint("\"");
- systemPrint(radioStateTable[order[index]].name);
- systemPrint("\", ");
-
- //Align the description column
- for (i = strlen(radioStateTable[order[index]].name); i < maxNameLength; i++)
- systemPrint(" ");
-
- //Print the description
- if (radioStateTable[order[index]].description)
- {
- systemPrint("\"");
- systemPrint(radioStateTable[order[index]].description);
- systemPrint("\"},");
- }
- else
- systemPrint("NULL},");
-
- //Align the comments
- for (i = radioStateTable[order[index]].description ? strlen(radioStateTable[order[index]].description) : 2;
- i < maxDescriptionLength; i++)
- systemPrint(" ");
-
- //Add the state value comment
- systemPrint("//");
- if (expectedState < 10)
- systemPrint(" ");
- systemPrintln(expectedState++);
- }
- systemPrintln("};");
- systemFlush();
-
- //Wait forever
- while (1);
- }
-}
-
-//Change states and print the new state
-void changeState(RadioStates newState)
-{
- radioState = newState;
-
- if ((settings.debug == false) && (settings.debugStates == false))
- return;
-
- //Debug print
- systemPrint("State: ");
- if (newState >= RADIO_MAX_STATE)
- {
- systemPrint(radioState);
- systemPrintln(" is Unknown");
- }
- else
- {
- if (radioStateTable[radioState].description)
- systemPrintln(radioStateTable[radioState].description);
- else
- systemPrintln(radioStateTable[radioState].name);
- }
-}
diff --git a/Firmware/LoRaSerial_Firmware/System.ino b/Firmware/LoRaSerial_Firmware/System.ino
deleted file mode 100644
index 1ad3bfb3..00000000
--- a/Firmware/LoRaSerial_Firmware/System.ino
+++ /dev/null
@@ -1,501 +0,0 @@
-void systemPrint(const char* value)
-{
- if (printerEndpoint == PRINT_TO_SERIAL)
- {
- arch.serialPrint(value);
- }
- else if (printerEndpoint == PRINT_TO_RF)
- {
- //Move these characters into the transmit buffer
- for (uint16_t x = 0 ; x < strlen(value) ; x++)
- {
- commandTXBuffer[commandTXHead++] = value[x];
- commandTXHead %= sizeof(commandTXBuffer);
- }
- }
-}
-
-void systemPrintln(const char* value)
-{
- systemPrint(value);
- systemPrint("\r\n");
-}
-
-void systemPrint(int value)
-{
- char temp[20];
- sprintf(temp, "%d", value);
- systemPrint(temp);
-}
-
-void systemPrint(int value, uint8_t printType)
-{
- char temp[20];
-
- if (printType == HEX)
- sprintf(temp, "%08x", value);
- else if (printType == DEC)
- sprintf(temp, "%d", value);
-
- systemPrint(temp);
-}
-
-void systemPrintln(int value)
-{
- systemPrint(value);
- systemPrint("\r\n");
-}
-
-void systemPrint(uint8_t value, uint8_t printType)
-{
- char temp[20];
-
- if (printType == HEX)
- sprintf(temp, "%02X", value);
- else if (printType == DEC)
- sprintf(temp, "%d", value);
-
- systemPrint(temp);
-}
-
-void systemPrintln(uint8_t value, uint8_t printType)
-{
- systemPrint(value, printType);
- systemPrint("\r\n");
-}
-
-void systemPrint(float value, uint8_t decimals)
-{
- char temp[20];
- sprintf(temp, "%.*f", decimals, value);
- systemPrint(temp);
-}
-
-void systemPrintln(float value, uint8_t decimals)
-{
- systemPrint(value, decimals);
- systemPrint("\r\n");
-}
-
-void systemPrint(double value, uint8_t decimals)
-{
- char temp[20];
- sprintf(temp, "%.*g", decimals, value);
- systemPrint(temp);
-}
-
-void systemPrintln(double value, uint8_t decimals)
-{
- systemPrint(value, decimals);
- systemPrint("\r\n");
-}
-
-void systemPrintln()
-{
- systemPrint("\r\n");
-}
-
-void systemPrintTimestamp()
-{
- unsigned int milliseconds;
- unsigned int seconds;
- unsigned int minutes;
- unsigned int hours;
- unsigned int days;
- unsigned int total;
-
- if (settings.printTimestamp)
- {
- petWDT();
- milliseconds = millis();
- seconds = milliseconds / 1000;
- minutes = seconds / 60;
- hours = minutes / 60;
- days = hours / 24;
-
- total = days * 24;
- hours -= total;
-
- total = (total + hours) * 60;
- minutes -= total;
-
- total = (total + minutes) * 60;
- seconds -= total;
-
- total = (total + seconds) * 1000;
- milliseconds -= total;
-
- //Print the days
- if (days < 10) systemPrint(" ");
- if (days)
- systemPrint(days);
- else
- systemPrint(" ");
- systemPrint(" ");
-
- //Print the time
- if (hours < 10) systemPrint(" ");
- systemPrint(hours);
- systemPrint(":");
- if (minutes < 10) systemPrint("0");
- systemPrint(minutes);
- systemPrint(":");
- if (seconds < 10) systemPrint("0");
- systemPrint(seconds);
- systemPrint(".");
- if (milliseconds < 100) systemPrint("0");
- if (milliseconds < 10) systemPrint("0");
- systemPrint(milliseconds);
- systemPrint(": ");
- petWDT();
- }
-}
-
-void systemPrintUniqueID(uint32_t * uniqueID)
-{
- uint8_t * id = (uint8_t *)uniqueID;
- int index;
-
- //Display in the same byte order as dump output
- for (index = 0; index < 16; index++)
- systemPrint(id[index], HEX);
-}
-
-void systemWrite(uint8_t value)
-{
- arch.serialWrite(value);
-}
-
-void systemFlush()
-{
- arch.serialFlush();
-}
-
-uint8_t systemRead()
-{
- return (arch.serialRead());
-}
-
-//Check the train button and change state accordingly
-void updateButton()
-{
- if (trainBtn != NULL)
- {
- trainBtn->read();
-
- if (trainState == TRAIN_NO_PRESS && trainBtn->pressedFor(trainButtonTime))
- {
- trainState = TRAIN_PRESSED_2S;
- lastTrainBlink = millis();
- }
- else if (trainState == TRAIN_PRESSED_2S && trainBtn->wasReleased())
- {
- setRSSI(0b1111);
-
- beginTraining();
-
- trainState = TRAIN_NO_PRESS;
- }
- else if (trainState == TRAIN_PRESSED_2S && trainBtn->pressedFor(trainWithDefaultsButtonTime))
- {
- trainState = TRAIN_PRESSED_5S;
- }
- else if (trainState == TRAIN_PRESSED_5S && trainBtn->wasReleased())
- {
- setRSSI(0b1111);
-
- beginDefaultTraining();
-
- trainState = TRAIN_NO_PRESS;
- }
-
- //Blink LEDs according to our state while we wait for user to release button
- if (trainState == TRAIN_PRESSED_2S)
- {
- if (millis() - lastTrainBlink > 500) //Slow blink
- {
- Serial.println("Train Blinking LEDs");
- lastTrainBlink = millis();
-
- //Toggle RSSI LEDs
- if (digitalRead(pin_rssi1LED) == HIGH)
- setRSSI(0);
- else
- setRSSI(0b1111);
- }
- }
- else if (trainState == TRAIN_PRESSED_5S)
- {
- if (millis() - lastTrainBlink > 100) //Fast blink
- {
- lastTrainBlink = millis();
-
- //Toggle RSSI LEDs
- if (digitalRead(pin_rssi1LED) == HIGH)
- setRSSI(0);
- else
- setRSSI(0b1111);
- }
- }
- }
-}
-
-//Platform specific reset commands
-void systemReset()
-{
- arch.systemReset();
-}
-
-//Encrypt a given array in place
-void encryptBuffer(uint8_t *bufferToEncrypt, uint8_t arraySize)
-{
- gcm.setKey(settings.encryptionKey, gcm.keySize());
- gcm.setIV(AESiv, sizeof(AESiv));
-
- gcm.encrypt(bufferToEncrypt, bufferToEncrypt, arraySize);
-}
-
-//Decrypt a given array in place
-void decryptBuffer(uint8_t *bufferToDecrypt, uint8_t arraySize)
-{
- gcm.setKey(settings.encryptionKey, gcm.keySize());
- gcm.setIV(AESiv, sizeof(AESiv));
-
- gcm.decrypt(bufferToDecrypt, bufferToDecrypt, arraySize);
-}
-
-
-//IBM Whitening process from Semtech "Software Whitening and CRC on SX12xx Devices" app note
-//Removes DC Bias from data with long strings of 1s or 0s
-void radioComputeWhitening(uint8_t *buffer, uint16_t bufferSize)
-{
- uint8_t WhiteningKeyMSB = 0x01;
- uint8_t WhiteningKeyLSB = 0xFF;
- uint8_t WhiteningKeyMSBPrevious = 0;
-
- for (uint16_t j = 0 ; j < bufferSize ; j++)
- {
- buffer[j] ^= WhiteningKeyLSB;
-
- for (uint8_t i = 0 ; i < 8 ; i++)
- {
- WhiteningKeyMSBPrevious = WhiteningKeyMSB;
- WhiteningKeyMSB = (WhiteningKeyLSB & 0x01) ^ ((WhiteningKeyLSB >> 5) & 0x01);
- WhiteningKeyLSB = ((WhiteningKeyLSB >> 1 ) & 0xFF) | ((WhiteningKeyMSBPrevious << 7) & 0x80);
- }
- }
-}
-
-//Toggle a pin. Used for logic analyzer debugging.
-void triggerEvent(uint8_t triggerNumber)
-{
- uint8_t triggerBitNumber;
- uint32_t triggerEnable;
- uint16_t triggerWidth;
-
- //Determine which trigger enable to use
- triggerBitNumber = triggerNumber;
- triggerEnable = settings.triggerEnable;
- if (triggerNumber >= 32)
- {
- triggerBitNumber -= 32;
- triggerEnable = settings.triggerEnable2;
- }
-
- //Determine if the trigger is enabled
- if ((pin_trigger != 255) && (triggerEnable & (1 << triggerBitNumber)))
- {
- //Determine if the trigger pin is enabled
- if (pin_trigger != 255)
- {
- if ((settings.debug == true) || (settings.debugTrigger == true))
- {
- //Determine the trigger pulse width
- triggerWidth = settings.triggerWidth;
- if (settings.triggerWidthIsMultiplier)
- triggerWidth *= (triggerNumber + 1);
-
- //Output the trigger pulse
- digitalWrite(pin_trigger, LOW);
- delayMicroseconds(triggerWidth);
- digitalWrite(pin_trigger, HIGH);
- }
- }
- }
-}
-
-//Copy the contents of settings struct to outgoing array
-//Note: All variables in struct_settings must be fully cast (uint16_t, int32_t, etc, not int)
-//so that we will have alignment between radios using different platforms (ie ESP32 vs SAMD)
-void moveSettingsToPacket(Settings settings, uint8_t* packetBuffer)
-{
- //Get a byte pointer that points to the beginning of the struct
- uint8_t *bytePtr = (uint8_t*)&settings;
-
- for (uint8_t x = 0 ; x < sizeof(settings) ; x++)
- packetBuffer[x] = bytePtr[x];
-}
-
-//Used to move an incoming packet into the remoteSettings temp buffer
-void movePacketToSettings(Settings settings, uint8_t* packetBuffer)
-{
- // Get a byte pointer that points to the beginning of the struct
- uint8_t *bytePtr = (uint8_t*)&settings;
-
- for (uint8_t x = 0 ; x < sizeof(settings) ; x++)
- bytePtr[x] = packetBuffer[x];
-}
-
-//Convert ASCII character to base 16
-int8_t charToHex(char a)
-{
- a = toupper(a);
-
- if ('0' <= a && a <= '9') a -= '0';
- else if ('A' <= a && a <= 'F') a = a - 'A' + 10;
- else a = -1;
- return a;
-}
-
-//Given two letters, convert to base 10
-uint8_t charHexToDec(char a, char b)
-{
- a = charToHex(a);
- b = charToHex(b);
- return ((a << 4) | b);
-}
-
-void dumpBuffer(uint8_t * data, int length)
-{
- char byte[2];
- int bytes;
- uint8_t * dataEnd;
- uint8_t * dataStart;
- const int displayWidth = 16;
- int index;
-
- byte[1] = 0;
- dataStart = data;
- dataEnd = &data[length];
- while (data < dataEnd)
- {
- // Display the offset
- systemPrint(" 0x");
- systemPrint((uint8_t)(data - dataStart), HEX);
- systemPrint(": ");
-
- // Determine the number of bytes to display
- bytes = dataEnd - data;
- if (bytes > displayWidth)
- bytes = displayWidth;
-
- // Display the data bytes in hex
- for (index = 0; index < bytes; index++)
- {
- systemPrint(" ");
- systemPrint(*data++, HEX);
- petWDT();
- }
-
- // Space over to the ASCII display
- for (; index < displayWidth; index++)
- {
- systemPrint(" ");
- petWDT();
- }
- systemPrint(" ");
-
- // Display the ASCII bytes
- data -= bytes;
- for (index = 0; index < bytes; index++) {
- byte[0] = *data++;
- systemPrint(((byte[0] <= ' ') || (byte[0] >= 0x7f)) ? "." : byte);
- }
- systemPrintln();
- petWDT();
- }
-}
-
-void updateRSSI()
-{
- //RSSI must be above these negative numbers for LED to illuminate
- const int rssiLevelLow = -150;
- const int rssiLevelMed = -70;
- const int rssiLevelHigh = -50;
- const int rssiLevelMax = -20;
-
- int rssi = radio.getRSSI();
-
- LRS_DEBUG_PRINT("RSSI: ");
- LRS_DEBUG_PRINTLN(rssi);
-
- //Set LEDs according to RSSI level
- if (rssi > rssiLevelLow)
- setRSSI(0b0001);
- if (rssi > rssiLevelMed)
- setRSSI(0b0011);
- if (rssi > rssiLevelHigh)
- setRSSI(0b0111);
- if (rssi > rssiLevelMax)
- setRSSI(0b1111);
-}
-
-void setRSSI(uint8_t ledBits)
-{
- if (ledBits & 0b0001)
- digitalWrite(pin_rssi1LED, HIGH);
- else
- digitalWrite(pin_rssi1LED, LOW);
-
- if (ledBits & 0b0010)
- digitalWrite(pin_rssi2LED, HIGH);
- else
- digitalWrite(pin_rssi2LED, LOW);
-
- if (ledBits & 0b0100)
- digitalWrite(pin_rssi3LED, HIGH);
- else
- digitalWrite(pin_rssi3LED, LOW);
-
- if (ledBits & 0b1000)
- digitalWrite(pin_rssi4LED, HIGH);
- else
- digitalWrite(pin_rssi4LED, LOW);
-}
-
-void txLED(bool illuminate)
-{
- if (pin_txLED != 255)
- {
- if (illuminate == true)
- digitalWrite(pin_txLED, HIGH);
- else
- digitalWrite(pin_txLED, LOW);
- }
-}
-
-void rxLED(bool illuminate)
-{
- if (pin_rxLED != 255)
- {
- if (illuminate == true)
- digitalWrite(pin_rxLED, HIGH);
- else
- digitalWrite(pin_rxLED, LOW);
- }
-}
-
-int stricmp(const char * str1, const char * str2)
-{
- char char1;
- char char2;
-
- //Do a case insensitive comparison between the two strings
- do {
- char1 = toupper(*str1++);
- char2 = toupper(*str2++);
- } while (char1 && (char1 == char2));
-
- //Return the difference between the two strings
- return char1 - char2;
-}
diff --git a/Firmware/LoRaSerial_Firmware/Train.ino b/Firmware/LoRaSerial_Firmware/Train.ino
deleted file mode 100644
index be39a13e..00000000
--- a/Firmware/LoRaSerial_Firmware/Train.ino
+++ /dev/null
@@ -1,256 +0,0 @@
-
-void beginTraining()
-{
- LRS_DEBUG_PRINTLN("Begin training");
-
- originalSettings = settings; //Make copy of current settings
-
- moveToTrainingFreq();
-}
-
-void beginDefaultTraining()
-{
- LRS_DEBUG_PRINTLN("Begin default training");
-
- originalSettings = defaultSettings; //Upon completion we will return to default settings
-
- moveToTrainingFreq();
-}
-
-//Upon successful exchange of keys, go back to original settings
-void endTraining(bool newTrainingAvailable)
-{
- settings = originalSettings; //Return to original radio settings
-
- //Apply new netID and AES if available
- if (newTrainingAvailable)
- {
- if (lastPacketSize == sizeof(settings.encryptionKey) + 1) //Error check, should be AES key + NetID
- {
- //Move training data into settings
- for (uint8_t x = 0 ; x < sizeof(settings.encryptionKey); x++)
- settings.encryptionKey[x] = lastPacket[x];
-
- settings.netID = lastPacket[lastPacketSize - 1]; //Last spot in array is netID
-
- if ((settings.debug == true) || (settings.debugTraining == true))
- {
- systemPrint("New ID: ");
- systemPrintln(settings.netID);
-
- systemPrint("New Key: ");
- for (uint8_t i = 0 ; i < 16 ; i++)
- {
- systemPrint(settings.encryptionKey[i], HEX);
- systemPrint(" ");
- }
- systemPrintln();
- }
- }
- else
- {
- //If the packet was marked as training but was not valid training data, then give up. Return to normal radio mode with pre-existing settings.
- }
- }
- else
- {
- //We transmitted the training data, move the local training data into settings
- for (uint8_t x = 0 ; x < sizeof(settings.encryptionKey); x++)
- settings.encryptionKey[x] = trainEncryptionKey[x];
-
- settings.netID = trainNetID; //Last spot in array is netID
- }
-
- recordSystemSettings();
-
- generateHopTable(); //Generate frequency table based on current settings
-
- configureRadio(); //Setup radio with settings
-
- returnToReceiving();
-
- //Blink LEDs to indicate training success
- setRSSI(0b0000);
- delayWDT(100);
-
- setRSSI(0b1001);
- delayWDT(500);
-
- setRSSI(0b0110);
- delayWDT(500);
-
- setRSSI(0b1111);
- delayWDT(500);
-
- setRSSI(0b0000);
- delayWDT(500);
-
- setRSSI(0b1111);
- delayWDT(1500);
-
- setRSSI(0);
- delayWDT(2000);
-
- changeState(RADIO_RESET);
-
- sentFirstPing = false; //Send ping as soon as we exit
-
- systemPrintln("LINK TRAINED");
-}
-
-/*
- beginTraining beginDefaultTraining
- | Save current settings | Save default settings
- V |
- +<-------------------------------’
- |
- V
- moveToTrainingFreq
- |
- V
- RADIO_TRAINING_TRANSMITTING
- |
- V
- RADIO_TRAINING_ACK_WAIT --------------.
- | |
- V |
- RADIO_TRAINING_RECEIVING_HERE_FIRST |
- | |
- +<----------------------------’
- |
- V
- RADIO_TRAINING_RECEIVED_PACKET
- |
- V
- endTraining
-
-
- moveToTrainingFreq
-
- 1. Disable point-to-point
- 2. Disable frequency hopping
- 3. Reduce power to minimum
- 4. Generate HOP table
- 5. Compute channel spacing
- 6. Set training frequency
- 7. Configure the radio
- 8. Send training ping
- 9. Set state RADIO_TRAINING_TRANSMITTING
-
- endTraining
-
- 1. Restore original settings
- 2. Update encryption key
- 3. Set net ID
-*/
-
-//Change to known training frequency based on available freq and current major firmware version
-//This will allow different minor versions to continue to train to each other
-//Send special packet with train = 1, then wait for response
-void moveToTrainingFreq()
-{
- //During training use default radio settings. This ensures both radios are at known good settings.
- settings = defaultSettings; //Move to default settings
-
- //Disable hopping
- settings.frequencyHop = false;
-
- //Disable NetID checking
- settings.pointToPoint = false;
- settings.verifyRxNetID = false;
-
- //Debug training if requested
- if (originalSettings.debugTraining)
- {
- settings.debugTraining = originalSettings.debugTraining;
- settings.printPktData = originalSettings.printPktData;
- settings.printRfData = originalSettings.printRfData;
- }
-
- //Turn power as low as possible. We assume two units will be near each other.
- settings.radioBroadcastPower_dbm = 14;
-
- generateHopTable(); //Generate frequency table based on current settings
-
- configureRadio(); //Setup radio with settings
-
- //Move to frequency that is not part of the hop table
- //In normal operation we move 1/2 a channel away from min. In training, we move a full channel away + major firmware version.
- float channelSpacing = (settings.frequencyMax - settings.frequencyMin) / (float)(settings.numberOfChannels + 2);
- float trainFrequency = settings.frequencyMin + (channelSpacing * (FIRMWARE_VERSION_MAJOR % settings.numberOfChannels));
-
- channels[0] = trainFrequency; //Inject this frequency into the channel table
-
- //Transmit general ping packet to see if anyone else is sitting on the training channel
- sendTrainingPingPacket();
-
- //Recalculate packetAirTime because we need to wait not for a 2-byte response, but a 19 byte response
- packetAirTime = calcAirTime(sizeof(trainEncryptionKey) + sizeof(trainNetID) + 2);
-
- //Reset cylon variables
- startCylonLEDs();
-
- changeState(RADIO_TRAINING_TRANSMITTING);
-}
-
-//Generate new netID/AES key to share
-//We assume the user needs to maintain their settings (airSpeed, numberOfChannels, freq min/max, bandwidth/spread/hop)
-//but need to be on a different netID/AES key.
-void generateTrainingSettings()
-{
- LRS_DEBUG_PRINTLN("Generate New Training Settings");
-
- //Seed random number based on RF noise. We use Arduino random() because platform specific generation does not matter
- randomSeed(radio.randomByte());
-
- //Generate new NetID
- trainNetID = random(0, 256); //Inclusive, exclusive
-
- //Generate new AES Key. User may not be using AES but we still need both radios to have the same key in case they do enable AES.
- for (int x = 0 ; x < 16 ; x++)
- trainEncryptionKey[x] = random(0, 256); //Inclusive, exclusive
-
- //We do not generate new AES Initial Values here. Those are generated during generateHopTable() based on the unit's settings.
-
- if ((settings.debug == true) || (settings.debugTraining == true))
- {
- systemPrint("Select new NetID: ");
- systemPrintln(trainNetID);
-
- systemPrint("Select new Encryption Key:");
- for (uint8_t i = 0 ; i < 16 ; i++)
- {
- systemPrint(" ");
- systemPrint(trainEncryptionKey[i], HEX);
- }
- systemPrintln();
- }
-}
-
-//Start the cylon LEDs
-void startCylonLEDs()
-{
- trainCylonNumber = 0b0001;
- trainCylonDirection = -1;
-}
-
-//Update the cylon LEDs
-void updateCylonLEDs()
-{
- if ( (millis() - lastTrainBlink) > 75) //Blink while unit waits in training state
- {
- lastTrainBlink = millis();
-
- //Cylon the RSSI LEDs
- setRSSI(trainCylonNumber);
-
- if (trainCylonNumber == 0b1000 || trainCylonNumber == 0b0001)
- trainCylonDirection *= -1; //Change direction
-
- if (trainCylonDirection > 0)
- trainCylonNumber <<= 1;
- else
- trainCylonNumber >>= 1;
- }
-}
-
diff --git a/Firmware/LoRaSerial_Firmware/settings.h b/Firmware/LoRaSerial_Firmware/settings.h
deleted file mode 100644
index 438de086..00000000
--- a/Firmware/LoRaSerial_Firmware/settings.h
+++ /dev/null
@@ -1,230 +0,0 @@
-typedef enum
-{
- RADIO_RESET = 0,
-
- RADIO_NO_LINK_RECEIVING_STANDBY,
- RADIO_NO_LINK_TRANSMITTING,
- RADIO_NO_LINK_ACK_WAIT,
- RADIO_NO_LINK_RECEIVED_PACKET,
-
- RADIO_LINKED_RECEIVING_STANDBY,
- RADIO_LINKED_TRANSMITTING,
- RADIO_LINKED_ACK_WAIT,
- RADIO_LINKED_RECEIVED_PACKET,
-
- RADIO_BROADCASTING_RECEIVING_STANDBY,
- RADIO_BROADCASTING_TRANSMITTING,
- RADIO_BROADCASTING_RECEIVED_PACKET,
-
- RADIO_TRAINING_RECEIVING_HERE_FIRST,
- RADIO_TRAINING_TRANSMITTING,
- RADIO_TRAINING_ACK_WAIT,
- RADIO_TRAINING_RECEIVED_PACKET,
-
- RADIO_MAX_STATE,
-} RadioStates;
-RadioStates radioState = RADIO_NO_LINK_RECEIVING_STANDBY;
-
-typedef struct _RADIO_STATE_ENTRY
-{
- RadioStates state;
- const char * name;
- const char * description;
-} RADIO_STATE_ENTRY;
-
-//Possible types of packets received
-typedef enum
-{
- PACKET_BAD = 0,
- PACKET_NETID_MISMATCH,
- PACKET_ACK, //ack = 1
- PACKET_DUPLICATE,
- PACKET_PING, //ack = 0, len = 0
- PACKET_DATA,
-
- PACKET_COMMAND_ACK, //remoteCommand = 1, ack = 1
- PACKET_COMMAND_DATA, //remoteCommand = 1
-
- PACKET_COMMAND_RESPONSE_ACK, //remoteCommand = 1, remoteCommandResponse = 1, ack = 1
- PACKET_COMMAND_RESPONSE_DATA, //remoteCommand = 1, remoteCommandResponse = 1,
-
- PACKET_TRAINING_PING,
- PACKET_TRAINING_DATA,
-} PacketType;
-
-//Train button states
-typedef enum
-{
- TRAIN_NO_PRESS = 0,
- TRAIN_PRESSED_2S,
- TRAIN_PRESSED_5S,
-} TrainStates;
-TrainStates trainState = TRAIN_NO_PRESS;
-
-enum
-{ //#, Width - Computed with:
- // triggerWidth = 25
- // triggerUseWidthAsMultiplier = true
- // triggerEnable = 0xffffffff
- TRIGGER_ACK_PROCESSED = 0, // 0, 25us
- TRIGGER_DATA_SEND, // 1, 50us
- TRIGGER_RTR_2BYTE, // 2, 75us
- TRIGGER_RTR_255BYTE, // 3, 100us
-
- TRIGGER_LINK_SEND_PING, // 4, 125us
- TRIGGER_LINK_SENT_ACK_PACKET, // 5, 150 us
- TRIGGER_LINK_NOISE_TRIGGERED_HOP, // 6, 175us
- TRIGGER_LINK_NOISE_TRIGGERED_HOP_ACK_WAIT, // 7, 200us
- TRIGGER_LINK_NO_ACK_GIVEUP, // 8, 225us
- TRIGGER_LINK_PACKET_RESEND, // 9, 250us
- TRIGGER_LINK_DATA_PACKET, //10, 275us
- TRIGGER_LINK_PACKET_RECEIVED, //11, 300us
-
- TRIGGER_NOLINK_SEND_PING, //12, 325us
- TRIGGER_NOLINK_SEND_ACK_PACKET, //13, 350us
- TRIGGER_NOLINK_NOISE_TRIGGERED_HOP, //14, 375us
- TRIGGER_NOLINK_NO_ACK_GIVEUP, //15, 400us
- TRIGGER_NOLINK_IDENT_PACKET, //16, 425us
-
- TRIGGER_BROADCAST_DATA_PACKET, //17, 450us
- TRIGGER_BROADCAST_PACKET_RECEIVED, //18, 475us
-
- TRIGGER_RX_IN_PROGRESS, //19, 500us
- TRIGGER_LINK_BAD_PACKET, //20, 525us
- TRIGGER_LINK_DUPLICATE_PACKET, //21, 550us
- TRIGGER_LINK_CONTROL_PACKET, //22, 575us
-
- TRIGGER_TRAINING_BAD_PACKET, //23, 600us
- TRIGGER_TRAINING_CONTROL_PACKET, //24, 625us
- TRIGGER_TRAINING_DATA_PACKET, //25, 650us
- TRIGGER_TRAINING_NO_ACK, //26, 675us
-
- TRIGGER_COMMAND_CONTROL_PACKET, //27, 700us
- TRIGGER_COMMAND_CONTROL_PACKET_ACK, //28, 725us
- TRIGGER_COMMAND_DATA_PACKET_ACK, //29, 750us
- TRIGGER_COMMAND_PACKET_RECEIVED, //30, 775us
- TRIGGER_COMMAND_SENT_ACK_PACKET, //31, 800us
- TRIGGER_COMMAND_PACKET_RESEND, //32, 825us
- TRIGGER_PACKET_COMMAND_DATA, //33, 850us
-};
-
-//Control where to print command output
-typedef enum
-{
- PRINT_TO_SERIAL = 0,
- PRINT_TO_RF,
-} PrinterEndpoints;
-PrinterEndpoints printerEndpoint = PRINT_TO_SERIAL;
-
-
-struct ControlTrailer
-{
- uint8_t resend : 1;
- uint8_t ack : 1;
- uint8_t remoteCommand : 1;
- uint8_t remoteCommandResponse : 1;
- uint8_t train : 1;
- uint8_t filler : 3;
-};
-struct ControlTrailer receiveTrailer;
-struct ControlTrailer responseTrailer;
-
-//These are all the settings that can be set on Serial Terminal Radio. It's recorded to NVM.
-typedef struct struct_settings {
- uint16_t sizeOfSettings = 0; //sizeOfSettings **must** be the first entry and must be int
- uint16_t strIdentifier = LRS_IDENTIFIER; // strIdentifier **must** be the second entry
-
- uint8_t escapeCharacter = '+';
- uint8_t maxEscapeCharacters = 3; //Number of characters needed to enter command mode
- uint8_t responseDelayDivisor = 4; //Add on to max response time after packet has been sent. Factor of 2. 8 is ok. 4 is good. A smaller number increases the delay.
-
- uint32_t serialSpeed = 57600; //Default to 57600bps to match RTK Surveyor default firmware
- uint32_t airSpeed = 4800; //Default to ~523 bytes per second to support RTCM. Overrides spread, bandwidth, and coding
- uint8_t netID = 192; //Both radios must share a network ID
- bool pointToPoint = true; //Receiving unit will check netID and ACK. If set to false, receiving unit doesn't check netID or ACK.
- bool encryptData = true; //AES encrypt each packet
- uint8_t encryptionKey[16] = { 0x37, 0x78, 0x21, 0x41, 0xA6, 0x65, 0x73, 0x4E, 0x44, 0x75, 0x67, 0x2A, 0xE6, 0x30, 0x83, 0x08 };
- bool dataScrambling = false; //Use IBM Data Whitening to reduce DC bias
- uint8_t radioBroadcastPower_dbm = 30; //Transmit power in dBm. Max is 30dBm (1W), min is 14dBm (25mW).
- float frequencyMin = 902.0; //MHz
- float frequencyMax = 928.0; //MHz
- uint8_t numberOfChannels = 50; //Divide the min/max freq band into this number of channels and hop between.
- bool frequencyHop = true; //Hop between frequencies to avoid dwelling on any one channel for too long
- uint16_t maxDwellTime = 400; //Max number of ms before hopping (if enabled). Useful for configuring radio to be within regulator limits (FCC = 400ms max)
- float radioBandwidth = 500.0; //kHz 125/250/500 generally. We need 500kHz for higher data.
- uint8_t radioSpreadFactor = 9; //6 to 12. Use higher factor for longer range.
- uint8_t radioCodingRate = 8; //5 to 8. Higher coding rates ensure less packets dropped.
- uint8_t radioSyncWord = 18; //18 = 0x12 is default for custom/private networks. Different sync words does *not* guarantee a remote radio will not get packet.
- uint16_t radioPreambleLength = 8; //Number of symbols. Different lengths does *not* guarantee a remote radio privacy. 8 to 11 works. 8 to 15 drops some. 8 to 20 is silent.
- uint8_t frameSize = MAX_PACKET_SIZE - 2; //Send batches of bytes through LoRa link, max (255 - control trailer) = 253.
- uint16_t serialTimeoutBeforeSendingFrame_ms = 50; //Send partial buffer if time expires
- bool debug = false; //Print basic events: ie, radio state changes
- bool echo = false; //Print locally inputted serial
- uint16_t heartbeatTimeout = 5000; //ms before sending ping to see if link is active
- bool flowControl = false; //Enable the use of CTS/RTS flow control signals
- bool autoTuneFrequency = false; //Based on the last packets frequency error, adjust our next transaction frequency
- bool displayPacketQuality = false; //Print RSSI, SNR, and freqError for received packets
- uint8_t maxResends = 2; //Attempt resends up to this number.
- bool sortParametersByName = false; //Sort the parameter list (ATI0) by parameter name
- bool printParameterName = false; //Print the parameter name in the ATSx? response
- bool printFrequency = false; //Print the updated frequency
- bool debugRadio = false; //Print radio info
- bool debugStates = false; //Print state changes
- bool debugTraining = false; //Print training info
- bool debugTrigger = false; //Print triggers
- bool usbSerialWait = false; //Wait for USB serial initialization
- bool printRfData = false; //Print RX and TX data
- bool printPktData = false; //Print data, before encryption and after decryption
- bool verifyRxNetID = false; //Verify RX netID value when not operating in point-to-point mode
- uint8_t triggerWidth = 25; //Trigger width in microSeconds or multipler for trigger width
- bool triggerWidthIsMultiplier = true; //Use the trigger width as a multiplier
- uint32_t triggerEnable = 0xffffffff; //Determine which triggers are enabled: 31 - 0
- uint32_t triggerEnable2 = 0xffffffff; //Determine which triggers are enabled: 63 - 32
- bool debugReceive = false; //Print receive processing
- bool debugTransmit = false; //Print transmit processing
- bool printTxErrors = false; //Print any transmit errors
- bool useV2 = false; //Use the V2 protocol
- bool printTimestamp = false; //Print a timestamp: days hours:minutes:seconds.milliseconds
-} Settings;
-Settings settings;
-
-//Monitor which devices on the device are on or offline.
-struct struct_online {
- bool radio = false;
- bool eeprom = false;
-} online;
-
-#include //Click here to get the library: http://librarymanager/All#RadioLib v5.1.0
-
-typedef void (* ARCH_BEGIN_BOARD)();
-typedef void (* ARCH_BEGIN_SERIAL)(uint16_t serialSpeed);
-typedef void (* ARCH_BEGIN_WDT)();
-typedef void (* ARCH_EEPROM_BEGIN)();
-typedef void (* ARCH_EEPROM_COMMIT)();
-typedef void (* ARCH_PET_WDT)();
-typedef Module * (* ARCH_RADIO)();
-typedef bool (* ARCH_SERIAL_AVAILABLE)();
-typedef void (* ARCH_SERIAL_FLUSH)();
-typedef void (* ARCH_SERIAL_PRINT)(const char * value);
-typedef uint8_t (* ARCH_SERIAL_READ)();
-typedef void (* ARCH_SERIAL_WRITE)(uint8_t value);
-typedef void (* ARCH_SYSTEM_RESET)();
-typedef void (* ARCH_UNIQUE_ID)(uint32_t * unique128_BitID);
-
-typedef struct _ARCH_TABLE
-{
- ARCH_BEGIN_BOARD beginBoard; //Initialize the board
- ARCH_BEGIN_SERIAL beginSerial; //Finish initializing the serial port
- ARCH_BEGIN_WDT beginWDT; //Initialize the watchdog timer
- ARCH_EEPROM_BEGIN eepromBegin; //Start an EEPROM operation
- ARCH_EEPROM_COMMIT eepromCommit;//Done with the EEPROM operation
- ARCH_PET_WDT petWDT; //Reset the expiration time for the WDT
- ARCH_RADIO radio; //Initialize the radio
- ARCH_SERIAL_AVAILABLE serialAvailable; //Determine if serial data is available
- ARCH_SERIAL_FLUSH serialFlush; //Flush the serial port
- ARCH_SERIAL_PRINT serialPrint; //Print the specified string value
- ARCH_SERIAL_READ serialRead; //Read a byte from the serial port
- ARCH_SERIAL_WRITE serialWrite; //Print the specified character
- ARCH_SYSTEM_RESET systemReset; //Reset the system
- ARCH_UNIQUE_ID uniqueID; //Get the 128 bit unique ID value
-} ARCH_TABLE;
diff --git a/Firmware/Test_Sketches/Flow_Control/Arch_SAMD.h b/Firmware/Test_Sketches/Flow_Control/Arch_SAMD.h
new file mode 100644
index 00000000..659ad130
--- /dev/null
+++ b/Firmware/Test_Sketches/Flow_Control/Arch_SAMD.h
@@ -0,0 +1,122 @@
+#if defined(ARDUINO_ARCH_SAMD)
+#ifndef __SAMD_H__
+
+/*
+ Data flow
+ +--------------+
+ | SAMD |
+ | |
+ TTL Serial <-->| Serial1 | +--------------+
+ | SPI |<----->| SX1276 Radio |<---> Antenna
+ USB Serial <-->| Serial | +--------------+ ^
+ +--------------+ |
+ |
+ +--------------+ |
+ | SAMD | |
+ | | |
+ TTL Serial <-->| Serial1 | +--------------+ V
+ | SPI |<----->| SX1276 Radio |<---> Antenna
+ USB Serial <-->| Serial | +--------------+
+ +--------------+
+
+ +--------------+
+ | SAMD |
+ | |
+ | PB02 A5 |---> rxLED
+ | PB23 31 |---> txLED
+ | |
+ | PA07 9 |---> rssi4LED
+ | PA06 8 |---> rssi3LED
+ | PA05 A4 |---> rssi2LED
+ | PA04 A3 |---> rssi1LED
+ | |
+ USB_D- <------------->| 28 PA24 |
+ USB_D+ <------------->| 29 PA25 |
+ | |
+ | PA15 5 |---> cs -----> LORA_CS/
+ | PA17 13 |---> SCLK ---> SPI_SCK
+ | PA16 11 |---> MOSI ---> SPI_PICO
+ | PA19 12 |<--- MISO ---> SPI_POCI
+ | |
+ RTS-0 <------ rts <---| 38 PA13 |
+ TX-0 <------- tx <----| 0 PA10 |
+ RX-I_LV <---- rx ---->| 1 PA11 |
+ CTS-I_LV <--- cts --->| 30 PB22 |
+ | |
+ | PA09 3 |---> rxen ---> LORA_RXEN
+ | PA14 2 |---> txen ---> LORA_TXEN
+ | |
+ | PA18 10 |<--- dio1 <--- LORA_D1 (Freq Change)
+ | PA21 7 |<--- dio0 <--- LORA_D0 (TX Done)
+ | |
+ | PA20 6 |---> rst ----> LORA_RST/
+ | |
+ | PA23 21 |---> SCL
+ | PA22 20 |---> SDA
+ +--------------+
+*/
+
+void samdBeginBoard()
+{
+ pin_cts = 30;
+ pin_rts = 38;
+ pin_txLED = 31;
+ pin_rxLED = A5;
+
+ //Flow control
+ pinMode(pin_rts, OUTPUT);
+ digitalWrite(pin_rts, INVERT_RTS_CTS ? HIGH : LOW); //Don't give me more
+
+ pinMode(pin_cts, INPUT_PULLUP);
+
+ //LEDs
+ pinMode(pin_txLED, OUTPUT);
+ digitalWrite(pin_txLED, LOW);
+ pinMode(pin_rxLED, OUTPUT);
+ digitalWrite(pin_rxLED, LOW);
+}
+
+void samdBeginSerial(uint16_t serialSpeed)
+{
+ //Wait for serial to come online for debug printing
+ SerialUSB.begin(serialSpeed);
+ while (!SerialUSB);
+
+ Serial1.begin(serialSpeed);
+}
+
+bool samdSerialAvailable()
+{
+ return (SerialUSB.available() || Serial1.available());
+}
+
+void samdSerialFlush()
+{
+ SerialUSB.flush();
+ Serial1.flush();
+}
+
+void samdSerialPrint(const char * value)
+{
+ SerialUSB.print(value);
+ Serial1.print(value);
+}
+
+uint8_t samdSerialRead()
+{
+ byte incoming = 0;
+ if (SerialUSB.available())
+ incoming = SerialUSB.read();
+ else if (Serial1.available())
+ incoming = Serial1.read();
+ return (incoming);
+}
+
+void samdSerialWrite(uint8_t value)
+{
+ SerialUSB.write(value);
+ Serial1.write(value);
+}
+
+#endif //__SAMD_H__
+#endif //ARDUINO_ARCH_SAMD
diff --git a/Firmware/Test_Sketches/Flow_Control/Flow_Control.ino b/Firmware/Test_Sketches/Flow_Control/Flow_Control.ino
new file mode 100644
index 00000000..3736e3f6
--- /dev/null
+++ b/Firmware/Test_Sketches/Flow_Control/Flow_Control.ino
@@ -0,0 +1,95 @@
+/*
+ October 26 2022
+ SparkFun Electronics
+ Lee Leahy
+
+ Verify flow control operation
+
+ Compiled with Arduino v1.8.15
+*/
+
+#define UNUSED(x) (void)(x)
+
+#define INVERT_RTS_CTS 1
+
+//Hardware connections
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//These pins are set in beginBoard()
+#define PIN_UNDEFINED 255
+
+uint8_t pin_rts = PIN_UNDEFINED;
+uint8_t pin_cts = PIN_UNDEFINED;
+uint8_t pin_txLED = PIN_UNDEFINED;
+uint8_t pin_rxLED = PIN_UNDEFINED;
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Global variables - Serial
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Buffer to store bytes incoming from serial before broadcasting over LoRa
+uint8_t serialTransmitBuffer[1024 * 1]; //Bytes received from RF waiting to be printed out UART. Buffer up to 1s of bytes at 4k
+
+uint16_t txHead = 0;
+uint16_t txTail = 0;
+
+//When RTS is asserted, host says it's ok to send data
+bool rtsAsserted;
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+/* Data Flow
+
+ USB or UART
+ |
+ | Flow control: RTS for UART
+ | Off: Buffer full
+ | On: Buffer drops below half full
+ V
+ serialTransmitBuffer
+ |
+ | Flow control: CTS for UART
+ |
+ V
+ USB or UART
+
+*/
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//Architecture variables
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+#include "Arch_SAMD.h"
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+void setup()
+{
+ samdBeginSerial(57600);
+ samdBeginBoard();
+ randomSeed(5);
+
+ //Enable the flow of data from the remote serial port into the SAMD
+ updateRTS(true);
+}
+
+void loop()
+{
+ updateSerial(); //Store incoming and print outgoing
+}
+
+void systemPrint(int value)
+{
+ char string[20];
+ sprintf(string, "%d", value);
+ SerialUSB.print(string);
+}
+
+void systemPrint(const char * string)
+{
+ SerialUSB.print(string);
+}
+
+void systemPrintln()
+{
+ SerialUSB.print("\r\n");
+}
diff --git a/Firmware/Test_Sketches/Flow_Control/Serial.ino b/Firmware/Test_Sketches/Flow_Control/Serial.ino
new file mode 100644
index 00000000..3e7020d0
--- /dev/null
+++ b/Firmware/Test_Sketches/Flow_Control/Serial.ino
@@ -0,0 +1,132 @@
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Serial RX - Data arriving at the USB or serial port
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Returns true if CTS is asserted (host says it's ok to send data)
+bool isCTS()
+{
+ return (digitalRead(pin_cts) == (INVERT_RTS_CTS ? LOW : HIGH));
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Serial TX - Data being sent to the USB or serial port
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//Return number of bytes sitting in the serial transmit buffer
+uint16_t availableTXBytes()
+{
+ if (txHead >= txTail)
+ return (txHead - txTail);
+ return (sizeof(serialTransmitBuffer) - txTail + txHead);
+}
+
+//Returns true if CTS is asserted (host says it's ok to send data)
+void updateRTS(bool assertRTS)
+{
+ rtsAsserted = assertRTS;
+ digitalWrite(pin_rts, assertRTS ^ INVERT_RTS_CTS);
+}
+
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+//Move serial data through the system
+//=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=
+
+//See if there's any serial from the remote radio that needs printing
+//Record any characters to the receive buffer
+//Scan for escape characters
+void updateSerial()
+{
+ bool bufferFull;
+ static uint32_t bufferFullCount;
+ static bool copyStarted;
+ static uint32_t delayMillis;
+ int x;
+ static uint32_t lastTime;
+ static uint32_t totalDelayMillis;
+
+ //Determine if bytea are available for transmission
+ while (availableTXBytes() && isCTS() && ((millis() - lastTime) >= delayMillis))
+ {
+ //Account for the delay time.
+ lastTime = millis();
+ totalDelayMillis += delayMillis;
+ delayMillis = random(1, 15);
+ copyStarted = true;
+
+ //Turn on LED during serial transmissions
+ txLED(true);
+
+ //Send a byte to the host
+ samdSerialWrite(serialTransmitBuffer[txTail++]);
+ txTail %= sizeof(serialTransmitBuffer);
+
+ //Assert RTS when enough space is available
+ if (availableTXBytes() <= (sizeof(serialTransmitBuffer) / 2))
+ updateRTS(true); //Ok to send more
+
+ //Since the UART does not have RTS and CTS, prevent loss of serial data
+ //by sending one character at a time
+ samdSerialFlush();
+
+ //Turn off LED
+ txLED(false);
+ }
+
+ //Look for local incoming serial
+ if (samdSerialAvailable() && rtsAsserted)
+ {
+ do
+ {
+ rxLED(true); //Turn on LED during serial reception
+
+ //Deassert RTS when the buffer becomes full
+ if (availableTXBytes() >= (sizeof(serialTransmitBuffer) - 32))
+ {
+ updateRTS(false); //Don't give me more
+ bufferFullCount += 1;
+ }
+
+ //Get the next character
+ serialTransmitBuffer[txHead++] = samdSerialRead();
+ txHead %= sizeof(serialTransmitBuffer);
+
+ rxLED(false); //Turn off LED
+ } while (samdSerialAvailable() && rtsAsserted);
+ }
+
+ if (copyStarted && ((millis() - lastTime) >= (5 * 1000)))
+ {
+ copyStarted = false;
+ systemPrint("Delay time: ");
+ systemPrint(totalDelayMillis);
+ systemPrint(" mSec");
+ systemPrintln();
+ systemPrint("RX Buffer Full Count: ");
+ systemPrint(bufferFullCount);
+ systemPrintln();
+ bufferFullCount = 0;
+ totalDelayMillis = 0;
+ }
+}
+
+void txLED(bool illuminate)
+{
+ if (pin_txLED != PIN_UNDEFINED)
+ {
+ if (illuminate == true)
+ digitalWrite(pin_txLED, HIGH);
+ else
+ digitalWrite(pin_txLED, LOW);
+ }
+}
+
+void rxLED(bool illuminate)
+{
+ if (pin_rxLED != PIN_UNDEFINED)
+ {
+ if (illuminate == true)
+ digitalWrite(pin_rxLED, HIGH);
+ else
+ digitalWrite(pin_rxLED, LOW);
+ }
+}
diff --git a/Firmware/Tools/Command_Validation_Script.txt b/Firmware/Tools/Command_Validation_Script.txt
index 62ddaae4..aab75bc4 100644
--- a/Firmware/Tools/Command_Validation_Script.txt
+++ b/Firmware/Tools/Command_Validation_Script.txt
@@ -17,6 +17,24 @@ ati6
ati7
ati8
ati9
+ati10
+ati11
+ati12
+ati13
+ati14
+ati15
+ati16
+ati17
+ati18
+ati19
+ati20
+ati21
+ati22
+ati23
+ati24
+ati25
+ati26
+ati27
ati0
ats28=0
@@ -441,6 +459,6 @@ ats255?
ati0
-at&w
+at&f
atz
diff --git a/Firmware/Tools/RadioV2.c b/Firmware/Tools/RadioV2.c
new file mode 100644
index 00000000..18f40f40
--- /dev/null
+++ b/Firmware/Tools/RadioV2.c
@@ -0,0 +1,121 @@
+#include "settings.h"
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Constants
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+const char * frameTypeTable[] =
+{
+ "VC_HEARTBEAT",
+ "ADDRESS_BYTE",
+};
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Frames
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+void xmitVcHeartbeat(int8_t addr, uint8_t * id)
+{
+ txData = txBuffer;
+ *txData++ = FRAME_VC_HEARTBEAT;
+ *txData++ = 0; //Reserve for length
+ *txData++ = VC_BROADCAST;
+ *txData++ = addr;
+ memcpy(txData, id, UNIQUE_ID_BYTES);
+ txData += UNIQUE_ID_BYTES;
+ transmitDatagram((const struct sockaddr *)&broadcastAddr, sizeof(broadcastAddr));
+}
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Datagram Receive
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+FRAME_TYPE rcvDatagram()
+{
+ FRAME_TYPE frameType;
+ uint8_t length;
+
+ //Receive a datagram from the client
+ if (usingTerminal)
+ rxBytes = readLoRaSerial(rxBuffer, sizeof(rxBuffer));
+ else
+ {
+ remoteAddrLength = sizeof(remoteAddr);
+ memset(&remoteAddr, 0, remoteAddrLength);
+ rxBytes = recvfrom(radio, rxBuffer, sizeof(rxBuffer), MSG_WAITALL,
+ (struct sockaddr *) &remoteAddr, &remoteAddrLength);
+ if (rxBytes < 0)
+ {
+ perror("Failed call to recvfrom!");
+ exit(rxBytes);
+ }
+ }
+
+ //Remove the header
+ rxData = rxBuffer;
+ frameType = (FRAME_TYPE)*rxData++;
+ length = rxData[0];
+ destAddr = rxData[1];
+ srcAddr = rxData[2];
+
+ //Display the received data
+ printf("Received Frame: %d --> %d\n", srcAddr, destAddr);
+ printf("Header:\n");
+ printf(" FrameType: %s\n", frameTypeTable[frameType]);
+ printf(" Length: %d\n", length);
+ printf(" Destination Address: %d\n", destAddr);
+ printf(" Source Address: %d\n", srcAddr);
+ dumpBuffer(rxBuffer, rxBytes);
+ rxBytes -= 1;
+
+ //Return the frame type
+ return frameType;
+}
+
+void returnToReceiving()
+{
+}
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Datagram Transmit
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+void transmitDatagram(const struct sockaddr * addr, int addrLen)
+{
+ int bytesSent;
+ uint8_t * data;
+ FRAME_TYPE frameType;
+ uint8_t length;
+
+ //Get the buffer length
+ txBytes = txData - txBuffer;
+ length = txBytes - 1;
+ txBuffer[1] = length;
+
+ //Decode the frame
+ data = txBuffer;
+ frameType = (FRAME_TYPE)*data++;
+ length = *data++;
+ destAddr = *data++;
+ srcAddr = *data++;
+
+ //Display this datagram
+ printf("Transmitting Frame: %d --> %d\n", srcAddr, destAddr);
+ printf("Header:\n");
+ printf(" FrameType: %s\n", frameTypeTable[frameType]);
+ printf(" Length: %d\n", length);
+ printf(" Destination Address: %d\n", destAddr);
+ printf(" Source Address: %d\n", srcAddr);
+ dumpBuffer(txBuffer, txBytes);
+
+ //Send this datagram
+ if (usingTerminal)
+ bytesSent = write(radio, (const void *)txBuffer, txBytes);
+ else
+ bytesSent = sendto(radio, (const char *)txBuffer, txBytes, MSG_CONFIRM,
+ addr, addrLen);
+ if (bytesSent < 0)
+ perror("Failed to send datagram!");
+ else
+ datagramTimer = millis();
+}
diff --git a/Firmware/Tools/Results/Command_Validation_Results.txt b/Firmware/Tools/Results/Command_Validation_Results.txt
index 64a1916b..085e562c 100644
--- a/Firmware/Tools/Results/Command_Validation_Results.txt
+++ b/Firmware/Tools/Results/Command_Validation_Results.txt
@@ -8,16 +8,26 @@ ERROR
at?
Command summary:
AT? - Print the command summary
+ ATD - Display the debug settings
ATF - Enter training mode and return to factory defaults
+ ATG - Generate new netID and encryption key
ATI - Display the radio version
ATI? - Display the information commands
ATIn - Display system information
+ ATL - VC link reset
ATO - Exit command mode
+ ATP - Display probe trigger settings
ATSn=xxx - Set parameter n's value to xxx
ATSn? - Print parameter n's current value
ATT - Enter training mode
+ ATV - Display virtual circuit settings
ATX - Stop the training server
ATZ - Reboot the radio
+ AT-Param=xxx - Set parameter's value to xxx by name (Param)
+ AT-Param? - Print parameter's current value by name (Param)
+ AT-? - Display the setting values
+ AT&F - Restore factory settings
+ AT&W - Save current settings to NVM
ati?
ATI0 - Show user settable parameters
ATI1 - Show board variant
@@ -28,15 +38,33 @@ ati?
ATI6 - Display AES key
ATI7 - Show current FHSS channel
ATI8 - Display unique ID
+ ATI9 - Display the total datagrams sent
+ ATI10 - Display the total datagrams received
+ ATI11 - Display the total frames sent
+ ATI12 - Display the total frames received
+ ATI13 - Display the total bad frames received
+ ATI14 - Display the total duplicate frames received
+ ATI15 - Display the total lost TX frames
+ ATI16 - Display the maximum datagram size
+ ATI17 - Display the total link failures
+ ATI18 - Display the VC frames sent
+ ATI19 - Display the VC frames received
+ ATI20 - Display the VC messages sent
+ ATI21 - Display the VC messages received
+ ATI22 - Display the VC bad length received
+ ATI23 - Display the VC link failures
+ ATI24 - Display the VC details
+ ATI25 - Display the total insufficient buffer count
+ ATI26 - Display the total number of bad CRC frames
# Allow leading white space (space, tab, cr, lf)
ERROR
ati
OK
-SparkFun LoRaSerial SAMD21 1W 915MHz v1.1
+SparkFun LoRaSerial SAMD21 1W 915MHz v2.0
ati1
SparkFun LoRaSerial SAMD21 1W 915MHz
ati2
-1.1
+2.0
ati3
-157
ati4
@@ -50,6 +78,42 @@ ati7
ati8
75E1FA5B4A34555020312E340F2715FF
ati9
+Total datagrams sent: 102
+ati10
+Total datagrams received: 0
+ati11
+Total frames sent: 0
+ati12
+Total frames sent: 0
+ati13
+Total bad frames received: 0
+ati14
+Total duplicate frames received: 0
+ati15
+Total lost TX frames: 0
+ati16
+Maximum datagram size: 253
+ati17
+Total link failures: 0
+ati18
+VC 0 frames sent: 0
+ati19
+VC 0 frames received: 0
+ati20
+VC 0 messages sent: 0
+ati21
+VC 0 messages received: 0
+ati22
+VC 0 bad length received: 0
+ati23
+VC 0 link failures: 0
+ati24
+VC 0: Not valid!
+ati25
+Total insufficient buffer count: 0
+ati26
+Total number of bad CRC frames: 0
+ati27
ERROR
ati0
ATS0:SerialSpeed=57600
@@ -105,772 +169,702 @@ OK
ERROR
ats0=0
ERROR
-ats0=1
+at-SerialSpeed=1
ERROR
-ats0=40
+at-SerialSpeed=40
ERROR
-ats0=50
+at-SerialSpeed=50
ERROR
-ats0=110
+at-SerialSpeed=110
ERROR
-ats0=134
+at-SerialSpeed=134
ERROR
-ats0=150
+at-SerialSpeed=150
ERROR
-ats0=300
+at-SerialSpeed=300
ERROR
-ats0=400
+at-SerialSpeed=400
ERROR
-ats0=600
+at-SerialSpeed=600
ERROR
-ats0=1200
+at-SerialSpeed=1200
ERROR
-ats0=2400
+at-SerialSpeed=2400
OK
-ats0=4800
+at-SerialSpeed=4800
OK
-ats0=9600
+at-SerialSpeed=9600
OK
-ats0=14400
+at-SerialSpeed=14400
OK
-ats0=19200
+at-SerialSpeed=19200
OK
-ats0=28800
+at-SerialSpeed=28800
ERROR
-ats0=38400
+at-SerialSpeed=38400
OK
-ats0=57600
+at-SerialSpeed=57600
OK
-ats0=76800
+at-SerialSpeed=76800
ERROR
-ats0=115200
+at-SerialSpeed=115200
OK
-ats0=128000
+at-SerialSpeed=128000
ERROR
-ats0=230400
+at-SerialSpeed=230400
ERROR
-ats0=250000
+at-SerialSpeed=250000
ERROR
-ats0=256000
+at-SerialSpeed=256000
ERROR
-ats0=460800
+at-SerialSpeed=460800
ERROR
-ats0=500000
+at-SerialSpeed=500000
ERROR
-ats0=512000
+at-SerialSpeed=512000
ERROR
-ats0=576000
+at-SerialSpeed=576000
ERROR
-ats0=921600
+at-SerialSpeed=921600
ERROR
-ats0=1000000
+at-SerialSpeed=1000000
ERROR
-ats0=1843200
+at-SerialSpeed=1843200
ERROR
-ats0=2000000
+at-SerialSpeed=2000000
ERROR
-ats0=3000000
+at-SerialSpeed=3000000
ERROR
-ats0=3686400
+at-SerialSpeed=3686400
ERROR
-ats0=4000000
+at-SerialSpeed=4000000
ERROR
-ats0=57600
+at-SerialSpeed=57600
OK
-ats0?
+at-SerialSpeed?
57600
-# AirSpeed
+at-AirSpeed=1
ERROR
-ats1=1
-ERROR
-ats1=40
+at-AirSpeed=40
OK
-ats1=50
+at-AirSpeed=50
ERROR
-ats1=110
+at-AirSpeed=110
ERROR
-ats1=134
+at-AirSpeed=134
ERROR
-ats1=150
+at-AirSpeed=150
OK
-ats1=300
+at-AirSpeed=300
ERROR
-ats1=400
+at-AirSpeed=400
OK
-ats1=600
+at-AirSpeed=600
ERROR
-ats1=1200
+at-AirSpeed=1200
OK
-ats1=2400
+at-AirSpeed=2400
OK
-ats1=4800
+at-AirSpeed=4800
OK
-ats1=9600
+at-AirSpeed=9600
OK
-ats1=14400
+at-AirSpeed=14400
ERROR
-ats1=19200
+at-AirSpeed=19200
OK
-ats1=28800
+at-AirSpeed=28800
OK
-ats1=38400
+at-AirSpeed=38400
OK
-ats1=57600
+at-AirSpeed=57600
ERROR
-ats1=76800
+at-AirSpeed=76800
ERROR
-ats1=115200
+at-AirSpeed=115200
ERROR
-ats1=128000
+at-AirSpeed=128000
ERROR
-ats1=230400
+at-AirSpeed=230400
ERROR
-ats1=250000
+at-AirSpeed=250000
ERROR
-ats1=256000
+at-AirSpeed=256000
ERROR
-ats1=460800
+at-AirSpeed=460800
ERROR
-ats1=500000
+at-AirSpeed=500000
ERROR
-ats1=512000
+at-AirSpeed=512000
ERROR
-ats1=576000
+at-AirSpeed=576000
ERROR
-ats1=921600
+at-AirSpeed=921600
ERROR
-ats1=1000000
+at-AirSpeed=1000000
ERROR
-ats1=1843200
+at-AirSpeed=1843200
ERROR
-ats1=2000000
+at-AirSpeed=2000000
ERROR
-ats1=3000000
+at-AirSpeed=3000000
ERROR
-ats1=3686400
+at-AirSpeed=3686400
ERROR
-ats1=4000000
+at-AirSpeed=4000000
ERROR
-ats1=0
+at-AirSpeed=0
OK
-ats1?
+at-AirSpeed?
0
-# NetID
-ERROR
-ats2=0
-OK
-ats2=255
-OK
-ats2=192
+at-AlternateLedUsage=1
OK
-ats2?
-192
-# PointToPoint
+at-AlternateLedUsage=2
ERROR
-ats3=0
+at-AlternateLedUsage=0
OK
-ats3=2
-ERROR
-ats3=1
+at-AlternateLedUsage?
+0
+at-AutoTune=1
OK
-ats3?
-1
-# EncryptData
+at-AutoTune=2
ERROR
-ats4=0
+at-AutoTune=0
OK
-ats4=2
-ERROR
-ats4=1
+at-AutoTune?
+0
+at-AirSpeed=4800
+Warning: AirSpeed override of bandwidth, spread factor, and coding rate
OK
-ats4?
-1
-# EncryptionKey
-ERROR
-ats5=00112233445566778899aabbccddeeff
+at-Bandwidth=0
OK
-ats5?
-00112233445566778899AABBCCDDEEFF
-ats5=00112233445566778899aabbccddeef
+at-Bandwidth=10.4
+AirSpeed is overriding
ERROR
-ats5=00112233445566778899aabbccddeefff
+at-Bandwidth=15.6
+AirSpeed is overriding
ERROR
-ats5=00112233445566778899aabbccddeefg
+at-Bandwidth=20
+AirSpeed is overriding
ERROR
-ats5=37782141A665734E4475672AE6308308
-OK
-ats5?
-37782141A665734E4475672AE6308308
-# DataScrambling
+at-Bandwidth=31.25
+AirSpeed is overriding
ERROR
-ats6=1
-OK
-ats6=2
+at-Bandwidth=41.7
+AirSpeed is overriding
ERROR
-ats6=0
-OK
-ats6?
-0
-# TxPower
+at-Bandwidth=62.5
+AirSpeed is overriding
ERROR
-ats7=13
+at-Bandwidth=125
+AirSpeed is overriding
ERROR
-ats7=14
-OK
-ats7=31
+at-Bandwidth=250
+AirSpeed is overriding
ERROR
-ats7=30
-OK
-ats7?
-30
-# FrequencyMin
+at-Bandwidth=500
+AirSpeed is overriding
ERROR
-ats9=928
+at-AirSpeed=0
OK
-ats8=0
-ERROR
-ats8=928.1
+at-Bandwidth=0
ERROR
-ats8=928
+at-Bandwidth=10.4
OK
-ats8=927.9
+at-Bandwidth=15.6
OK
-ats8=901.9
-ERROR
-ats8=902
-OK
-ats8?
-902.000
-# FrequencyMax
-ERROR
-ats9=0
-ERROR
-ats9=901.9
-ERROR
-ats9=902
+at-Bandwidth=20.8
OK
-ats9=902.1
+at-Bandwidth=31.25
OK
-ats9=927.9
+at-Bandwidth=41.7
OK
-ats9=928.1
-ERROR
-ats9=928
+at-Bandwidth=62.5
OK
-ats9?
-928.000
-# NumberOfChannels
-ERROR
-ats10=0
-ERROR
-ats10=1
+at-Bandwidth=125
OK
-ats10=255
+at-Bandwidth=250
OK
-ats10=256
-ERROR
-ats10=50
+at-Bandwidth=500
OK
-ats10?
-50
-# FrequencyHop
+at-Bandwidth?
+500.00
+at-ClientRetryInterval=1
ERROR
-ats11=0
-OK
-ats11=2
+at-ClientRetryInterval=2
ERROR
-ats11=1
-OK
-ats11?
-1
-# MaxDwellTime
+at-ClientRetryInterval=0
ERROR
-ats12=9
+at-ClientRetryInterval?
ERROR
-ats12=10
-OK
-ats12=65535
+at-CmdVC=0
OK
-ast12=65536
-ERROR
-ats12=400
+at-CmdVC=7;
OK
-ats12?
-400
-# Bandwidth
+at-CmdVC=8;
ERROR
-ats1=4800
+at-CmdVC?
+7
+at-AirSpeed=4800
Warning: AirSpeed override of bandwidth, spread factor, and coding rate
OK
-ats13=0
-OK
-ats13=10.4
-AirSpeed is overriding
-ERROR
-ats13=15.6
+at-CodingRate=4
AirSpeed is overriding
ERROR
-ats13=20
+at-CodingRate=5
AirSpeed is overriding
ERROR
-ats13=31.25
+at-CodingRate=9
AirSpeed is overriding
ERROR
-ats13=41.7
+at-CodingRate=8
AirSpeed is overriding
ERROR
-ats13=62.5
-AirSpeed is overriding
-ERROR
-ats13=125
-AirSpeed is overriding
-ERROR
-ats13=250
-AirSpeed is overriding
-ERROR
-ats13=500
-AirSpeed is overriding
+at-AirSpeed=0
+OK
+at-CodingRate=4
ERROR
-ats1=0
+at-CodingRate=5
OK
-ats13=0
+at-CodingRate=9
ERROR
-ats13=10.4
+at-CodingRate=8
OK
-ats13=15.6
+at-CodingRate?
+8
+at-CopyDebug=1
OK
-ats13=20.8
+at-CopyDebug=2
+ERROR
+at-CopyDebug=0
OK
-ats13=31.25
+at-CopyDebug?
+0
+at-CopySerial=1
OK
-ats13=41.7
+at-CopySerial=2
+ERROR
+at-CopySerial=0
OK
-ats13=62.5
+at-CopySerial?
+0
+at-CopyTriggers=1
OK
-ats13=125
+at-CopyTriggers=2
+ERROR
+at-CopyTriggers=0
OK
-ats13=250
+at-CopyTriggers?
+0
+at-DataScrambling=1
OK
-ats13=500
+at-DataScrambling=2
+ERROR
+at-DataScrambling=0
OK
-ats13?
-500.00
-ats1=4800
-Warning: AirSpeed override of bandwidth, spread factor, and coding rate
+at-DataScrambling?
+0
+at-Debug=1
OK
-# SpreadFactor
-ERROR
-ats14=5
-AirSpeed is overriding
+at-Debug=2
ERROR
-ats14=6
-AirSpeed is overriding
-ERROR
-ats14=12
-AirSpeed is overriding
-ERROR
-ats14=13
-AirSpeed is overriding
-ERROR
-ats14=9
-AirSpeed is overriding
-ERROR
-ats1=0
+at-Debug=0
+OK
+at-Debug?
+0
+at-DebugDatagrams=1
OK
-ats14=5
+at-DebugDatagrams=2
ERROR
-ats14=6
+at-DebugDatagrams=0
OK
-ats14=12
+at-DebugDatagrams?
+0
+at-DebugRadio=1
OK
-ats14=13
+at-DebugRadio=2
ERROR
-ats14=9
+at-DebugRadio=0
OK
-ats14?
-9
-# CodingRate
-ERROR
-ats15=4
-ERROR
-ats15=5
+at-DebugRadio?
+0
+at-DebugStates=1
OK
-ats15=9
+at-DebugStates=2
ERROR
-ats15=8
+at-DebugStates=0
OK
-ats1=4800
-Warning: AirSpeed override of bandwidth, spread factor, and coding rate
+at-DebugStates?
+0
+at-DebugTraining=1
OK
-ats15=4
-AirSpeed is overriding
-ERROR
-ats15=5
-AirSpeed is overriding
-ERROR
-ats15=9
-AirSpeed is overriding
-ERROR
-ats15=8
-AirSpeed is overriding
+at-DebugTraining=2
ERROR
-ats15?
-8
-# SyncWord
-ERROR
-ats16=0
+at-DebugTraining=0
OK
-ats16=255
+at-DebugTraining?
+0
+at-DebugReceive=1
OK
-ats16=256
+at-DebugReceive=2
ERROR
-ats16=18
+at-DebugReceive=0
OK
-ats16?
-18
-# PreambleLength
+at-DebugReceive?
+0
+at-DebugTransmit=1
+OK
+at-DebugTransmit=2
ERROR
-ats17=5
+at-DebugTransmit=0
+OK
+at-DebugTransmit?
+0
+at-DisplayPacketQuality=1
+OK
+at-DisplayPacketQuality=2
ERROR
-ats17=6
+at-DisplayPacketQuality=0
OK
-ats17=255
+at-DisplayPacketQuality?
+0
+at-DisplayRealMillis=1
OK
-ats17=256
+at-DisplayRealMillis=2
+ERROR
+at-DisplayRealMillis=0
OK
-ats17=65535
+at-DisplayRealMillis?
+0
+at-Echo=1
OK
-ats17=65536
+at-Echo=2
ERROR
-ats17=8
+at-Echo=0
OK
-ats17?
-8
-# FrameSize
+at-Echo?
+0
+at-EnableCRC16=1
+OK
+at-EnableCRC16=2
ERROR
-ats18=15
+at-EnableCRC16=0
+OK
+at-EnableCRC16?
+0
+at-EncryptData=0
+OK
+at-EncryptData=2
ERROR
-ats18=16
+at-EncryptData=1
+OK
+at-EncryptData?
+1
+at-EncryptionKey=00112233445566778899aabbccddeeff
OK
-ats18=256
+at-EncryptionKey?
+00112233445566778899AABBCCDDEEFF
+at-EncryptionKey=00112233445566778899aabbccddeef
+ERROR
+at-EncryptionKey=00112233445566778899aabbccddeefff
ERROR
-ats18=255
+at-EncryptionKey=00112233445566778899aabbccddeefg
ERROR
-ats18=254
+at-EncryptionKey=37782141A665734E4475672AE6308308
OK
-ats18=253
+at-EncryptionKey?
+37782141A665734E4475672AE6308308
+at-FlowControl=1
OK
-ats18?
-253
-# FrameTimeout
+at-FlowControl=2
ERROR
-ats19=9
+at-FlowControl=0
+OK
+at-FlowControl?
+0
+at-FrameTimeout=9
ERROR
-ats19=10
+at-FrameTimeout=10
OK
-ats19=2000
+at-FrameTimeout=2000
OK
-ats19=2001
+at-FrameTimeout=2001
ERROR
-ats19=50
+at-FrameTimeout=50
OK
-ats19?
+at-FrameTimeout?
50
-# Debug
+at-FrequencyHop=0
+OK
+at-FrequencyHop=2
ERROR
-ats20=1
+at-FrequencyHop=1
OK
-ats20=2
+at-FrequencyHop?
+1
+at-FrequencyMin=0
+ERROR
+at-FrequencyMin=901.9
ERROR
-ats20=0
+at-FrequencyMin=902
OK
-ats20?
-0
-# Echo
+at-FrequencyMin=902.1
+OK
+at-FrequencyMin=927.9
+OK
+at-FrequencyMin=928.1
ERROR
-ats21=1
+at-FrequencyMin=928
OK
-ats21=2
+at-FrequencyMin?
+928.000
+at-FrequencyMin=928
+OK
+at-FrequencyMin=0
+ERROR
+at-FrequencyMin=928.1
ERROR
-ats21=0
+at-FrequencyMin=928
OK
-ats21?
-0
-# HeartBeatTimeout
+at-FrequencyMin=927.9
+OK
+at-FrequencyMin=901.9
ERROR
-ats22=249
+at-FrequencyMin=902
+OK
+at-FrequencyMin?
+902.000
+at-HeartBeatTimeout=249
ERROR
-ats22=250
+at-HeartBeatTimeout=250
OK
-ats22=65535
+at-HeartBeatTimeout=65535
OK
-ats22=65536
+at-HeartBeatTimeout=65536
ERROR
-ats22=5000
+at-HeartBeatTimeout=5000
OK
-ats22?
+at-HeartBeatTimeout?
5000
-# FlowControl
-ERROR
-ats23=1
+at-InvertCts=1
OK
-ats23=2
+at-InvertCts=2
ERROR
-ats23=0
+at-InvertCts=0
OK
-ats23?
+at-InvertCts?
0
-# AutoTune
-ERROR
-ats24=1
+at-InvertRts=1
OK
-ats24=2
+at-InvertRts=2
ERROR
-ats24=0
+at-InvertRts=0
OK
-ats24?
+at-InvertRts?
0
-# DisplayPacketQuality
+at-MaxDwellTime=9
ERROR
-ats25=1
+at-MaxDwellTime=10
OK
-ats25=2
-ERROR
-ats25=0
+at-MaxDwellTime=65535
OK
-ats25?
-0
-# MaxResends
+at-MaxDwellTime=65536
ERROR
-ats26=0
+at-MaxDwellTime=400
+OK
+at-MaxDwellTime?
+400
+at-MaxResends=0
OK
-ats26=255
+at-MaxResends=255
OK
-ats26=256
+at-MaxResends=256
ERROR
-ats26=2
+at-MaxResends=2
OK
-ats26?
+at-MaxResends?
2
-# SortParametersByName
-ERROR
-ats27=0
+at-NetID=0
OK
-ats27=2
-ERROR
-ats27=1
+at-NetID=255
OK
-ats27?
-1
-# ParameterName
-ERROR
-ats28=0
+at-NetID=192
OK
-ats28=2
+at-NetID?
+192
+at-NumberOfChannels=0
ERROR
-ats28=1
-PrintParameterName=1
+at-NumberOfChannels=1
OK
-ats28?
-PrintParameterName=1
-# PrintFrequency
-ERROR
-ats29=1
-PrintFrequency=1
+at-NumberOfChannels=255
OK
-ats29=2
+at-NumberOfChannels=256
ERROR
-ats29=0
-PrintFrequency=0
+at-NumberOfChannels=50
OK
-ats29?
-PrintFrequency=0
-# DebugRadio
-ERROR
-ats30=1
-DebugRadio=1
+at-NumberOfChannels?
+50
+at-OperatingMode=0
OK
-ats30=2
-ERROR
-ats30=0
-DebugRadio=0
+at-OperatingMode=2
OK
-ats30?
-DebugRadio=0
-# DebugStates
+at-OperatingMode=3
ERROR
-ats31=1
-DebugStates=1
+at-OperatingMode=1
OK
-ats31=2
-ERROR
-ats31=0
-DebugStates=0
+at-OperatingMode?
+1
+at-OverHeadtime=0
OK
-ats31?
-DebugStates=0
-# DebugTraining
-ERROR
-ats32=1
-DebugTraining=1
+at-OverHeadtime=1000
OK
-ats32=2
+at-OverHeadtime=1001
ERROR
-ats32=0
-DebugTraining=0
-OK
-ats32?
-DebugTraining=0
-# DebugTrigger
+at-OverHeadtime?
+1000
+at-PreambleLength=5
ERROR
-ats33=1
-DebugTrigger=1
+at-PreambleLength=6
OK
-ats33=2
-ERROR
-ats33=0
-DebugTrigger=0
+at-PreambleLength=255
OK
-ats33?
-DebugTrigger=0
-# UsbSerialWait
-ERROR
-ats34=1
-UsbSerialWait=1
+at-PreambleLength=256
OK
-ats34=2
-ERROR
-ats34=0
-UsbSerialWait=0
+at-PreambleLength=65535
OK
-ats34?
-UsbSerialWait=0
-# PrintRfData
+at-PreambleLength=65536
ERROR
-ats35=1
-PrintRfData=1
+at-PreambleLength=8
OK
-ats35=2
-ERROR
-ats35=0
-PrintRfData=0
+at-PreambleLength?
+8
+at-PrintFrequency=1
OK
-ats35?
-PrintRfData=0
-# PrintPktData
+at-PrintFrequency=2
ERROR
-ats36=1
-PrintPktData=1
+at-PrintFrequency=0
OK
-ats36=2
-ERROR
-ats36=0
-PrintPktData=0
+at-PrintFrequency?
+0
+at-PrintLinkUpDown=1
OK
-ats36?
-PrintPktData=0
-# VerifyRxNetID
+at-PrintLinkUpDown=2
ERROR
-ats37=1
-VerifyRxNetID=1
+at-PrintLinkUpDown=0
+OK
+at-PrintLinkUpDown?
+0
+at-PrintPktData=1
OK
-ats37=2
+at-PrintPktData=2
ERROR
-ats37=0
-VerifyRxNetID=0
+at-PrintPktData=0
OK
-ats37?
-VerifyRxNetID=0
-# TriggerWidth
+at-PrintPktData?
+0
+at-PrintRfData=1
+OK
+at-PrintRfData=2
ERROR
-ats38=0
+at-PrintRfData=0
+OK
+at-PrintRfData?
+0
+at-PrintTimestamp=1
+OK
+at-PrintTimestamp=2
ERROR
-ats38=1
-TriggerWidth=1
+at-PrintTimestamp=0
OK
-ats38=255
-TriggerWidth=255
+at-PrintTimestamp?
+0
+at-PrintTxErrors=1
OK
-ats38=256
+at-PrintTxErrors=2
ERROR
-ats38=25
-TriggerWidth=25
+at-PrintTxErrors=0
OK
-# TriggerWidthIsMultiplier
+at-PrintTxErrors?
+0
+at-RadioProtocolVersion=0
+ERROR
+at-RadioProtocolVersion=1
+ERROR
+at-RadioProtocolVersion=2
ERROR
-ats39=0
-TriggerWidthIsMultiplier=0
+at-RadioProtocolVersion=3
+ERROR
+at-RadioProtocolVersion?
+ERROR
+at-AirSpeed=4800
+Warning: AirSpeed override of bandwidth, spread factor, and coding rate
OK
-ats39=2
+at-SpreadFactor=5
+AirSpeed is overriding
+ERROR
+at-SpreadFactor=6
+AirSpeed is overriding
+ERROR
+at-SpreadFactor=12
+AirSpeed is overriding
+ERROR
+at-SpreadFactor=13
+AirSpeed is overriding
+ERROR
+at-SpreadFactor=9
+AirSpeed is overriding
ERROR
-ats39=1
-TriggerWidthIsMultiplier=1
+at-AirSpeed=0
OK
-# TriggerEnable: 31-0
+at-SpreadFactor=5
ERROR
-ats40=0
-TriggerEnable: 31-0=0
+at-SpreadFactor=6
OK
-ats40=4294967295
-TriggerEnable: 31-0=-1
+at-SpreadFactor=12
OK
-# TriggerEnable: 63-32
+at-SpreadFactor=13
ERROR
-ats41=0
-TriggerEnable: 63-32=0
+at-SpreadFactor=9
OK
-ats41=4294967295
-TriggerEnable: 63-32=-1
+at-SpreadFactor?
+9
+at-SyncWord=0
OK
-# DebugReceive
-ERROR
-ats42=1
-DebugReceive=1
+at-SyncWord=255
OK
-ats42=2
+at-SyncWord=256
ERROR
-ats42=0
-DebugReceive=0
+at-SyncWord=18
OK
-# DebugTransmit
-ERROR
-ats43=1
-DebugTransmit=1
+at-SyncWord?
+18
+at-TrainingKey=01020304050607080910111213141516
OK
-ats43=2
+at-TrainingKey=0102030405060708091011121314151
ERROR
-ats43=0
-DebugTransmit=0
-OK
-# PrintTxErrors
+at-TrainingKey=010203040506070809101112131415160
ERROR
-ats44=1
-PrintTxErrors=1
+at-TrainingKey?
+01020304050607080910111213141516
+at-TrainingServer=1
OK
-ats44=2
+at-TrainingServer=2
ERROR
-ats44=0
-PrintTxErrors=0
+at-TrainingServer=0
OK
-# useV2
-ERROR
-ats45=1
-UseV2=1
+at-TrainingServer?
+0
+at-TrainingTimeout=1
OK
-ats45=2
-ERROR
-ats45=0
-UseV2=0
+at-TrainingTimeout=255
OK
-# PrintTimestamp
+at-TrainingTimeout=0
ERROR
-ats46=1
-PrintTimestamp=1
+at-TrainingTimeout?
+255
+at-TriggerEnable_31-0=0
OK
-ats46=2
-ERROR
-ats46=0
-PrintTimestamp=0
+at-TriggerEnable_31-0=4294967295
OK
# Invalid commands
ERROR
@@ -934,3 +928,5 @@ at&w
OK
atz
OK
+LRS
+LRS Setup Complete
diff --git a/Firmware/Tools/Sockets.c b/Firmware/Tools/Sockets.c
new file mode 100644
index 00000000..7d458e2b
--- /dev/null
+++ b/Firmware/Tools/Sockets.c
@@ -0,0 +1,56 @@
+#include "settings.h"
+
+int openSocket()
+{
+ const int broadcastEnable = 1;
+ const int non_blocking = 1;
+ int status;
+
+ //Open the socket
+ radio = socket(AF_INET, SOCK_DGRAM, 0);
+ if (radio < 0)
+ {
+ status = errno;
+ perror("Failed to open the socket!");
+ return status;
+ }
+
+ //Set the broadcast IPv4 address
+ memset(&broadcastAddr, 0, sizeof(broadcastAddr));
+ broadcastAddr.sin_family = AF_INET;
+ broadcastAddr.sin_addr.s_addr = BROADCAST_IPV4_ADDRESS;
+ broadcastAddr.sin_port = htons(PORT);
+
+ //Enable reception via any IPv4 address
+ memset(&localAddr, 0, sizeof(localAddr));
+ localAddr.sin_family = AF_INET;
+ localAddr.sin_addr.s_addr = INADDR_ANY;
+ localAddr.sin_port = htons(PORT);
+
+ // Bind the socket with the server address
+ status = bind(radio, (const struct sockaddr *)&localAddr, sizeof(localAddr));
+ if (status < 0 )
+ {
+ perror("Failed to bind the socket!");
+ return status;
+ }
+
+ //Support broadcasting
+ status = setsockopt (radio, SOL_SOCKET, SO_BROADCAST, &broadcastEnable, sizeof(broadcastEnable));
+ if (status < 0)
+ {
+ perror("setsockopt failed");
+ close(radio);
+ return status;
+ }
+
+ //Set the socket to non-blocking
+ status = ioctl(radio, FIONBIO, (char *)&non_blocking);
+ if (status < 0)
+ {
+ perror("ioctl failed");
+ close(radio);
+ return status;
+ }
+ return 0;
+}
diff --git a/Firmware/Tools/States.c b/Firmware/Tools/States.c
new file mode 100644
index 00000000..9b3ca946
--- /dev/null
+++ b/Firmware/Tools/States.c
@@ -0,0 +1,143 @@
+#include "settings.h"
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Constants
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+const STATE_ENTRY stateList[] =
+{
+ {STATE_RESET, "RESET"}, // 0
+ {STATE_WAIT_TX_DONE, "STATE_WAIT_TX_DONE"}, // 1
+ {STATE_WAIT_RECEIVE, "STATE_WAIT_RECEIVE"}, // 2
+};
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Main loop
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+void loop()
+{
+ int8_t addressByte;
+ FRAME_TYPE frameType;
+
+ switch (state)
+ {
+ default:
+ printf("Unknown state");
+ while(1)
+ petWDT();
+ break;
+
+ case STATE_RESET:
+ if (settings.trainingServer)
+ //Reserve the server's address (0)
+ myAddr = idToAddressByte(VC_SERVER, myUniqueId);
+ else
+ //Unknown client address
+ myAddr = VC_UNASSIGNED;
+
+ //Start sending heartbeats
+ xmitVcHeartbeat(myAddr, myUniqueId);
+ changeState(STATE_WAIT_TX_DONE);
+ break;
+
+ case STATE_WAIT_TX_DONE:
+ returnToReceiving();
+ changeState(STATE_WAIT_RECEIVE);
+ break;
+
+ case STATE_WAIT_RECEIVE:
+ if (transactionComplete)
+ {
+ transactionComplete = false;
+
+ //Receive a datagram from the client
+ frameType = rcvDatagram();
+
+ /*
+ .------- rxData
+ |
+ V
+ +--------+------+-----+--- ... ---+
+ | Length | Dest | Src | Data |
+ +--------+------+-----+--- ... ---+
+ | |
+ |<----------- rxBytes ----------->|
+ */
+
+ //Process the datagram
+ switch(frameType)
+ {
+ default:
+ break;
+
+ case FRAME_VC_HEARTBEAT:
+ //Save our address
+ if ((myAddr == VC_UNASSIGNED) && (memcmp(myUniqueId, &rxData[3], UNIQUE_ID_BYTES) == 0))
+ {
+ myAddr = srcAddr;
+printf("myAddr: %d\n", myAddr);
+ }
+
+ //Translate the unique ID into an address byte
+ addressByte = idToAddressByte(srcAddr, &rxData[3]);
+
+ if (settings.trainingServer && (srcAddr == VC_UNASSIGNED) && (addressByte >= 0))
+ //Assign the address to the client
+ xmitVcHeartbeat(addressByte, &rxData[3]);
+
+ changeState(STATE_WAIT_TX_DONE);
+ break;
+
+ case FRAME_VC_DATA:
+ if ((destAddr != myAddr) && (destAddr != VC_BROADCAST))
+ returnToReceiving();
+ else
+ {
+ //place in serial output buffer
+ }
+ break;
+ }
+ }
+ //Process serial data length bytes at a time
+// else if ((serialAvailable() && (available data >= length byte))
+// {
+// if ((length <= maxFrameSize) && ((dest == broadcast) or (dest == cmd) or (link up for dest)))
+// {
+// if (dest == cmd)
+// {
+// Send to command processor
+// Package response with length, dest=myAddr, src=cmd
+// Place packaged response in output serial buffer
+// }
+// else if (dest == myAddr)
+// {
+// Place in output serial buffer
+// }
+// else
+// {
+// xmitVcData();
+// changeState(STATE_WAIT_TX_DONE);
+// }
+// }
+// else
+// {
+// //Discard the frame
+// }
+// }
+ else if ((millis() - datagramTimer) >= settings.heartbeatTimeout)
+ {
+printf("deltaTime: %d\n", millis() - datagramTimer);
+ //Send another heartbeat
+ xmitVcHeartbeat(myAddr, myUniqueId);
+ changeState(STATE_WAIT_TX_DONE);
+ }
+ break;
+ }
+}
+
+void changeState(int newState)
+{
+ printf("State: %s\n", stateList[newState].name);
+ state = newState;
+}
diff --git a/Firmware/Tools/System.c b/Firmware/Tools/System.c
new file mode 100644
index 00000000..34884261
--- /dev/null
+++ b/Firmware/Tools/System.c
@@ -0,0 +1,194 @@
+#include "settings.h"
+
+void defaultSettings(Settings * settings)
+{
+ settings->trainingServer = false;
+ settings->heartbeatTimeout = 5000;
+}
+
+void dumpBuffer(uint8_t * data, int length)
+{
+ char byte;
+ int bytes;
+ uint8_t * dataEnd;
+ uint8_t * dataStart;
+ const int displayWidth = 16;
+ int index;
+
+ dataStart = data;
+ dataEnd = &data[length];
+ while (data < dataEnd)
+ {
+ // Display the offset
+ printf(" 0x%02x: ", (unsigned int)(data - dataStart));
+
+ // Determine the number of bytes to display
+ bytes = dataEnd - data;
+ if (bytes > displayWidth)
+ bytes = displayWidth;
+
+ // Display the data bytes in hex
+ for (index = 0; index < bytes; index++)
+ printf(" %02x", *data++);
+
+ // Space over to the ASCII display
+ for (; index < displayWidth; index++)
+ printf(" ");
+ printf(" ");
+
+ // Display the ASCII bytes
+ data -= bytes;
+ for (index = 0; index < bytes; index++) {
+ byte = *data++;
+ printf("%c", ((byte < ' ') || (byte >= 0x7f)) ? '.' : byte);
+ }
+ printf("\n");
+ }
+}
+
+uint32_t millis()
+{
+ return currentTime;
+}
+
+int8_t idToAddressByte(int8_t srcAddr, uint8_t * id)
+{
+ int8_t index;
+ RESERVED_ADDRESS * addr;
+
+ //Determine if the address is already in the list
+ for (index = 0; index < MAX_CLIENT_ADDRESS; index++)
+ {
+ //Verify that an address is present
+ if ((freeAddresses & (1 << index)) == 0)
+ continue;
+
+ //Compare the unique ID values
+ if (memcmp(addressList[index]->uniqueId, id, UNIQUE_ID_BYTES) == 0)
+ {
+printf ("Address %d already assigned to ", index);
+for (int i = 0; i < UNIQUE_ID_BYTES; i++)
+printf("%02x", id[i]);
+printf("\n");
+ if ((linkUp & (1 << index)) == 0)
+ {
+ linkUp |= 1 << index;
+ printf("========== Link %d up ==========\n", srcAddr);
+ }
+ return index;
+ }
+ }
+
+ //Fill in clients that were already running
+ index = srcAddr;
+
+ //Only the server can assign the address bytes
+ if ((srcAddr == VC_UNASSIGNED) && (!settings.trainingServer))
+ return -1;
+
+ //Assign an address if necessary
+ if (srcAddr == VC_UNASSIGNED)
+ {
+ //Unknown client ID
+ //Determine if there is a free address
+ if (freeAddresses == (ADDRESS_MASK)(-1))
+ {
+ printf ("ERROR: Too many clients, no free addresses!\n");
+ return -2;
+ }
+
+ //Look for the next free address byte
+ for (index = 0; index < MAX_CLIENT_ADDRESS; index++)
+ if ((freeAddresses & (1 << index)) == 0)
+ break;
+
+printf ("Server assigning address %d to : ", index);
+for (int i = 0; i < UNIQUE_ID_BYTES; i++)
+printf("%02x", id[i]);
+printf("\n");
+ }
+
+ //Check for an address conflict
+ if (addressList[index])
+ {
+ printf("ERROR: Unknown ID with pre-assigned conflicting address: %d\n", srcAddr);
+ printf("Received ID: ");
+ for (int i = 0; i < UNIQUE_ID_BYTES; i++)
+ printf("%02x", id[i]);
+ printf("\n");
+ printf("Assigned ID: ");
+ for (int i = 0; i < UNIQUE_ID_BYTES; i++)
+ printf("%02x", addressList[srcAddr]->uniqueId[i]);
+ printf("\n");
+ return -3;
+ }
+
+ //Allocate the address structure
+ addr = malloc(sizeof(*addr));
+ if (!addr)
+ {
+ printf ("ERROR: No free memory, malloc of RESERVED_ADDRESS failed!\n");
+ return -4;
+ }
+
+ //Reserve this address
+ freeAddresses |= 1 << index;
+ addr->addressByte = index;
+ memcpy(&addr->uniqueId, id, UNIQUE_ID_BYTES);
+ addressList[index] = addr;
+
+ //Mark this link as up
+ linkUp |= 1 << index;
+ printf("========== Link %d up ==========\n", index);
+
+ //Returned the assigned address
+ return index;
+}
+
+void petWDT()
+{
+}
+
+int processData()
+{
+ int deltaMillis;
+ struct timeval start;
+ int status;
+ struct timeval stop;
+ struct timeval timeout;
+
+ //Initialize the fd_sets
+ FD_ZERO(&exceptfds);
+ FD_ZERO(&readfds);
+ FD_ZERO(&writefds);
+
+ //Implement the protocol
+ changeState(STATE_RESET);
+ gettimeofday(&start, NULL);
+ while (1)
+ {
+ //Set the timeout
+ timeout.tv_sec = 0;
+ timeout.tv_usec = 1000;
+
+ //Wait for receive data or timeout
+ FD_SET(radio, &readfds);
+ status = select(radio + 1, &readfds, &writefds, &exceptfds, &timeout);
+
+ //Update the milliseconds since started
+ gettimeofday(&stop, NULL);
+ deltaMillis = ((stop.tv_sec - start.tv_sec) * 1000000) + stop.tv_usec - start.tv_usec;
+ deltaMillis /= 1000;
+ if (deltaMillis)
+ {
+ currentTime += deltaMillis;
+ start = stop;
+ }
+
+ //Indicate receive interrupt
+ if (status == 1)
+ transactionComplete = 1;
+ loop();
+ }
+ return 0;
+}
diff --git a/Firmware/Tools/Terminal.c b/Firmware/Tools/Terminal.c
new file mode 100644
index 00000000..fa95b4d0
--- /dev/null
+++ b/Firmware/Tools/Terminal.c
@@ -0,0 +1,102 @@
+#include "settings.h"
+
+int openLoRaSerial(const char *terminal)
+{
+ struct termios params;
+ int status;
+
+ radio = open (terminal, O_RDWR);
+ if (radio < 0)
+ {
+ perror ("ERROR: Failed to open the terminal");
+ return errno;
+ }
+
+ if (tcgetattr(radio, ¶ms) != 0) {
+ perror("ERROR: tcgetattr failed!");
+ return errno;
+ }
+
+ //Initialize the terminal parameters
+ params.c_cflag &= ~(CSIZE | CSTOPB | PARENB);
+ params.c_cflag |= CS8 | CRTSCTS | CREAD | CLOCAL;
+
+ params.c_lflag &= ~(ICANON | ECHO | ECHOE | ECHONL | ISIG);
+
+ params.c_iflag &= ~(IXON | IXOFF | IXANY | IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL);
+
+ params.c_oflag &= ~(OPOST | ONLCR);
+
+ cfsetispeed(¶ms, B57600);
+ cfsetospeed(¶ms, B57600);
+
+ if (tcsetattr(radio, TCSANOW, ¶ms) != 0) {
+ perror("ERROR: tcsetattr failed!");
+ return errno;
+ }
+
+ usingTerminal = true;
+ return 0;
+}
+
+int readLoRaSerial(uint8_t * buffer, int bufferLength)
+{
+ int bytes;
+ int length;
+
+ //Read the frame type
+ bytes = read(radio, buffer, 1);
+ if (bytes < 0)
+ {
+ perror("Failed to read frame type!");
+ exit(bytes);
+ }
+ rxBytes = bytes;
+
+ //Read the length in bytes
+ bytes = read(radio, &buffer[rxBytes], 1);
+ if (bytes < 0)
+ {
+ perror("Failed to read length byte!");
+ exit(bytes);
+ }
+
+ //Get the length in bytes
+ length = buffer[rxBytes];
+ rxBytes += bytes;
+
+ //Read the length in bytes
+ while (length - rxBytes)
+ {
+ bytes = read(radio, &buffer[rxBytes], length - rxBytes);
+ if (bytes < 0)
+ {
+ perror("Failed to read remaining data!");
+ exit(bytes);
+ }
+ rxBytes += bytes;
+ }
+
+ return rxBytes;
+}
+
+int updateTerm(int fd)
+{
+ struct termios params;
+ int status;
+
+ if (tcgetattr(fd, ¶ms) != 0) {
+ perror("ERROR: STDIN tcgetattr failed!");
+ return errno;
+ }
+
+ //Initialize the terminal parameters
+ params.c_iflag &= ~(IXON | IXOFF | ISTRIP);
+
+ if (tcsetattr(fd, TCSANOW, ¶ms) != 0) {
+ perror("ERROR: STDIN tcsetattr failed!");
+ return errno;
+ }
+
+ return 0;
+}
diff --git a/Firmware/Tools/VcServerTest.c b/Firmware/Tools/VcServerTest.c
new file mode 100644
index 00000000..08cda76e
--- /dev/null
+++ b/Firmware/Tools/VcServerTest.c
@@ -0,0 +1,715 @@
+#define ADD_VC_STATE_NAMES_TABLE
+#include "settings.h"
+
+#define BUFFER_SIZE 2048
+#define INPUT_BUFFER_SIZE BUFFER_SIZE
+#define MAX_MESSAGE_SIZE 32
+#define STDIN 0
+#define STDOUT 1
+
+#define BREAK_LINKS_COMMAND "atb"
+#define GET_MY_VC_ADDRESS "atI11"
+#define GET_VC_STATUS "ata"
+#define LINK_RESET_COMMAND "atz"
+#define MY_VC_ADDRESS "myVc: "
+
+#define DEBUG_LOCAL_COMMANDS 0
+#define DEBUG_PC_TO_RADIO 0
+#define DEBUG_RADIO_TO_PC 0
+#define DISPLAY_COMMAND_COMPLETE 0
+#define DISPLAY_DATA_ACK 0
+#define DISPLAY_DATA_NACK 1
+#define DISPLAY_STATE_TRANSITION 0
+#define DISPLAY_UNKNOWN_COMMANDS 0
+#define DISPLAY_VC_STATE 0
+#define DUMP_RADIO_TO_PC 0
+#define SEND_ATC_COMMAND 1
+
+typedef struct _VIRTUAL_CIRCUIT
+{
+ int vcState;
+} VIRTUAL_CIRCUIT;
+
+bool commandStatus;
+bool findMyVc;
+int myVc = VC_UNASSIGNED;
+int remoteVc;
+uint8_t inputBuffer[INPUT_BUFFER_SIZE];
+uint8_t outputBuffer[VC_SERIAL_HEADER_BYTES + BUFFER_SIZE];
+int timeoutCount;
+VIRTUAL_CIRCUIT virtualCircuitList[MAX_VC];
+volatile bool waitingForCommandComplete;
+uint8_t remoteCommandVc;
+
+int cmdToRadio(uint8_t * buffer, int length)
+{
+ int bytesSent;
+ int bytesWritten;
+ VC_SERIAL_MESSAGE_HEADER header;
+
+ //Build the virtual circuit serial header
+ header.start = START_OF_VC_SERIAL;
+ header.radio.length = VC_RADIO_HEADER_BYTES + length;
+ header.radio.destVc = VC_COMMAND;
+ header.radio.srcVc = PC_COMMAND;
+
+ //Display the data being sent to the radio
+ if (DEBUG_PC_TO_RADIO)
+ {
+ dumpBuffer((uint8_t *)&header, VC_SERIAL_HEADER_BYTES);
+ dumpBuffer(buffer, length);
+ }
+ if (DEBUG_LOCAL_COMMANDS)
+ printf("Sending LoRaSerial command: %s\n", buffer);
+
+ //Send the header
+ bytesWritten = write(radio, (uint8_t *)&header, VC_SERIAL_HEADER_BYTES);
+ if (bytesWritten < (int)VC_SERIAL_HEADER_BYTES)
+ {
+ perror("ERROR: Write of header to radio failed!");
+ return -1;
+ }
+
+ //Send the message
+ bytesSent = 0;
+ while (bytesSent < length)
+ {
+ bytesWritten = write(radio, buffer, length);
+ if (bytesWritten < 0)
+ {
+ perror("ERROR: Write of data to radio failed!");
+ return bytesWritten;
+ }
+ bytesSent += bytesWritten;
+ }
+
+ //Return the amount of the buffer that was sent
+ return length;
+}
+
+int hostToRadio(uint8_t destVc, uint8_t * buffer, int length)
+{
+ int bytesSent;
+ int bytesWritten;
+ VC_SERIAL_MESSAGE_HEADER header;
+
+ //Build the virtual circuit serial header
+ header.start = START_OF_VC_SERIAL;
+ header.radio.length = VC_RADIO_HEADER_BYTES + length;
+ header.radio.destVc = destVc;
+ header.radio.srcVc = myVc;
+
+ //Display the data being sent to the radio
+ if (DEBUG_PC_TO_RADIO)
+ {
+ dumpBuffer((uint8_t *)&header, VC_SERIAL_HEADER_BYTES);
+ dumpBuffer(buffer, length);
+ }
+
+ //Send the header
+ bytesWritten = write(radio, (uint8_t *)&header, VC_SERIAL_HEADER_BYTES);
+ if (bytesWritten < (int)VC_SERIAL_HEADER_BYTES)
+ {
+ perror("ERROR: Write of header to radio failed!");
+ return -1;
+ }
+
+ //Send the message
+ bytesSent = 0;
+ while (bytesSent < length)
+ {
+ bytesWritten = write(radio, buffer, length);
+ if (bytesWritten < 0)
+ {
+ perror("ERROR: Write of data to radio failed!");
+ return bytesWritten;
+ }
+ bytesSent += bytesWritten;
+ }
+
+ //Return the amount of the buffer that was sent
+ return length;
+}
+
+int stdinToRadio()
+{
+ int bytesRead;
+ int bytesSent;
+ int bytesToSend;
+ int bytesWritten;
+ int length;
+ int maxfds;
+ int status;
+ struct timeval timeout;
+ static int index;
+
+ status = 0;
+ if (!waitingForCommandComplete)
+ {
+ if (remoteVc == VC_COMMAND)
+ {
+ do
+ {
+ do
+ {
+ //Read the console input data into the local buffer.
+ bytesRead = read(STDIN, &inputBuffer[index], 1);
+ if (bytesRead < 0)
+ {
+ perror("ERROR: Read from stdin failed!");
+ status = bytesRead;
+ break;
+ }
+ index += bytesRead;
+ } while (bytesRead && (inputBuffer[index - bytesRead] != '\n'));
+
+ //Check for end of data
+ if (!bytesRead)
+ break;
+
+ //Send this command the VC
+ bytesWritten = cmdToRadio(inputBuffer, index);
+ waitingForCommandComplete = true;
+ remoteCommandVc = myVc;
+ index = 0;
+ } while (0);
+ }
+ else
+ do
+ {
+ //Read the console input data into the local buffer.
+ bytesRead = read(STDIN, inputBuffer, BUFFER_SIZE);
+ if (bytesRead < 0)
+ {
+ perror("ERROR: Read from stdin failed!");
+ status = bytesRead;
+ break;
+ }
+
+ //Determine if this is a remote command
+ if ((remoteVc >= PC_REMOTE_COMMAND) && (remoteVc < THIRD_PARTY_COMMAND))
+ {
+ remoteCommandVc = remoteVc & VCAB_NUMBER_MASK;
+ waitingForCommandComplete = true;
+ }
+
+ //Send this data over the VC
+ bytesSent = 0;
+ while (bytesSent < bytesRead)
+ {
+ //Break up the data if necessary
+ bytesToSend = bytesRead - bytesSent;
+ if (bytesToSend > MAX_MESSAGE_SIZE)
+ bytesToSend = MAX_MESSAGE_SIZE;
+
+ //Send the data
+ bytesWritten = hostToRadio(remoteVc, &inputBuffer[bytesSent], bytesToSend);
+ if (bytesWritten < 0)
+ {
+ perror("ERROR: Write to radio failed!");
+ status = bytesWritten;
+ break;
+ }
+
+ //Account for the bytes written
+ bytesSent += bytesWritten;
+ }
+ } while (0);
+ }
+ return status;
+}
+
+int hostToStdout(uint8_t * data, uint8_t bytesToSend)
+{
+ uint8_t * buffer;
+ uint8_t * bufferEnd;
+ int bytesSent;
+ int bytesWritten;
+ static uint8_t compareBuffer[4 * BUFFER_SIZE];
+ static int offset;
+ int status;
+ int vcNumber;
+
+ //Locate myVc if necessary
+ if (findMyVc)
+ {
+ //Place the data into the compare buffer
+ buffer = compareBuffer;
+ memcpy(&compareBuffer[offset], data, bytesToSend);
+ offset += bytesToSend;
+ bufferEnd = &buffer[offset];
+
+ //Walk through the buffer
+ while (buffer < bufferEnd)
+ {
+ if ((strncmp((const char *)buffer, MY_VC_ADDRESS, strlen(MY_VC_ADDRESS)) == 0)
+ && (&buffer[strlen(MY_VC_ADDRESS) + 3] <= bufferEnd))
+ {
+ if ((sscanf((const char *)&buffer[strlen(MY_VC_ADDRESS)], "%d", &vcNumber) == 1)
+ && ((uint8_t)vcNumber < MAX_VC))
+ {
+ findMyVc = false;
+
+ //Set the local radio's VC number
+ myVc = (int8_t)vcNumber;
+ printf("myVc: %d\n", myVc);
+
+ //Request the status for all of the VCs
+ cmdToRadio((uint8_t *)GET_VC_STATUS, strlen(GET_VC_STATUS));
+ break;
+ }
+ }
+
+ //Skip to the end of the line
+ while ((buffer < bufferEnd) && (*buffer != '\n'))
+ buffer++;
+
+ if ((buffer < bufferEnd) && (*buffer == '\n'))
+ {
+ //Skip to the next line
+ while ((buffer < bufferEnd) && (*buffer == '\n'))
+ buffer++;
+
+ //Move this data to the beginning of the buffer
+ offset = bufferEnd - buffer;
+ memcpy(compareBuffer, buffer, offset);
+ buffer = compareBuffer;
+ bufferEnd = &buffer[offset];
+ }
+ }
+ }
+
+ //Write this data to stdout
+ bytesSent = 0;
+ status = 0;
+ while (bytesSent < bytesToSend)
+ {
+ bytesWritten = write(STDOUT, &data[bytesSent], bytesToSend - bytesSent);
+ if (bytesWritten < 0)
+ {
+ perror("ERROR: Write to stdout!");
+ status = bytesWritten;
+ break;
+ }
+
+ //Account for the bytes written
+ bytesSent += bytesWritten;
+ }
+ return status;
+}
+
+void radioToPcLinkStatus(VC_SERIAL_MESSAGE_HEADER * header, uint8_t length)
+{
+ char cmdBuffer[128];
+ int newState;
+ int previousState;
+ int srcVc;
+ VC_STATE_MESSAGE * vcMsg;
+
+ //Remember the previous state
+ srcVc = header->radio.srcVc;
+ previousState = virtualCircuitList[srcVc].vcState;
+ vcMsg = (VC_STATE_MESSAGE *)&header[1];
+
+ //Set the new state
+ newState = vcMsg->vcState;
+ virtualCircuitList[srcVc].vcState = newState;
+
+ //Display the state if requested
+ if (DISPLAY_STATE_TRANSITION)
+ printf("VC%d: %s --> %s\n", srcVc, vcStateNames[previousState], vcStateNames[newState]);
+ switch (newState)
+ {
+ default:
+ if (DISPLAY_VC_STATE)
+ printf("------- VC %d State %3d ------\n", srcVc, vcMsg->vcState);
+ break;
+
+ case VC_STATE_LINK_DOWN:
+ if (DISPLAY_VC_STATE)
+ printf("--------- VC %d DOWN ---------\n", srcVc);
+ break;
+
+ case VC_STATE_LINK_ALIVE:
+ //Upon transition to ALIVE, if is the server or the source VC matches the
+ //target VC or myVc, bring up the connection
+ if (SEND_ATC_COMMAND && (previousState != newState)
+ && ((myVc == VC_SERVER) || (srcVc == remoteVc) || (srcVc == myVc)))
+ {
+ //Select the VC to use
+ sprintf(cmdBuffer, "at-CmdVc=%d", srcVc);
+ cmdToRadio((uint8_t *)cmdBuffer, strlen(cmdBuffer));
+
+ //Bring up the VC connection to this remote system
+ strcpy(cmdBuffer, "atC");
+ cmdToRadio((uint8_t *)cmdBuffer, strlen(cmdBuffer));
+ }
+
+ if (DISPLAY_VC_STATE)
+ printf("-=--=--=- VC %d ALIVE =--=--=-\n", srcVc);
+ break;
+
+ case VC_STATE_SEND_UNKNOWN_ACKS:
+ if (DISPLAY_VC_STATE)
+ printf("-=--=-- VC %d ALIVE UA --=--=-\n", srcVc);
+ break;
+
+ case VC_STATE_WAIT_SYNC_ACKS:
+ if (DISPLAY_VC_STATE)
+ printf("-=--=-- VC %d ALIVE SA --=--=-\n", srcVc);
+ break;
+
+ case VC_STATE_WAIT_ZERO_ACKS:
+ if (DISPLAY_VC_STATE)
+ {
+ if (previousState == VC_STATE_CONNECTED)
+ printf("-=-=- VC %d DISCONNECTED -=-=-", srcVc);
+ printf("-=--=-- VC %d ALIVE ZA --=--=-\n", srcVc);
+ }
+ break;
+
+ case VC_STATE_CONNECTED:
+ if (DISPLAY_VC_STATE)
+ printf("======= VC %d CONNECTED ======\n", srcVc);
+ break;
+ }
+
+ //Clear the waiting for command complete if the link fails
+ if (waitingForCommandComplete && (newState != VC_STATE_CONNECTED)
+ && (srcVc == remoteCommandVc))
+ {
+ commandStatus = VC_CMD_ERROR;
+ waitingForCommandComplete = false;
+ }
+}
+
+void radioDataAck(uint8_t * data, uint8_t length)
+{
+ VC_DATA_ACK_NACK_MESSAGE * vcMsg;
+
+ vcMsg = (VC_DATA_ACK_NACK_MESSAGE *)data;
+ if (DISPLAY_DATA_ACK)
+ printf("ACK from VC %d\n", vcMsg->msgDestVc);
+}
+
+void radioDataNack(uint8_t * data, uint8_t length)
+{
+ VC_DATA_ACK_NACK_MESSAGE * vcMsg;
+
+ vcMsg = (VC_DATA_ACK_NACK_MESSAGE *)data;
+ if (DISPLAY_DATA_NACK)
+ printf("NACK from VC %d\n", vcMsg->msgDestVc);
+}
+
+void radioCommandComplete(uint8_t srcVc, uint8_t * data, uint8_t length)
+{
+ VC_COMMAND_COMPLETE_MESSAGE * vcMsg;
+
+ vcMsg = (VC_COMMAND_COMPLETE_MESSAGE *)data;
+ if (DISPLAY_COMMAND_COMPLETE)
+ printf("Command complete from VC %d: %s\n", srcVc,
+ (vcMsg->cmdStatus == VC_CMD_SUCCESS) ? "OK" : "ERROR");
+ commandStatus = vcMsg->cmdStatus;
+ waitingForCommandComplete = false;
+}
+
+int radioToHost()
+{
+ int bytesRead;
+ int bytesSent;
+ int bytesToRead;
+ int bytesToSend;
+ static uint8_t * data = outputBuffer;
+ static uint8_t * dataStart = outputBuffer;
+ static uint8_t * dataEnd = outputBuffer;
+ int8_t destAddr;
+ static VC_SERIAL_MESSAGE_HEADER * header = (VC_SERIAL_MESSAGE_HEADER *)outputBuffer;
+ int length;
+ int maxfds;
+ int status;
+ int8_t srcAddr;
+ struct timeval timeout;
+
+ status = 0;
+ do
+ {
+ //Read the virtual circuit header into the local buffer.
+ bytesToRead = &outputBuffer[sizeof(outputBuffer)] - dataEnd;
+ bytesRead = read(radio, dataEnd, bytesToRead);
+ if (bytesRead == 0)
+ break;
+ if (bytesRead < 0)
+ {
+ perror("ERROR: Read from radio failed!");
+ status = bytesRead;
+ break;
+ }
+ dataEnd += bytesRead;
+
+ //Display the data received from the radio
+ if (DUMP_RADIO_TO_PC)
+ if (bytesRead)
+ dumpBuffer(dataStart, dataEnd - dataStart);
+
+ //The data read is a mix of debug serial output and virtual circuit messages
+ //Any data before the VC_SERIAL_MESSAGE_HEADER is considered debug serial output
+ data = dataStart;
+ while ((data < dataEnd) && (*data != START_OF_VC_SERIAL))
+ data++;
+
+ //Process any debug data
+ length = data - dataStart;
+ if (length)
+ //Output the debug data
+ hostToStdout(dataStart, length);
+
+ //Determine if this is the beginning of a virtual circuit message
+ length = dataEnd - data;
+ if (length <= 0)
+ {
+ //Refill the empty buffer
+ dataStart = outputBuffer;
+ data = dataStart;
+ dataEnd = data;
+ break;
+ }
+
+ //This is the beginning of a virtual circuit message
+ //Move it to the beginning of the buffer to make things easier
+ if (data != outputBuffer)
+ memcpy(outputBuffer, data, length);
+ dataEnd = &outputBuffer[length];
+ dataStart = outputBuffer;
+ data = dataStart;
+
+ //Determine if the VC header is in the buffer
+ if (length < (int)VC_SERIAL_HEADER_BYTES)
+ //Need more data
+ break;
+
+ //Determine if the entire message is in the buffer
+ if (length < (header->radio.length + 1))
+ //Need more data
+ break;
+
+ //Set the beginning of the message
+ data = &outputBuffer[VC_SERIAL_HEADER_BYTES];
+ length = header->radio.length - VC_RADIO_HEADER_BYTES;
+
+ //Display the VC header and message
+ if (DEBUG_RADIO_TO_PC)
+ {
+ printf("VC Header:\n");
+ printf(" length: %d\n", header->radio.length);
+ printf(" destVc: %d\n", header->radio.destVc);
+ printf(" srcVc: %d\n", header->radio.srcVc);
+ if (length > 0)
+ dumpBuffer(data, length);
+ }
+
+ //------------------------------
+ //Process the message
+ //------------------------------
+
+ //Display link status
+ if (header->radio.destVc == PC_LINK_STATUS)
+ radioToPcLinkStatus(header, VC_SERIAL_HEADER_BYTES + length);
+
+ //Display remote command response
+ else if (header->radio.destVc == (PC_REMOTE_RESPONSE | myVc))
+ status = hostToStdout(data, length);
+
+ //Display command completion status
+ else if (header->radio.destVc == PC_COMMAND_COMPLETE)
+ radioCommandComplete(header->radio.srcVc, data, length);
+
+ //Display ACKs for transmitted messages
+ else if (header->radio.destVc == PC_DATA_ACK)
+ radioDataAck(data, length);
+
+ //Display NACKs for transmitted messages
+ else if (header->radio.destVc == PC_DATA_NACK)
+ radioDataNack(data, length);
+
+ //Display received messages
+ else if ((header->radio.destVc == myVc) || (header->radio.destVc == VC_BROADCAST))
+ {
+ //Output this message
+ status = hostToStdout(data, length);
+ }
+
+ //Unknown messages
+ else
+ {
+ if (DISPLAY_UNKNOWN_COMMANDS)
+ {
+ printf("Unknown message, VC Header:\n");
+ printf(" length: %d\n", header->radio.length);
+ printf(" destVc: %d\n", header->radio.destVc);
+ printf(" srcVc: %d\n", header->radio.srcVc);
+ if (length > 0)
+ dumpBuffer(data, length);
+ }
+ }
+
+ //Continue processing the rest of the data in the buffer
+ if (length > 0)
+ data += length;
+ dataStart = data;
+ } while(0);
+ return status;
+}
+
+int
+main (
+ int argc,
+ char ** argv
+)
+{
+ bool breakLinks;
+ fd_set currentfds;
+ int maxfds;
+ int numfds;
+ bool reset;
+ int status;
+ char * terminal;
+ struct timeval timeout;
+
+ maxfds = STDIN;
+ status = 0;
+ do
+ {
+ //Display the help text if necessary
+ if (argc < 3)
+ {
+ printf("%s terminal target_VC [options]\n", argv[0]);
+ printf("\n");
+ printf("terminal - Name or path to the terminal device for the radio\n");
+ printf("target_VC:\n");
+ printf(" Server: 0\n");
+ printf(" Client: 1 - %d\n", MAX_VC - 1);
+ printf(" Loopback: my_VC\n");
+ printf(" Broadcast: %d\n", VC_BROADCAST);
+ printf(" Command: %d\n", VC_COMMAND);
+ printf("Options:\n");
+ printf(" --reset Reset the LoRaSerial radio and break the links\n");
+ printf(" --break Use ATB command to break the links\n");
+ status = -1;
+ break;
+ }
+
+ //Get the path to the terminal
+ terminal = argv[1];
+
+ //Determine the remote VC address
+ if ((sscanf(argv[2], "%d", &remoteVc) != 1)
+ || ((remoteVc > PC_LINK_STATUS) && (remoteVc < VC_COMMAND)))
+ {
+ fprintf(stderr, "ERROR: Invalid target VC address, please use one of the following:\n");
+ if (myVc)
+ fprintf(stderr, " Server: 0\n");
+ fprintf(stderr, " Client: 1 - %d\n", MAX_VC - 1);
+ fprintf(stderr, " Loopback: my_VC\n");
+ fprintf(stderr, " Broadcast: %d\n", VC_BROADCAST);
+ fprintf(stderr, " Command: %d\n", VC_COMMAND);
+ status = -1;
+ break;
+ }
+
+ //Open the terminal
+ status = openLoRaSerial(terminal);
+ if (status)
+ break;
+
+ //Determine the options
+ reset = false;
+ if ((argc == 4) && (strcmp("--reset", argv[3]) == 0))
+ reset = true;
+
+ breakLinks = reset;
+ if ((argc == 4) && (strcmp("--break", argv[3]) == 0))
+ breakLinks = true;
+
+ //Reset the LoRaSerial radio if requested
+ if (reset)
+ {
+ //Delay a while to let the radio complete its reset operation
+ sleep(2);
+
+ //Break the links to this node
+ cmdToRadio((uint8_t *)LINK_RESET_COMMAND, strlen(LINK_RESET_COMMAND));
+
+ //Allow the device to reset
+ close(radio);
+ do
+ {
+ sleep(1);
+
+ //Open the terminal
+ status = openLoRaSerial(terminal);
+ } while (status);
+
+ //Delay a while to let the radio complete its reset operation
+ sleep(2);
+ }
+
+ //Break the links if requested
+ findMyVc = true;
+ if (breakLinks)
+ cmdToRadio((uint8_t *)BREAK_LINKS_COMMAND, strlen(BREAK_LINKS_COMMAND));
+
+ //Initialize the fd_sets
+ if (maxfds < radio)
+ maxfds = radio;
+ FD_ZERO(&readfds);
+ FD_SET(STDIN, &readfds);
+ FD_SET(radio, &readfds);
+
+ while (1)
+ {
+ //Set the timeout
+ timeout.tv_sec = 0;
+ timeout.tv_usec = 1000;
+
+ //Wait for receive data or timeout
+ memcpy((void *)¤tfds, (void *)&readfds, sizeof(readfds));
+ numfds = select(maxfds + 1, ¤tfds, NULL, NULL, &timeout);
+ if (numfds < 0)
+ {
+ perror("ERROR: select call failed!");
+ status = errno;
+ break;
+ }
+
+ //Check for timeout
+ if ((numfds == 0) && (timeoutCount++ >= 1000))
+ {
+ timeoutCount = 0;
+ if (myVc == VC_UNASSIGNED)
+ {
+ //Get myVc address
+ findMyVc = true;
+ cmdToRadio((uint8_t *)GET_MY_VC_ADDRESS, strlen(GET_MY_VC_ADDRESS));
+ }
+ }
+
+ //Determine if console input is available
+ if (FD_ISSET(STDIN, ¤tfds))
+ {
+ //Send the console input to the radio
+ status = stdinToRadio();
+ if (status)
+ break;
+ }
+
+ if (FD_ISSET(radio, ¤tfds))
+ {
+ //Process the incoming data from the radio
+ status = radioToHost();
+ if (status)
+ break;
+ }
+ }
+ } while (0);
+ return status;
+}
diff --git a/Firmware/Tools/makefile b/Firmware/Tools/makefile
new file mode 100644
index 00000000..808895d7
--- /dev/null
+++ b/Firmware/Tools/makefile
@@ -0,0 +1,63 @@
+######################################################################
+# makefile
+#
+# Builds the LoRaSerial support programs
+######################################################################
+
+##########
+# Source files
+##########
+
+EXECUTABLES += VcServerTest
+
+INCLUDES = settings.h ../LoRaSerial_Firmware/Virtual_Circuit_Protocol.h
+
+COMMON_LIB = Common_Lib.a
+
+LIB_OBJS = RadioV2.o Sockets.o States.o System.o Terminal.o
+
+##########
+# Buid tools and rules
+##########
+
+GCC = gcc
+CFLAGS = -flto -O3 -Wpedantic -pedantic-errors -Wall -Wextra -Werror -Wno-unused-variable -Wno-unused-parameter
+CC = $(GCC) $(CFLAGS)
+
+%.o: %.c $(INCLUDES)
+ $(CC) -c -o $@ $<
+
+%: %.c $(INCLUDES)
+ $(CC) $(CFLAGS) -o $@ $<
+
+##########
+# Buid all the sources - must be first
+##########
+
+.PHONY: all
+
+all: $(EXECUTABLES)
+
+##########
+# Buid the libraries
+##########
+
+$(COMMON_LIB): $(LIB_OBJS)
+ gcc --version
+ ar rvs $@ $^
+
+##########
+# Build the executables
+##########
+
+VcServerTest: VcServerTest.c $(COMMON_LIB)
+ $(CC) -o $@ $^
+
+########
+# Clean the build directory
+##########
+
+.PHONY: clean
+
+clean:
+ rm -f *.o *.a $(EXECUTABLES)
diff --git a/Firmware/Tools/settings.h b/Firmware/Tools/settings.h
new file mode 100644
index 00000000..8549f060
--- /dev/null
+++ b/Firmware/Tools/settings.h
@@ -0,0 +1,143 @@
+#ifndef __settings_h__
+#define __settings_h__
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "../LoRaSerial/Virtual_Circuit_Protocol.h"
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Defines
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+#define PORT 7272
+#define UNIQUE_ID_BYTES 16
+
+//#define false 0
+//#define true 1
+
+#define BROADCAST_IPV4_ADDRESS inet_addr("192.168.86.255") //INADDR_BROADCAST
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Enums
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+typedef enum {
+ FRAME_VC_HEARTBEAT = 0,
+ FRAME_VC_DATA,
+} FRAME_TYPE;
+
+typedef enum
+{
+ STATE_RESET = 0, // 0
+ STATE_WAIT_TX_DONE, // 1
+ STATE_WAIT_RECEIVE, // 2
+} STATE;
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Types
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+typedef uint8_t ADDRESS_MASK;
+
+typedef struct _RESERVED_ADDRESS
+{
+ uint8_t uniqueId[UNIQUE_ID_BYTES];
+ uint8_t addressByte;
+} RESERVED_ADDRESS;
+
+typedef struct _STATE_ENTRY
+{
+ STATE state;
+ const char * name;
+} STATE_ENTRY;
+
+typedef struct _SETTINGS
+{
+ uint32_t heartbeatTimeout;
+ bool trainingServer;
+} Settings;
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Globals
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+uint32_t currentTime;
+uint32_t datagramTimer;
+int8_t destAddr;
+fd_set exceptfds;
+int8_t myAddr;
+uint8_t myUniqueId[UNIQUE_ID_BYTES];
+int radio;
+fd_set readfds;
+uint8_t rxBuffer[255];
+int rxBytes;
+uint8_t * rxData;
+Settings settings;
+int8_t srcAddr;
+int state;
+bool transactionComplete;
+uint8_t txBuffer[255];
+int txBytes;
+uint8_t * txData;
+bool usingTerminal;
+fd_set writefds;
+
+struct sockaddr_in localAddr;
+struct sockaddr_in remoteAddr;
+struct sockaddr_in broadcastAddr;
+socklen_t remoteAddrLength;
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Address Byte Management
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+ADDRESS_MASK freeAddresses;
+ADDRESS_MASK linkUp;
+#define MAX_CLIENT_ADDRESS ((uint8_t)(sizeof(freeAddresses) * 8))
+RESERVED_ADDRESS * addressList[MAX_CLIENT_ADDRESS];
+
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+//Forward Declarations
+//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-
+
+//RadioV2
+FRAME_TYPE rcvDatagram();
+void returnToReceiving();
+void transmitDatagram(const struct sockaddr * addr, int addrLen);
+void xmitVcHeartbeat(int8_t addr, uint8_t * id);
+
+//Sockets
+int openSocket();
+
+//States
+void changeState(int newState);
+void loop();
+
+//Systems
+void defaultSettings(Settings * settings);
+void dumpBuffer(uint8_t * data, int length);
+int8_t idToAddressByte(int8_t srcAddr, uint8_t * id);
+uint32_t millis();
+void petWDT();
+int processData();
+
+//Terminal
+int openLoRaSerial(const char *ttyName);
+int readLoRaSerial(uint8_t * buffer, int bufferLength);
+int updateTerm(int fd);
+
+#endif // __settings_h__
diff --git a/Hardware/868MHz/SparkFun LoRaSerial 868MHz - 1W.brd b/Hardware/868MHz/SparkFun LoRaSerial 868MHz - 1W.brd
index 0f647ace..c8062aa5 100644
--- a/Hardware/868MHz/SparkFun LoRaSerial 868MHz - 1W.brd
+++ b/Hardware/868MHz/SparkFun LoRaSerial 868MHz - 1W.brd
@@ -10,8 +10,8 @@
-
-
+
+
@@ -21,34 +21,34 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
+
+
+
+
+
-
+
@@ -4997,7 +4997,7 @@ You are welcome to use this library for commercial purposes. For attribution, we
-
+
<b>SMA Antenna Connector</b><p>
This is a footprint for an edge mount RF antenna. Works pretty well with SMA type connectors but may also work with other edge mount RF connectors. Keep in mind, these edge mount connectors assume you are using a 0.062" (1.6mm) PCB thickness.
@@ -5061,8 +5061,6 @@ This is a footprint for an edge mount RF antenna. Works pretty well with SMA typ
-
-
@@ -6146,8 +6144,8 @@ These are the free and generally easy to produce 4-layer PCB design rules. You c
-
-
+
+
@@ -6486,6 +6484,124 @@ These are the free and generally easy to produce 4-layer PCB design rules. You c
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/Hardware/868MHz/SparkFun LoRaSerial 868MHz - 1W.sch b/Hardware/868MHz/SparkFun LoRaSerial 868MHz - 1W.sch
index a05c8420..e2fb8635 100644
--- a/Hardware/868MHz/SparkFun LoRaSerial 868MHz - 1W.sch
+++ b/Hardware/868MHz/SparkFun LoRaSerial 868MHz - 1W.sch
@@ -43484,7 +43484,7 @@ touch button, slider and wheel user interfaces.</p>
-
+
diff --git a/README.md b/README.md
index 812fcc29..7da3de9b 100644
--- a/README.md
+++ b/README.md
@@ -3,7 +3,7 @@ SparkFun LoRaSerial
[](https://www.sparkfun.com/products/19311)
-[*SparkFun GPS-RTK-SMA - ZED-F9P (GPS-19311)*](https://www.sparkfun.com/products/19311)
+[*SparkFun LoRaSerial Kit - 915MHz (WRL-19311)*](https://www.sparkfun.com/products/19311)
Head to the [LoRaSerial Product Manual](http://docs.sparkfun.com/SparkFun_LoRaSerial/) for technical documentation.