[SX127x] Update to 5.0.0

This commit is contained in:
jgromes 2021-11-14 11:42:12 +01:00
parent 6f744a8f13
commit 8c7b8a1b63
24 changed files with 1174 additions and 1168 deletions

View file

@ -36,7 +36,7 @@ void setup() {
// initialize SX1278 with default settings // initialize SX1278 with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.begin(); int state = radio.begin();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -51,11 +51,11 @@ void loop() {
// start scanning current channel // start scanning current channel
int state = radio.scanChannel(); int state = radio.scanChannel();
if (state == PREAMBLE_DETECTED) { if (state == RADIOLIB_PREAMBLE_DETECTED) {
// LoRa preamble was detected // LoRa preamble was detected
Serial.println(F("detected preamble!")); Serial.println(F("detected preamble!"));
} else if (state == CHANNEL_FREE) { } else if (state == RADIOLIB_CHANNEL_FREE) {
// no preamble was detected, channel is free // no preamble was detected, channel is free
Serial.println(F("channel is free!")); Serial.println(F("channel is free!"));

View file

@ -31,7 +31,7 @@ SX1278 radio = new Module(10, 2, 9, 3);
//SX1278 radio = RadioShield.ModuleA; //SX1278 radio = RadioShield.ModuleA;
// save state between loops // save state between loops
int scanState = ERR_NONE; int scanState = RADIOLIB_ERR_NONE;
void setup() { void setup() {
Serial.begin(9600); Serial.begin(9600);
@ -39,7 +39,7 @@ void setup() {
// initialize SX1278 with default settings // initialize SX1278 with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.begin(); int state = radio.begin();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -58,7 +58,7 @@ void setup() {
// start scanning the channel // start scanning the channel
Serial.print(F("[SX1278] Starting scan for LoRa preamble ... ")); Serial.print(F("[SX1278] Starting scan for LoRa preamble ... "));
state = radio.startChannelScan(); state = radio.startChannelScan();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -125,7 +125,7 @@ void loop() {
// start scanning current channel // start scanning current channel
int state = radio.startChannelScan(); int state = radio.startChannelScan();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));

View file

@ -36,7 +36,7 @@ void setup() {
// initialize SX1278 FSK modem with default settings // initialize SX1278 FSK modem with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.beginFSK(); int state = radio.beginFSK();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -61,7 +61,7 @@ void setup() {
uint8_t syncWord[] = {0x01, 0x23, 0x45, 0x67, uint8_t syncWord[] = {0x01, 0x23, 0x45, 0x67,
0x89, 0xAB, 0xCD, 0xEF}; 0x89, 0xAB, 0xCD, 0xEF};
state = radio.setSyncWord(syncWord, 8); state = radio.setSyncWord(syncWord, 8);
if (state != ERR_NONE) { if (state != RADIOLIB_ERR_NONE) {
Serial.print(F("Unable to set configuration, code ")); Serial.print(F("Unable to set configuration, code "));
Serial.println(state); Serial.println(state);
while (true); while (true);
@ -74,7 +74,7 @@ void setup() {
// setDataShapingOOK() to set the correct shaping! // setDataShapingOOK() to set the correct shaping!
state = radio.setOOK(true); state = radio.setOOK(true);
state = radio.setDataShapingOOK(1); state = radio.setDataShapingOOK(1);
if (state != ERR_NONE) { if (state != RADIOLIB_ERR_NONE) {
Serial.print(F("Unable to change modulation, code ")); Serial.print(F("Unable to change modulation, code "));
Serial.println(state); Serial.println(state);
while (true); while (true);
@ -95,11 +95,11 @@ void loop() {
0x89, 0xAB, 0xCD, 0xEF}; 0x89, 0xAB, 0xCD, 0xEF};
int state = radio.transmit(byteArr, 8); int state = radio.transmit(byteArr, 8);
*/ */
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1278] Packet transmitted successfully!")); Serial.println(F("[SX1278] Packet transmitted successfully!"));
} else if (state == ERR_PACKET_TOO_LONG) { } else if (state == RADIOLIB_ERR_PACKET_TOO_LONG) {
Serial.println(F("[SX1278] Packet too long!")); Serial.println(F("[SX1278] Packet too long!"));
} else if (state == ERR_TX_TIMEOUT) { } else if (state == RADIOLIB_ERR_TX_TIMEOUT) {
Serial.println(F("[SX1278] Timed out while transmitting!")); Serial.println(F("[SX1278] Timed out while transmitting!"));
} else { } else {
Serial.println(F("[SX1278] Failed to transmit packet, code ")); Serial.println(F("[SX1278] Failed to transmit packet, code "));
@ -113,11 +113,11 @@ void loop() {
byte byteArr[8]; byte byteArr[8];
int state = radio.receive(byteArr, 8); int state = radio.receive(byteArr, 8);
*/ */
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1278] Received packet!")); Serial.println(F("[SX1278] Received packet!"));
Serial.print(F("[SX1278] Data:\t")); Serial.print(F("[SX1278] Data:\t"));
Serial.println(str); Serial.println(str);
} else if (state == ERR_RX_TIMEOUT) { } else if (state == RADIOLIB_ERR_RX_TIMEOUT) {
Serial.println(F("[SX1278] Timed out while waiting for packet!")); Serial.println(F("[SX1278] Timed out while waiting for packet!"));
} else { } else {
Serial.println(F("[SX1278] Failed to receive packet, code ")); Serial.println(F("[SX1278] Failed to receive packet, code "));
@ -138,7 +138,7 @@ void loop() {
state = radio.setNodeAddress(0x02); state = radio.setNodeAddress(0x02);
// set broadcast address to 0xFF // set broadcast address to 0xFF
state = radio.setBroadcastAddress(0xFF); state = radio.setBroadcastAddress(0xFF);
if (state != ERR_NONE) { if (state != RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1278] Unable to set address filter, code ")); Serial.println(F("[SX1278] Unable to set address filter, code "));
Serial.println(state); Serial.println(state);
} }
@ -148,7 +148,7 @@ void loop() {
// node and broadcast address // node and broadcast address
/* /*
state = radio.disableAddressFiltering(); state = radio.disableAddressFiltering();
if (state != ERR_NONE) { if (state != RADIOLIB_ERR_NONE) {
Serial.println(F("Unable to remove address filter, code ")); Serial.println(F("Unable to remove address filter, code "));
} }
*/ */
@ -159,7 +159,7 @@ void loop() {
// activate direct mode transmitter // activate direct mode transmitter
state = radio.transmitDirect(); state = radio.transmitDirect();
if (state != ERR_NONE) { if (state != RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1278] Unable to start direct transmission mode, code ")); Serial.println(F("[SX1278] Unable to start direct transmission mode, code "));
Serial.println(state); Serial.println(state);
} }
@ -170,7 +170,7 @@ void loop() {
// it is recommended to set data shaping to 0 // it is recommended to set data shaping to 0
// (no shaping) when transmitting audio // (no shaping) when transmitting audio
state = radio.setDataShaping(0.0); state = radio.setDataShaping(0.0);
if (state != ERR_NONE) { if (state != RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1278] Unable to set data shaping, code ")); Serial.println(F("[SX1278] Unable to set data shaping, code "));
Serial.println(state); Serial.println(state);
} }
@ -193,7 +193,7 @@ void loop() {
// direct mode transmissions can also be received // direct mode transmissions can also be received
// as bit stream on DIO1 (data) and DIO2 (clock) // as bit stream on DIO1 (data) and DIO2 (clock)
state = radio.receiveDirect(); state = radio.receiveDirect();
if (state != ERR_NONE) { if (state != RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1278] Unable to start direct reception mode, code ")); Serial.println(F("[SX1278] Unable to start direct reception mode, code "));
Serial.println(state); Serial.println(state);
} }

View file

@ -27,7 +27,7 @@ SX1278 radio = new Module(10, 2, 9, 3);
//SX1278 radio = RadioShield.ModuleA; //SX1278 radio = RadioShield.ModuleA;
// save transmission states between loops // save transmission states between loops
int transmissionState = ERR_NONE; int transmissionState = RADIOLIB_ERR_NONE;
// flag to indicate transmission or reception state // flag to indicate transmission or reception state
bool transmitFlag = false; bool transmitFlag = false;
@ -58,7 +58,7 @@ void setup() {
// initialize SX1278 with default settings // initialize SX1278 with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.begin(); int state = radio.begin();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -79,7 +79,7 @@ void setup() {
// start listening for LoRa packets on this node // start listening for LoRa packets on this node
Serial.print(F("[SX1278] Starting to listen ... ")); Serial.print(F("[SX1278] Starting to listen ... "));
state = radio.startReceive(); state = radio.startReceive();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -102,7 +102,7 @@ void loop() {
if(transmitFlag) { if(transmitFlag) {
// the previous operation was transmission, listen for response // the previous operation was transmission, listen for response
// print the result // print the result
if (transmissionState == ERR_NONE) { if (transmissionState == RADIOLIB_ERR_NONE) {
// packet was successfully sent // packet was successfully sent
Serial.println(F("transmission finished!")); Serial.println(F("transmission finished!"));
@ -122,7 +122,7 @@ void loop() {
String str; String str;
int state = radio.readData(str); int state = radio.readData(str);
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
// packet was successfully received // packet was successfully received
Serial.println(F("[SX1278] Received packet!")); Serial.println(F("[SX1278] Received packet!"));

View file

@ -40,7 +40,7 @@ void setup() {
// initialize SX1278 with default settings // initialize SX1278 with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.begin(); int state = radio.begin();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -65,7 +65,7 @@ void loop() {
int state = radio.receive(byteArr, 8); int state = radio.receive(byteArr, 8);
*/ */
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
// packet was successfully received // packet was successfully received
Serial.println(F("success!")); Serial.println(F("success!"));
@ -91,11 +91,11 @@ void loop() {
Serial.print(radio.getFrequencyError()); Serial.print(radio.getFrequencyError());
Serial.println(F(" Hz")); Serial.println(F(" Hz"));
} else if (state == ERR_RX_TIMEOUT) { } else if (state == RADIOLIB_ERR_RX_TIMEOUT) {
// timeout occurred while waiting for a packet // timeout occurred while waiting for a packet
Serial.println(F("timeout!")); Serial.println(F("timeout!"));
} else if (state == ERR_CRC_MISMATCH) { } else if (state == RADIOLIB_ERR_CRC_MISMATCH) {
// packet was received, but is malformed // packet was received, but is malformed
Serial.println(F("CRC error!")); Serial.println(F("CRC error!"));

View file

@ -34,7 +34,7 @@ void setup() {
// initialize SX1278 with FSK modem at 9600 bps // initialize SX1278 with FSK modem at 9600 bps
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.beginFSK(434.0, 9.6, 20.0); int state = radio.beginFSK(434.0, 9.6, 20.0);
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));

View file

@ -41,7 +41,7 @@ void setup() {
// initialize SX1278 with default settings // initialize SX1278 with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.begin(); int state = radio.begin();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -56,7 +56,7 @@ void setup() {
// start listening for LoRa packets // start listening for LoRa packets
Serial.print(F("[SX1278] Starting to listen ... ")); Serial.print(F("[SX1278] Starting to listen ... "));
state = radio.startReceive(); state = radio.startReceive();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -115,7 +115,7 @@ void loop() {
int state = radio.readData(byteArr, 8); int state = radio.readData(byteArr, 8);
*/ */
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
// packet was successfully received // packet was successfully received
Serial.println(F("[SX1278] Received packet!")); Serial.println(F("[SX1278] Received packet!"));
@ -138,7 +138,7 @@ void loop() {
Serial.print(radio.getFrequencyError()); Serial.print(radio.getFrequencyError());
Serial.println(F(" Hz")); Serial.println(F(" Hz"));
} else if (state == ERR_CRC_MISMATCH) { } else if (state == RADIOLIB_ERR_CRC_MISMATCH) {
// packet was received, but is malformed // packet was received, but is malformed
Serial.println(F("[SX1278] CRC error!")); Serial.println(F("[SX1278] CRC error!"));

View file

@ -47,7 +47,7 @@ void setup() {
// initialize SX1278 with default settings // initialize SX1278 with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio1.begin(); int state = radio1.begin();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -73,7 +73,7 @@ void setup() {
// preamble length: 20 symbols // preamble length: 20 symbols
// amplifier gain: 1 (maximum gain) // amplifier gain: 1 (maximum gain)
state = radio2.begin(915.0, 500.0, 6, 5, 0x14, 2, 20, 1); state = radio2.begin(915.0, 500.0, 6, 5, 0x14, 2, 20, 1);
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -85,32 +85,32 @@ void setup() {
// and check if the configuration was changed successfully // and check if the configuration was changed successfully
// set carrier frequency to 433.5 MHz // set carrier frequency to 433.5 MHz
if (radio1.setFrequency(433.5) == ERR_INVALID_FREQUENCY) { if (radio1.setFrequency(433.5) == RADIOLIB_ERR_INVALID_FREQUENCY) {
Serial.println(F("Selected frequency is invalid for this module!")); Serial.println(F("Selected frequency is invalid for this module!"));
while (true); while (true);
} }
// set bandwidth to 250 kHz // set bandwidth to 250 kHz
if (radio1.setBandwidth(250.0) == ERR_INVALID_BANDWIDTH) { if (radio1.setBandwidth(250.0) == RADIOLIB_ERR_INVALID_BANDWIDTH) {
Serial.println(F("Selected bandwidth is invalid for this module!")); Serial.println(F("Selected bandwidth is invalid for this module!"));
while (true); while (true);
} }
// set spreading factor to 10 // set spreading factor to 10
if (radio1.setSpreadingFactor(10) == ERR_INVALID_SPREADING_FACTOR) { if (radio1.setSpreadingFactor(10) == RADIOLIB_ERR_INVALID_SPREADING_FACTOR) {
Serial.println(F("Selected spreading factor is invalid for this module!")); Serial.println(F("Selected spreading factor is invalid for this module!"));
while (true); while (true);
} }
// set coding rate to 6 // set coding rate to 6
if (radio1.setCodingRate(6) == ERR_INVALID_CODING_RATE) { if (radio1.setCodingRate(6) == RADIOLIB_ERR_INVALID_CODING_RATE) {
Serial.println(F("Selected coding rate is invalid for this module!")); Serial.println(F("Selected coding rate is invalid for this module!"));
while (true); while (true);
} }
// set LoRa sync word to 0x14 // set LoRa sync word to 0x14
// NOTE: value 0x34 is reserved for LoRaWAN networks and should not be used // NOTE: value 0x34 is reserved for LoRaWAN networks and should not be used
if (radio1.setSyncWord(0x14) != ERR_NONE) { if (radio1.setSyncWord(0x14) != RADIOLIB_ERR_NONE) {
Serial.println(F("Unable to set sync word!")); Serial.println(F("Unable to set sync word!"));
while (true); while (true);
} }
@ -118,20 +118,20 @@ void setup() {
// set output power to 10 dBm (accepted range is -3 - 17 dBm) // set output power to 10 dBm (accepted range is -3 - 17 dBm)
// NOTE: 20 dBm value allows high power operation, but transmission // NOTE: 20 dBm value allows high power operation, but transmission
// duty cycle MUST NOT exceed 1% // duty cycle MUST NOT exceed 1%
if (radio1.setOutputPower(10) == ERR_INVALID_OUTPUT_POWER) { if (radio1.setOutputPower(10) == RADIOLIB_ERR_INVALID_OUTPUT_POWER) {
Serial.println(F("Selected output power is invalid for this module!")); Serial.println(F("Selected output power is invalid for this module!"));
while (true); while (true);
} }
// set over current protection limit to 80 mA (accepted range is 45 - 240 mA) // set over current protection limit to 80 mA (accepted range is 45 - 240 mA)
// NOTE: set value to 0 to disable overcurrent protection // NOTE: set value to 0 to disable overcurrent protection
if (radio1.setCurrentLimit(80) == ERR_INVALID_CURRENT_LIMIT) { if (radio1.setCurrentLimit(80) == RADIOLIB_ERR_INVALID_CURRENT_LIMIT) {
Serial.println(F("Selected current limit is invalid for this module!")); Serial.println(F("Selected current limit is invalid for this module!"));
while (true); while (true);
} }
// set LoRa preamble length to 15 symbols (accepted range is 6 - 65535) // set LoRa preamble length to 15 symbols (accepted range is 6 - 65535)
if (radio1.setPreambleLength(15) == ERR_INVALID_PREAMBLE_LENGTH) { if (radio1.setPreambleLength(15) == RADIOLIB_ERR_INVALID_PREAMBLE_LENGTH) {
Serial.println(F("Selected preamble length is invalid for this module!")); Serial.println(F("Selected preamble length is invalid for this module!"));
while (true); while (true);
} }
@ -139,7 +139,7 @@ void setup() {
// set amplifier gain to 1 (accepted range is 1 - 6, where 1 is maximum gain) // set amplifier gain to 1 (accepted range is 1 - 6, where 1 is maximum gain)
// NOTE: set value to 0 to enable automatic gain control // NOTE: set value to 0 to enable automatic gain control
// leave at 0 unless you know what you're doing // leave at 0 unless you know what you're doing
if (radio1.setGain(1) == ERR_INVALID_GAIN) { if (radio1.setGain(1) == RADIOLIB_ERR_INVALID_GAIN) {
Serial.println(F("Selected gain is invalid for this module!")); Serial.println(F("Selected gain is invalid for this module!"));
while (true); while (true);
} }

View file

@ -24,7 +24,7 @@
// DIO0 pin: 2 // DIO0 pin: 2
// RESET pin: 9 // RESET pin: 9
// DIO1 pin: 3 // DIO1 pin: 3
SX1278 radio = new Module(10, 2, 9, 3); SX1278 radio = new Module(5, 2, 9, 3);
// or using RadioShield // or using RadioShield
// https://github.com/jgromes/RadioShield // https://github.com/jgromes/RadioShield
@ -36,7 +36,7 @@ void setup() {
// initialize SX1278 with default settings // initialize SX1278 with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.begin(); int state = radio.begin();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -71,7 +71,7 @@ void loop() {
int state = radio.transmit(byteArr, 8); int state = radio.transmit(byteArr, 8);
*/ */
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
// the packet was successfully transmitted // the packet was successfully transmitted
Serial.println(F(" success!")); Serial.println(F(" success!"));
@ -80,11 +80,11 @@ void loop() {
Serial.print(radio.getDataRate()); Serial.print(radio.getDataRate());
Serial.println(F(" bps")); Serial.println(F(" bps"));
} else if (state == ERR_PACKET_TOO_LONG) { } else if (state == RADIOLIB_ERR_PACKET_TOO_LONG) {
// the supplied packet was longer than 256 bytes // the supplied packet was longer than 256 bytes
Serial.println(F("too long!")); Serial.println(F("too long!"));
} else if (state == ERR_TX_TIMEOUT) { } else if (state == RADIOLIB_ERR_TX_TIMEOUT) {
// timeout occurred while transmitting packet // timeout occurred while transmitting packet
Serial.println(F("timeout!")); Serial.println(F("timeout!"));

View file

@ -32,7 +32,7 @@ SX1278 radio = new Module(10, 2, 9, 3);
//SX1278 radio = RadioShield.ModuleA; //SX1278 radio = RadioShield.ModuleA;
// save transmission state between loops // save transmission state between loops
int transmissionState = ERR_NONE; int transmissionState = RADIOLIB_ERR_NONE;
void setup() { void setup() {
Serial.begin(9600); Serial.begin(9600);
@ -40,7 +40,7 @@ void setup() {
// initialize SX1278 with default settings // initialize SX1278 with default settings
Serial.print(F("[SX1278] Initializing ... ")); Serial.print(F("[SX1278] Initializing ... "));
int state = radio.begin(); int state = radio.begin();
if (state == ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!")); Serial.println(F("success!"));
} else { } else {
Serial.print(F("failed, code ")); Serial.print(F("failed, code "));
@ -97,7 +97,7 @@ void loop() {
// reset flag // reset flag
transmittedFlag = false; transmittedFlag = false;
if (transmissionState == ERR_NONE) { if (transmissionState == RADIOLIB_ERR_NONE) {
// packet was successfully sent // packet was successfully sent
Serial.println(F("transmission finished!")); Serial.println(F("transmission finished!"));

View file

@ -7,7 +7,7 @@ SX1272::SX1272(Module* mod) : SX127x(mod) {
int16_t SX1272::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) { int16_t SX1272::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) {
// execute common part // execute common part
int16_t state = SX127x::begin(SX1272_CHIP_VERSION, syncWord, preambleLength); int16_t state = SX127x::begin(RADIOLIB_SX1272_CHIP_VERSION, syncWord, preambleLength);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure publicly accessible settings // configure publicly accessible settings
@ -34,7 +34,7 @@ int16_t SX1272::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t sync
int16_t SX1272::beginFSK(float freq, float br, float rxBw, float freqDev, int8_t power, uint16_t preambleLength, bool enableOOK) { int16_t SX1272::beginFSK(float freq, float br, float rxBw, float freqDev, int8_t power, uint16_t preambleLength, bool enableOOK) {
// execute common part // execute common part
int16_t state = SX127x::beginFSK(SX1272_CHIP_VERSION, br, rxBw, freqDev, preambleLength, enableOOK); int16_t state = SX127x::beginFSK(RADIOLIB_SX1272_CHIP_VERSION, br, rxBw, freqDev, preambleLength, enableOOK);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure settings not accessible by API // configure settings not accessible by API
@ -60,19 +60,19 @@ int16_t SX1272::beginFSK(float freq, float br, float rxBw, float freqDev, int8_t
} }
void SX1272::reset() { void SX1272::reset() {
Module::pinMode(_mod->getRst(), OUTPUT); _mod->pinMode(_mod->getRst(), OUTPUT);
Module::digitalWrite(_mod->getRst(), HIGH); _mod->digitalWrite(_mod->getRst(), HIGH);
Module::delay(1); _mod->delay(1);
Module::digitalWrite(_mod->getRst(), LOW); _mod->digitalWrite(_mod->getRst(), LOW);
Module::delay(5); _mod->delay(5);
} }
int16_t SX1272::setFrequency(float freq) { int16_t SX1272::setFrequency(float freq) {
RADIOLIB_CHECK_RANGE(freq, 860.0, 1020.0, ERR_INVALID_FREQUENCY); RADIOLIB_CHECK_RANGE(freq, 860.0, 1020.0, RADIOLIB_ERR_INVALID_FREQUENCY);
// set frequency and if successful, save the new setting // set frequency and if successful, save the new setting
int16_t state = SX127x::setFrequencyRaw(freq); int16_t state = SX127x::setFrequencyRaw(freq);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_freq = freq; SX127x::_freq = freq;
} }
return(state); return(state);
@ -80,26 +80,26 @@ int16_t SX1272::setFrequency(float freq) {
int16_t SX1272::setBandwidth(float bw) { int16_t SX1272::setBandwidth(float bw) {
// check active modem // check active modem
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
uint8_t newBandwidth; uint8_t newBandwidth;
// check allowed bandwidth values // check allowed bandwidth values
if(fabs(bw - 125.0) <= 0.001) { if(fabs(bw - 125.0) <= 0.001) {
newBandwidth = SX1272_BW_125_00_KHZ; newBandwidth = RADIOLIB_SX1272_BW_125_00_KHZ;
} else if(fabs(bw - 250.0) <= 0.001) { } else if(fabs(bw - 250.0) <= 0.001) {
newBandwidth = SX1272_BW_250_00_KHZ; newBandwidth = RADIOLIB_SX1272_BW_250_00_KHZ;
} else if(fabs(bw - 500.0) <= 0.001) { } else if(fabs(bw - 500.0) <= 0.001) {
newBandwidth = SX1272_BW_500_00_KHZ; newBandwidth = RADIOLIB_SX1272_BW_500_00_KHZ;
} else { } else {
return(ERR_INVALID_BANDWIDTH); return(RADIOLIB_ERR_INVALID_BANDWIDTH);
} }
// set bandwidth and if successful, save the new setting // set bandwidth and if successful, save the new setting
int16_t state = SX1272::setBandwidthRaw(newBandwidth); int16_t state = SX1272::setBandwidthRaw(newBandwidth);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_bw = bw; SX127x::_bw = bw;
// calculate symbol length and set low data rate optimization, if auto-configuration is enabled // calculate symbol length and set low data rate optimization, if auto-configuration is enabled
@ -109,9 +109,9 @@ int16_t SX1272::setBandwidth(float bw) {
RADIOLIB_DEBUG_PRINT(symbolLength); RADIOLIB_DEBUG_PRINT(symbolLength);
RADIOLIB_DEBUG_PRINTLN(" ms"); RADIOLIB_DEBUG_PRINTLN(" ms");
if(symbolLength >= 16.0) { if(symbolLength >= 16.0) {
state = _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1272_LOW_DATA_RATE_OPT_ON, 0, 0); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1272_LOW_DATA_RATE_OPT_ON, 0, 0);
} else { } else {
state = _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1272_LOW_DATA_RATE_OPT_OFF, 0, 0); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1272_LOW_DATA_RATE_OPT_OFF, 0, 0);
} }
} }
} }
@ -120,8 +120,8 @@ int16_t SX1272::setBandwidth(float bw) {
int16_t SX1272::setSpreadingFactor(uint8_t sf) { int16_t SX1272::setSpreadingFactor(uint8_t sf) {
// check active modem // check active modem
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
uint8_t newSpreadingFactor; uint8_t newSpreadingFactor;
@ -129,33 +129,33 @@ int16_t SX1272::setSpreadingFactor(uint8_t sf) {
// check allowed spreading factor values // check allowed spreading factor values
switch(sf) { switch(sf) {
case 6: case 6:
newSpreadingFactor = SX127X_SF_6; newSpreadingFactor = RADIOLIB_SX127X_SF_6;
break; break;
case 7: case 7:
newSpreadingFactor = SX127X_SF_7; newSpreadingFactor = RADIOLIB_SX127X_SF_7;
break; break;
case 8: case 8:
newSpreadingFactor = SX127X_SF_8; newSpreadingFactor = RADIOLIB_SX127X_SF_8;
break; break;
case 9: case 9:
newSpreadingFactor = SX127X_SF_9; newSpreadingFactor = RADIOLIB_SX127X_SF_9;
break; break;
case 10: case 10:
newSpreadingFactor = SX127X_SF_10; newSpreadingFactor = RADIOLIB_SX127X_SF_10;
break; break;
case 11: case 11:
newSpreadingFactor = SX127X_SF_11; newSpreadingFactor = RADIOLIB_SX127X_SF_11;
break; break;
case 12: case 12:
newSpreadingFactor = SX127X_SF_12; newSpreadingFactor = RADIOLIB_SX127X_SF_12;
break; break;
default: default:
return(ERR_INVALID_SPREADING_FACTOR); return(RADIOLIB_ERR_INVALID_SPREADING_FACTOR);
} }
// set spreading factor and if successful, save the new setting // set spreading factor and if successful, save the new setting
int16_t state = SX1272::setSpreadingFactorRaw(newSpreadingFactor); int16_t state = SX1272::setSpreadingFactorRaw(newSpreadingFactor);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_sf = sf; SX127x::_sf = sf;
// calculate symbol length and set low data rate optimization, if auto-configuration is enabled // calculate symbol length and set low data rate optimization, if auto-configuration is enabled
@ -165,9 +165,9 @@ int16_t SX1272::setSpreadingFactor(uint8_t sf) {
RADIOLIB_DEBUG_PRINT(symbolLength); RADIOLIB_DEBUG_PRINT(symbolLength);
RADIOLIB_DEBUG_PRINTLN(" ms"); RADIOLIB_DEBUG_PRINTLN(" ms");
if(symbolLength >= 16.0) { if(symbolLength >= 16.0) {
state = _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1272_LOW_DATA_RATE_OPT_ON, 0, 0); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1272_LOW_DATA_RATE_OPT_ON, 0, 0);
} else { } else {
state = _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1272_LOW_DATA_RATE_OPT_OFF, 0, 0); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1272_LOW_DATA_RATE_OPT_OFF, 0, 0);
} }
} }
} }
@ -176,8 +176,8 @@ int16_t SX1272::setSpreadingFactor(uint8_t sf) {
int16_t SX1272::setCodingRate(uint8_t cr) { int16_t SX1272::setCodingRate(uint8_t cr) {
// check active modem // check active modem
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
uint8_t newCodingRate; uint8_t newCodingRate;
@ -185,24 +185,24 @@ int16_t SX1272::setCodingRate(uint8_t cr) {
// check allowed coding rate values // check allowed coding rate values
switch(cr) { switch(cr) {
case 5: case 5:
newCodingRate = SX1272_CR_4_5; newCodingRate = RADIOLIB_SX1272_CR_4_5;
break; break;
case 6: case 6:
newCodingRate = SX1272_CR_4_6; newCodingRate = RADIOLIB_SX1272_CR_4_6;
break; break;
case 7: case 7:
newCodingRate = SX1272_CR_4_7; newCodingRate = RADIOLIB_SX1272_CR_4_7;
break; break;
case 8: case 8:
newCodingRate = SX1272_CR_4_8; newCodingRate = RADIOLIB_SX1272_CR_4_8;
break; break;
default: default:
return(ERR_INVALID_CODING_RATE); return(RADIOLIB_ERR_INVALID_CODING_RATE);
} }
// set coding rate and if successful, save the new setting // set coding rate and if successful, save the new setting
int16_t state = SX1272::setCodingRateRaw(newCodingRate); int16_t state = SX1272::setCodingRateRaw(newCodingRate);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_cr = cr; SX127x::_cr = cr;
} }
return(state); return(state);
@ -211,9 +211,9 @@ int16_t SX1272::setCodingRate(uint8_t cr) {
int16_t SX1272::setOutputPower(int8_t power, bool useRfo) { int16_t SX1272::setOutputPower(int8_t power, bool useRfo) {
// check allowed power range // check allowed power range
if(useRfo) { if(useRfo) {
RADIOLIB_CHECK_RANGE(power, -1, 14, ERR_INVALID_OUTPUT_POWER); RADIOLIB_CHECK_RANGE(power, -1, 14, RADIOLIB_ERR_INVALID_OUTPUT_POWER);
} else { } else {
RADIOLIB_CHECK_RANGE(power, 2, 20, ERR_INVALID_OUTPUT_POWER); RADIOLIB_CHECK_RANGE(power, 2, 20, RADIOLIB_ERR_INVALID_OUTPUT_POWER);
} }
// set mode to standby // set mode to standby
@ -221,22 +221,22 @@ int16_t SX1272::setOutputPower(int8_t power, bool useRfo) {
if(useRfo) { if(useRfo) {
// RFO output // RFO output
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, SX127X_PA_SELECT_RFO, 7, 7); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, RADIOLIB_SX127X_PA_SELECT_RFO, 7, 7);
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, (power + 1), 3, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, (power + 1), 3, 0);
state |= _mod->SPIsetRegValue(SX1272_REG_PA_DAC, SX127X_PA_BOOST_OFF, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX1272_REG_PA_DAC, RADIOLIB_SX127X_PA_BOOST_OFF, 2, 0);
} else { } else {
if(power <= 17) { if(power <= 17) {
// power is 2 - 17 dBm, enable PA1 + PA2 on PA_BOOST // power is 2 - 17 dBm, enable PA1 + PA2 on PA_BOOST
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, SX127X_PA_SELECT_BOOST, 7, 7); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, RADIOLIB_SX127X_PA_SELECT_BOOST, 7, 7);
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, (power - 2), 3, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, (power - 2), 3, 0);
state |= _mod->SPIsetRegValue(SX1272_REG_PA_DAC, SX127X_PA_BOOST_OFF, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX1272_REG_PA_DAC, RADIOLIB_SX127X_PA_BOOST_OFF, 2, 0);
} else { } else {
// power is 18 - 20 dBm, enable PA1 + PA2 on PA_BOOST and enable high power control // power is 18 - 20 dBm, enable PA1 + PA2 on PA_BOOST and enable high power control
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, SX127X_PA_SELECT_BOOST, 7, 7); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, RADIOLIB_SX127X_PA_SELECT_BOOST, 7, 7);
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, (power - 5), 3, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, (power - 5), 3, 0);
state |= _mod->SPIsetRegValue(SX1272_REG_PA_DAC, SX127X_PA_BOOST_ON, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX1272_REG_PA_DAC, RADIOLIB_SX127X_PA_BOOST_ON, 2, 0);
} }
@ -248,7 +248,7 @@ int16_t SX1272::setOutputPower(int8_t power, bool useRfo) {
int16_t SX1272::setGain(uint8_t gain) { int16_t SX1272::setGain(uint8_t gain) {
// check allowed range // check allowed range
if(gain > 6) { if(gain > 6) {
return(ERR_INVALID_GAIN); return(RADIOLIB_ERR_INVALID_GAIN);
} }
// set mode to standby // set mode to standby
@ -256,24 +256,24 @@ int16_t SX1272::setGain(uint8_t gain) {
// get modem // get modem
int16_t modem = getActiveModem(); int16_t modem = getActiveModem();
if(modem == SX127X_LORA){ if(modem == RADIOLIB_SX127X_LORA){
// set gain // set gain
if(gain == 0) { if(gain == 0) {
// gain set to 0, enable AGC loop // gain set to 0, enable AGC loop
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, SX1272_AGC_AUTO_ON, 2, 2); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, RADIOLIB_SX1272_AGC_AUTO_ON, 2, 2);
} else { } else {
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, SX1272_AGC_AUTO_OFF, 2, 2); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, RADIOLIB_SX1272_AGC_AUTO_OFF, 2, 2);
state |= _mod->SPIsetRegValue(SX127X_REG_LNA, (gain << 5) | SX127X_LNA_BOOST_ON); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_LNA, (gain << 5) | RADIOLIB_SX127X_LNA_BOOST_ON);
} }
} else if(modem == SX127X_FSK_OOK) { } else if(modem == RADIOLIB_SX127X_FSK_OOK) {
// set gain // set gain
if(gain == 0) { if(gain == 0) {
// gain set to 0, enable AGC loop // gain set to 0, enable AGC loop
state |= _mod->SPIsetRegValue(SX127X_REG_RX_CONFIG, SX127X_AGC_AUTO_ON, 3, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_RX_CONFIG, RADIOLIB_SX127X_AGC_AUTO_ON, 3, 3);
} else { } else {
state |= _mod->SPIsetRegValue(SX127X_REG_RX_CONFIG, SX127X_AGC_AUTO_ON, 3, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_RX_CONFIG, RADIOLIB_SX127X_AGC_AUTO_ON, 3, 3);
state |= _mod->SPIsetRegValue(SX127X_REG_LNA, (gain << 5) | SX127X_LNA_BOOST_ON); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_LNA, (gain << 5) | RADIOLIB_SX127X_LNA_BOOST_ON);
} }
} }
@ -283,13 +283,13 @@ int16_t SX1272::setGain(uint8_t gain) {
int16_t SX1272::setDataShaping(uint8_t sh) { int16_t SX1272::setDataShaping(uint8_t sh) {
// check active modem // check active modem
if(getActiveModem() != SX127X_FSK_OOK) { if(getActiveModem() != RADIOLIB_SX127X_FSK_OOK) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
// check modulation // check modulation
if(SX127x::_ook) { if(SX127x::_ook) {
return(ERR_INVALID_MODULATION); return(RADIOLIB_ERR_INVALID_MODULATION);
} }
// set mode to standby // set mode to standby
@ -299,27 +299,27 @@ int16_t SX1272::setDataShaping(uint8_t sh) {
// set data shaping // set data shaping
switch(sh) { switch(sh) {
case RADIOLIB_SHAPING_NONE: case RADIOLIB_SHAPING_NONE:
return(_mod->SPIsetRegValue(SX127X_REG_OP_MODE, SX1272_NO_SHAPING, 4, 3)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_OP_MODE, RADIOLIB_SX1272_NO_SHAPING, 4, 3));
case RADIOLIB_SHAPING_0_3: case RADIOLIB_SHAPING_0_3:
return(_mod->SPIsetRegValue(SX127X_REG_OP_MODE, SX1272_FSK_GAUSSIAN_0_3, 4, 3)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_OP_MODE, RADIOLIB_SX1272_FSK_GAUSSIAN_0_3, 4, 3));
case RADIOLIB_SHAPING_0_5: case RADIOLIB_SHAPING_0_5:
return(_mod->SPIsetRegValue(SX127X_REG_OP_MODE, SX1272_FSK_GAUSSIAN_0_5, 4, 3)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_OP_MODE, RADIOLIB_SX1272_FSK_GAUSSIAN_0_5, 4, 3));
case RADIOLIB_SHAPING_1_0: case RADIOLIB_SHAPING_1_0:
return(_mod->SPIsetRegValue(SX127X_REG_OP_MODE, SX1272_FSK_GAUSSIAN_1_0, 4, 3)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_OP_MODE, RADIOLIB_SX1272_FSK_GAUSSIAN_1_0, 4, 3));
default: default:
return(ERR_INVALID_DATA_SHAPING); return(RADIOLIB_ERR_INVALID_DATA_SHAPING);
} }
} }
int16_t SX1272::setDataShapingOOK(uint8_t sh) { int16_t SX1272::setDataShapingOOK(uint8_t sh) {
// check active modem // check active modem
if(getActiveModem() != SX127X_FSK_OOK) { if(getActiveModem() != RADIOLIB_SX127X_FSK_OOK) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
// check modulation // check modulation
if(!SX127x::_ook) { if(!SX127x::_ook) {
return(ERR_INVALID_MODULATION); return(RADIOLIB_ERR_INVALID_MODULATION);
} }
// set mode to standby // set mode to standby
@ -328,16 +328,16 @@ int16_t SX1272::setDataShapingOOK(uint8_t sh) {
// set data shaping // set data shaping
switch(sh) { switch(sh) {
case 0: case 0:
state |= _mod->SPIsetRegValue(SX127X_REG_OP_MODE, SX1272_NO_SHAPING, 4, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_OP_MODE, RADIOLIB_SX1272_NO_SHAPING, 4, 3);
break; break;
case 1: case 1:
state |= _mod->SPIsetRegValue(SX127X_REG_OP_MODE, SX1272_OOK_FILTER_BR, 4, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_OP_MODE, RADIOLIB_SX1272_OOK_FILTER_BR, 4, 3);
break; break;
case 2: case 2:
state |= _mod->SPIsetRegValue(SX127X_REG_OP_MODE, SX1272_OOK_FILTER_2BR, 4, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_OP_MODE, RADIOLIB_SX1272_OOK_FILTER_2BR, 4, 3);
break; break;
default: default:
state = ERR_INVALID_DATA_SHAPING; state = RADIOLIB_ERR_INVALID_DATA_SHAPING;
break; break;
} }
@ -345,9 +345,9 @@ int16_t SX1272::setDataShapingOOK(uint8_t sh) {
} }
float SX1272::getRSSI(bool skipReceive) { float SX1272::getRSSI(bool skipReceive) {
if(getActiveModem() == SX127X_LORA) { if(getActiveModem() == RADIOLIB_SX127X_LORA) {
// RSSI calculation uses different constant for low-frequency and high-frequency ports // RSSI calculation uses different constant for low-frequency and high-frequency ports
float lastPacketRSSI = -139 + _mod->SPIgetRegValue(SX127X_REG_PKT_RSSI_VALUE); float lastPacketRSSI = -139 + _mod->SPIgetRegValue(RADIOLIB_SX127X_REG_PKT_RSSI_VALUE);
// spread-spectrum modulation signal can be received below noise floor // spread-spectrum modulation signal can be received below noise floor
// check last packet SNR and if it's less than 0, add it to reported RSSI to get the correct value // check last packet SNR and if it's less than 0, add it to reported RSSI to get the correct value
@ -365,7 +365,7 @@ float SX1272::getRSSI(bool skipReceive) {
} }
// read the value for FSK // read the value for FSK
float rssi = (float)_mod->SPIgetRegValue(SX127X_REG_RSSI_VALUE_FSK) / -2.0; float rssi = (float)_mod->SPIgetRegValue(RADIOLIB_SX127X_REG_RSSI_VALUE_FSK) / -2.0;
// set mode back to standby // set mode back to standby
if(!skipReceive) { if(!skipReceive) {
@ -378,61 +378,61 @@ float SX1272::getRSSI(bool skipReceive) {
} }
int16_t SX1272::setCRC(bool enable, bool mode) { int16_t SX1272::setCRC(bool enable, bool mode) {
if(getActiveModem() == SX127X_LORA) { if(getActiveModem() == RADIOLIB_SX127X_LORA) {
// set LoRa CRC // set LoRa CRC
SX127x::_crcEnabled = enable; SX127x::_crcEnabled = enable;
if(enable) { if(enable) {
return(_mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, SX1272_RX_CRC_MODE_ON, 2, 2)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, RADIOLIB_SX1272_RX_CRC_MODE_ON, 2, 2));
} else { } else {
return(_mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, SX1272_RX_CRC_MODE_OFF, 2, 2)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, RADIOLIB_SX1272_RX_CRC_MODE_OFF, 2, 2));
} }
} else { } else {
// set FSK CRC // set FSK CRC
int16_t state = ERR_NONE; int16_t state = RADIOLIB_ERR_NONE;
if(enable) { if(enable) {
state = _mod->SPIsetRegValue(SX127X_REG_PACKET_CONFIG_1, SX127X_CRC_ON, 4, 4); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PACKET_CONFIG_1, RADIOLIB_SX127X_CRC_ON, 4, 4);
} else { } else {
state = _mod->SPIsetRegValue(SX127X_REG_PACKET_CONFIG_1, SX127X_CRC_OFF, 4, 4); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PACKET_CONFIG_1, RADIOLIB_SX127X_CRC_OFF, 4, 4);
} }
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// set FSK CRC mode // set FSK CRC mode
if(mode) { if(mode) {
return(_mod->SPIsetRegValue(SX127X_REG_PACKET_CONFIG_1, SX127X_CRC_WHITENING_TYPE_IBM, 0, 0)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PACKET_CONFIG_1, RADIOLIB_SX127X_CRC_WHITENING_TYPE_IBM, 0, 0));
} else { } else {
return(_mod->SPIsetRegValue(SX127X_REG_PACKET_CONFIG_1, SX127X_CRC_WHITENING_TYPE_CCITT, 0, 0)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PACKET_CONFIG_1, RADIOLIB_SX127X_CRC_WHITENING_TYPE_CCITT, 0, 0));
} }
} }
} }
int16_t SX1272::forceLDRO(bool enable) { int16_t SX1272::forceLDRO(bool enable) {
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
_ldroAuto = false; _ldroAuto = false;
if(enable) { if(enable) {
return(_mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1272_LOW_DATA_RATE_OPT_ON, 0, 0)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1272_LOW_DATA_RATE_OPT_ON, 0, 0));
} else { } else {
return(_mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1272_LOW_DATA_RATE_OPT_OFF, 0, 0)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1272_LOW_DATA_RATE_OPT_OFF, 0, 0));
} }
} }
int16_t SX1272::autoLDRO() { int16_t SX1272::autoLDRO() {
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
_ldroAuto = true; _ldroAuto = true;
return(ERR_NONE); return(RADIOLIB_ERR_NONE);
} }
int16_t SX1272::implicitHeader(size_t len) { int16_t SX1272::implicitHeader(size_t len) {
return(setHeaderType(SX1272_HEADER_IMPL_MODE, len)); return(setHeaderType(RADIOLIB_SX1272_HEADER_IMPL_MODE, len));
} }
int16_t SX1272::explicitHeader() { int16_t SX1272::explicitHeader() {
return(setHeaderType(SX1272_HEADER_EXPL_MODE)); return(setHeaderType(RADIOLIB_SX1272_HEADER_EXPL_MODE));
} }
int16_t SX1272::setBandwidthRaw(uint8_t newBandwidth) { int16_t SX1272::setBandwidthRaw(uint8_t newBandwidth) {
@ -440,7 +440,7 @@ int16_t SX1272::setBandwidthRaw(uint8_t newBandwidth) {
int16_t state = SX127x::standby(); int16_t state = SX127x::standby();
// write register // write register
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, newBandwidth, 7, 6); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, newBandwidth, 7, 6);
return(state); return(state);
} }
@ -449,16 +449,16 @@ int16_t SX1272::setSpreadingFactorRaw(uint8_t newSpreadingFactor) {
int16_t state = SX127x::standby(); int16_t state = SX127x::standby();
// write registers // write registers
if(newSpreadingFactor == SX127X_SF_6) { if(newSpreadingFactor == RADIOLIB_SX127X_SF_6) {
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1272_HEADER_IMPL_MODE | (SX127x::_crcEnabled ? SX1272_RX_CRC_MODE_ON : SX1272_RX_CRC_MODE_OFF), 2, 1); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1272_HEADER_IMPL_MODE | (SX127x::_crcEnabled ? RADIOLIB_SX1272_RX_CRC_MODE_ON : RADIOLIB_SX1272_RX_CRC_MODE_OFF), 2, 1);
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, SX127X_SF_6 | SX127X_TX_MODE_SINGLE, 7, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, RADIOLIB_SX127X_SF_6 | RADIOLIB_SX127X_TX_MODE_SINGLE, 7, 3);
state |= _mod->SPIsetRegValue(SX127X_REG_DETECT_OPTIMIZE, SX127X_DETECT_OPTIMIZE_SF_6, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_DETECT_OPTIMIZE, RADIOLIB_SX127X_DETECT_OPTIMIZE_SF_6, 2, 0);
state |= _mod->SPIsetRegValue(SX127X_REG_DETECTION_THRESHOLD, SX127X_DETECTION_THRESHOLD_SF_6); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_DETECTION_THRESHOLD, RADIOLIB_SX127X_DETECTION_THRESHOLD_SF_6);
} else { } else {
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1272_HEADER_EXPL_MODE | (SX127x::_crcEnabled ? SX1272_RX_CRC_MODE_ON : SX1272_RX_CRC_MODE_OFF), 2, 1); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1272_HEADER_EXPL_MODE | (SX127x::_crcEnabled ? RADIOLIB_SX1272_RX_CRC_MODE_ON : RADIOLIB_SX1272_RX_CRC_MODE_OFF), 2, 1);
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, newSpreadingFactor | SX127X_TX_MODE_SINGLE, 7, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, newSpreadingFactor | RADIOLIB_SX127X_TX_MODE_SINGLE, 7, 3);
state |= _mod->SPIsetRegValue(SX127X_REG_DETECT_OPTIMIZE, SX127X_DETECT_OPTIMIZE_SF_7_12, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_DETECT_OPTIMIZE, RADIOLIB_SX127X_DETECT_OPTIMIZE_SF_7_12, 2, 0);
state |= _mod->SPIsetRegValue(SX127X_REG_DETECTION_THRESHOLD, SX127X_DETECTION_THRESHOLD_SF_7_12); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_DETECTION_THRESHOLD, RADIOLIB_SX127X_DETECTION_THRESHOLD_SF_7_12);
} }
return(state); return(state);
} }
@ -468,22 +468,22 @@ int16_t SX1272::setCodingRateRaw(uint8_t newCodingRate) {
int16_t state = SX127x::standby(); int16_t state = SX127x::standby();
// write register // write register
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, newCodingRate, 5, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, newCodingRate, 5, 3);
return(state); return(state);
} }
int16_t SX1272::setHeaderType(uint8_t headerType, size_t len) { int16_t SX1272::setHeaderType(uint8_t headerType, size_t len) {
// check active modem // check active modem
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
// set requested packet mode // set requested packet mode
int16_t state = _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, headerType, 2, 2); int16_t state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, headerType, 2, 2);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// set length to register // set length to register
state = _mod->SPIsetRegValue(SX127X_REG_PAYLOAD_LENGTH, len); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PAYLOAD_LENGTH, len);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// update cached value // update cached value
@ -498,7 +498,7 @@ int16_t SX1272::configFSK() {
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// set fast PLL hop // set fast PLL hop
state = _mod->SPIsetRegValue(SX1272_REG_PLL_HOP, SX127X_FAST_HOP_ON, 7, 7); state = _mod->SPIsetRegValue(RADIOLIB_SX1272_REG_PLL_HOP, RADIOLIB_SX127X_FAST_HOP_ON, 7, 7);
return(state); return(state);
} }

View file

@ -9,82 +9,82 @@
#include "SX127x.h" #include "SX127x.h"
// SX1272 specific register map // SX1272 specific register map
#define SX1272_REG_AGC_REF 0x43 #define RADIOLIB_SX1272_REG_AGC_REF 0x43
#define SX1272_REG_AGC_THRESH_1 0x44 #define RADIOLIB_SX1272_REG_AGC_THRESH_1 0x44
#define SX1272_REG_AGC_THRESH_2 0x45 #define RADIOLIB_SX1272_REG_AGC_THRESH_2 0x45
#define SX1272_REG_AGC_THRESH_3 0x46 #define RADIOLIB_SX1272_REG_AGC_THRESH_3 0x46
#define SX1272_REG_PLL_HOP 0x4B #define RADIOLIB_SX1272_REG_PLL_HOP 0x4B
#define SX1272_REG_TCXO 0x58 #define RADIOLIB_SX1272_REG_TCXO 0x58
#define SX1272_REG_PA_DAC 0x5A #define RADIOLIB_SX1272_REG_PA_DAC 0x5A
#define SX1272_REG_PLL 0x5C #define RADIOLIB_SX1272_REG_PLL 0x5C
#define SX1272_REG_PLL_LOW_PN 0x5E #define RADIOLIB_SX1272_REG_PLL_LOW_PN 0x5E
#define SX1272_REG_FORMER_TEMP 0x6C #define RADIOLIB_SX1272_REG_FORMER_TEMP 0x6C
#define SX1272_REG_BIT_RATE_FRAC 0x70 #define RADIOLIB_SX1272_REG_BIT_RATE_FRAC 0x70
// SX1272 LoRa modem settings // SX1272 LoRa modem settings
// SX1272_REG_FRF_MSB + REG_FRF_MID + REG_FRF_LSB // RADIOLIB_SX1272_REG_FRF_MSB + REG_FRF_MID + REG_FRF_LSB
#define SX1272_FRF_MSB 0xE4 // 7 0 carrier frequency setting: f_RF = (F(XOSC) * FRF)/2^19 #define RADIOLIB_SX1272_FRF_MSB 0xE4 // 7 0 carrier frequency setting: f_RF = (F(XOSC) * FRF)/2^19
#define SX1272_FRF_MID 0xC0 // 7 0 where F(XOSC) = 32 MHz #define RADIOLIB_SX1272_FRF_MID 0xC0 // 7 0 where F(XOSC) = 32 MHz
#define SX1272_FRF_LSB 0x00 // 7 0 FRF = 3 byte value of FRF registers #define RADIOLIB_SX1272_FRF_LSB 0x00 // 7 0 FRF = 3 byte value of FRF registers
// SX127X_REG_MODEM_CONFIG_1 // RADIOLIB_SX127X_REG_MODEM_CONFIG_1
#define SX1272_BW_125_00_KHZ 0b00000000 // 7 6 bandwidth: 125 kHz #define RADIOLIB_SX1272_BW_125_00_KHZ 0b00000000 // 7 6 bandwidth: 125 kHz
#define SX1272_BW_250_00_KHZ 0b01000000 // 7 6 250 kHz #define RADIOLIB_SX1272_BW_250_00_KHZ 0b01000000 // 7 6 250 kHz
#define SX1272_BW_500_00_KHZ 0b10000000 // 7 6 500 kHz #define RADIOLIB_SX1272_BW_500_00_KHZ 0b10000000 // 7 6 500 kHz
#define SX1272_CR_4_5 0b00001000 // 5 3 error coding rate: 4/5 #define RADIOLIB_SX1272_CR_4_5 0b00001000 // 5 3 error coding rate: 4/5
#define SX1272_CR_4_6 0b00010000 // 5 3 4/6 #define RADIOLIB_SX1272_CR_4_6 0b00010000 // 5 3 4/6
#define SX1272_CR_4_7 0b00011000 // 5 3 4/7 #define RADIOLIB_SX1272_CR_4_7 0b00011000 // 5 3 4/7
#define SX1272_CR_4_8 0b00100000 // 5 3 4/8 #define RADIOLIB_SX1272_CR_4_8 0b00100000 // 5 3 4/8
#define SX1272_HEADER_EXPL_MODE 0b00000000 // 2 2 explicit header mode #define RADIOLIB_SX1272_HEADER_EXPL_MODE 0b00000000 // 2 2 explicit header mode
#define SX1272_HEADER_IMPL_MODE 0b00000100 // 2 2 implicit header mode #define RADIOLIB_SX1272_HEADER_IMPL_MODE 0b00000100 // 2 2 implicit header mode
#define SX1272_RX_CRC_MODE_OFF 0b00000000 // 1 1 CRC disabled #define RADIOLIB_SX1272_RX_CRC_MODE_OFF 0b00000000 // 1 1 CRC disabled
#define SX1272_RX_CRC_MODE_ON 0b00000010 // 1 1 CRC enabled #define RADIOLIB_SX1272_RX_CRC_MODE_ON 0b00000010 // 1 1 CRC enabled
#define SX1272_LOW_DATA_RATE_OPT_OFF 0b00000000 // 0 0 low data rate optimization disabled #define RADIOLIB_SX1272_LOW_DATA_RATE_OPT_OFF 0b00000000 // 0 0 low data rate optimization disabled
#define SX1272_LOW_DATA_RATE_OPT_ON 0b00000001 // 0 0 low data rate optimization enabled, mandatory for SF 11 and 12 with BW 125 kHz #define RADIOLIB_SX1272_LOW_DATA_RATE_OPT_ON 0b00000001 // 0 0 low data rate optimization enabled, mandatory for SF 11 and 12 with BW 125 kHz
// SX127X_REG_MODEM_CONFIG_2 // RADIOLIB_SX127X_REG_MODEM_CONFIG_2
#define SX1272_AGC_AUTO_OFF 0b00000000 // 2 2 LNA gain set by REG_LNA #define RADIOLIB_SX1272_AGC_AUTO_OFF 0b00000000 // 2 2 LNA gain set by REG_LNA
#define SX1272_AGC_AUTO_ON 0b00000100 // 2 2 LNA gain set by internal AGC loop #define RADIOLIB_SX1272_AGC_AUTO_ON 0b00000100 // 2 2 LNA gain set by internal AGC loop
// SX127X_REG_VERSION // RADIOLIB_SX127X_REG_VERSION
#define SX1272_CHIP_VERSION 0x22 #define RADIOLIB_SX1272_CHIP_VERSION 0x22
// SX1272 FSK modem settings // SX1272 FSK modem settings
// SX127X_REG_OP_MODE // RADIOLIB_SX127X_REG_OP_MODE
#define SX1272_NO_SHAPING 0b00000000 // 4 3 data shaping: no shaping (default) #define RADIOLIB_SX1272_NO_SHAPING 0b00000000 // 4 3 data shaping: no shaping (default)
#define SX1272_FSK_GAUSSIAN_1_0 0b00001000 // 4 3 FSK modulation Gaussian filter, BT = 1.0 #define RADIOLIB_SX1272_FSK_GAUSSIAN_1_0 0b00001000 // 4 3 FSK modulation Gaussian filter, BT = 1.0
#define SX1272_FSK_GAUSSIAN_0_5 0b00010000 // 4 3 FSK modulation Gaussian filter, BT = 0.5 #define RADIOLIB_SX1272_FSK_GAUSSIAN_0_5 0b00010000 // 4 3 FSK modulation Gaussian filter, BT = 0.5
#define SX1272_FSK_GAUSSIAN_0_3 0b00011000 // 4 3 FSK modulation Gaussian filter, BT = 0.3 #define RADIOLIB_SX1272_FSK_GAUSSIAN_0_3 0b00011000 // 4 3 FSK modulation Gaussian filter, BT = 0.3
#define SX1272_OOK_FILTER_BR 0b00001000 // 4 3 OOK modulation filter, f_cutoff = BR #define RADIOLIB_SX1272_OOK_FILTER_BR 0b00001000 // 4 3 OOK modulation filter, f_cutoff = BR
#define SX1272_OOK_FILTER_2BR 0b00010000 // 4 3 OOK modulation filter, f_cutoff = 2*BR #define RADIOLIB_SX1272_OOK_FILTER_2BR 0b00010000 // 4 3 OOK modulation filter, f_cutoff = 2*BR
// SX127X_REG_PA_RAMP // RADIOLIB_SX127X_REG_PA_RAMP
#define SX1272_LOW_PN_TX_PLL_OFF 0b00010000 // 4 4 use standard PLL in transmit mode (default) #define RADIOLIB_SX1272_LOW_PN_TX_PLL_OFF 0b00010000 // 4 4 use standard PLL in transmit mode (default)
#define SX1272_LOW_PN_TX_PLL_ON 0b00000000 // 4 4 use lower phase noise PLL in transmit mode #define RADIOLIB_SX1272_LOW_PN_TX_PLL_ON 0b00000000 // 4 4 use lower phase noise PLL in transmit mode
// SX127X_REG_SYNC_CONFIG // RADIOLIB_SX127X_REG_SYNC_CONFIG
#define SX1272_FIFO_FILL_CONDITION_SYNC_ADDRESS 0b00000000 // 3 3 FIFO will be filled when sync address interrupt occurs (default) #define RADIOLIB_SX1272_FIFO_FILL_CONDITION_SYNC_ADDRESS 0b00000000 // 3 3 FIFO will be filled when sync address interrupt occurs (default)
#define SX1272_FIFO_FILL_CONDITION_ALWAYS 0b00001000 // 3 3 FIFO will be filled as long as this bit is set #define RADIOLIB_SX1272_FIFO_FILL_CONDITION_ALWAYS 0b00001000 // 3 3 FIFO will be filled as long as this bit is set
// SX1272_REG_AGC_REF // RADIOLIB_SX1272_REG_AGC_REF
#define SX1272_AGC_REFERENCE_LEVEL 0x13 // 5 0 floor reference for AGC thresholds: AgcRef = -174 + 10*log(2*RxBw) + 8 + AGC_REFERENCE_LEVEL [dBm] #define RADIOLIB_SX1272_AGC_REFERENCE_LEVEL 0x13 // 5 0 floor reference for AGC thresholds: AgcRef = -174 + 10*log(2*RxBw) + 8 + AGC_REFERENCE_LEVEL [dBm]
// SX1272_REG_AGC_THRESH_1 // RADIOLIB_SX1272_REG_AGC_THRESH_1
#define SX1272_AGC_STEP_1 0x0E // 4 0 1st AGC threshold #define RADIOLIB_SX1272_AGC_STEP_1 0x0E // 4 0 1st AGC threshold
// SX1272_REG_AGC_THRESH_2 // RADIOLIB_SX1272_REG_AGC_THRESH_2
#define SX1272_AGC_STEP_2 0x50 // 7 4 2nd AGC threshold #define RADIOLIB_SX1272_AGC_STEP_2 0x50 // 7 4 2nd AGC threshold
#define SX1272_AGC_STEP_3 0x0B // 4 0 3rd AGC threshold #define RADIOLIB_SX1272_AGC_STEP_3 0x0B // 4 0 3rd AGC threshold
// SX1272_REG_AGC_THRESH_3 // RADIOLIB_SX1272_REG_AGC_THRESH_3
#define SX1272_AGC_STEP_4 0xD0 // 7 4 4th AGC threshold #define RADIOLIB_SX1272_AGC_STEP_4 0xD0 // 7 4 4th AGC threshold
#define SX1272_AGC_STEP_5 0x0B // 4 0 5th AGC threshold #define RADIOLIB_SX1272_AGC_STEP_5 0x0B // 4 0 5th AGC threshold
// SX1272_REG_PLL_LOW_PN // RADIOLIB_SX1272_REG_PLL_LOW_PN
#define SX1272_PLL_LOW_PN_BANDWIDTH_75_KHZ 0b00000000 // 7 6 low phase noise PLL bandwidth: 75 kHz #define RADIOLIB_SX1272_PLL_LOW_PN_BANDWIDTH_75_KHZ 0b00000000 // 7 6 low phase noise PLL bandwidth: 75 kHz
#define SX1272_PLL_LOW_PN_BANDWIDTH_150_KHZ 0b01000000 // 7 6 150 kHz #define RADIOLIB_SX1272_PLL_LOW_PN_BANDWIDTH_150_KHZ 0b01000000 // 7 6 150 kHz
#define SX1272_PLL_LOW_PN_BANDWIDTH_225_KHZ 0b10000000 // 7 6 225 kHz #define RADIOLIB_SX1272_PLL_LOW_PN_BANDWIDTH_225_KHZ 0b10000000 // 7 6 225 kHz
#define SX1272_PLL_LOW_PN_BANDWIDTH_300_KHZ 0b11000000 // 7 6 300 kHz (default) #define RADIOLIB_SX1272_PLL_LOW_PN_BANDWIDTH_300_KHZ 0b11000000 // 7 6 300 kHz (default)
/*! /*!
\class SX1272 \class SX1272
@ -130,7 +130,7 @@ class SX1272: public SX127x {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t begin(float freq = 915.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0); int16_t begin(float freq = 915.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0);
/*! /*!
\brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module. \brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module.
@ -253,7 +253,7 @@ class SX1272: public SX127x {
\param enable Enable (true) or disable (false) CRC. \param enable Enable (true) or disable (false) CRC.
\param mode Set CRC mode to SX127X_CRC_WHITENING_TYPE_CCITT for CCITT, polynomial X16 + X12 + X5 + 1 (false) or SX127X_CRC_WHITENING_TYPE_IBM for IBM, polynomial X16 + X15 + X2 + 1 (true). Only valid in FSK mode. \param mode Set CRC mode to RADIOLIB_SX127X_CRC_WHITENING_TYPE_CCITT for CCITT, polynomial X16 + X12 + X5 + 1 (false) or RADIOLIB_SX127X_CRC_WHITENING_TYPE_IBM for IBM, polynomial X16 + X15 + X2 + 1 (true). Only valid in FSK mode.
\returns \ref status_codes \returns \ref status_codes
*/ */

View file

@ -7,7 +7,7 @@ SX1273::SX1273(Module* mod) : SX1272(mod) {
int16_t SX1273::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) { int16_t SX1273::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) {
// execute common part // execute common part
int16_t state = SX127x::begin(SX1272_CHIP_VERSION, syncWord, preambleLength); int16_t state = SX127x::begin(RADIOLIB_SX1272_CHIP_VERSION, syncWord, preambleLength);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure publicly accessible settings // configure publicly accessible settings
@ -38,24 +38,24 @@ int16_t SX1273::setSpreadingFactor(uint8_t sf) {
// check allowed spreading factor values // check allowed spreading factor values
switch(sf) { switch(sf) {
case 6: case 6:
newSpreadingFactor = SX127X_SF_6; newSpreadingFactor = RADIOLIB_SX127X_SF_6;
break; break;
case 7: case 7:
newSpreadingFactor = SX127X_SF_7; newSpreadingFactor = RADIOLIB_SX127X_SF_7;
break; break;
case 8: case 8:
newSpreadingFactor = SX127X_SF_8; newSpreadingFactor = RADIOLIB_SX127X_SF_8;
break; break;
case 9: case 9:
newSpreadingFactor = SX127X_SF_9; newSpreadingFactor = RADIOLIB_SX127X_SF_9;
break; break;
default: default:
return(ERR_INVALID_SPREADING_FACTOR); return(RADIOLIB_ERR_INVALID_SPREADING_FACTOR);
} }
// set spreading factor and if successful, save the new setting // set spreading factor and if successful, save the new setting
int16_t state = setSpreadingFactorRaw(newSpreadingFactor); int16_t state = setSpreadingFactorRaw(newSpreadingFactor);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_sf = sf; SX127x::_sf = sf;
} }

View file

@ -49,7 +49,7 @@ class SX1273: public SX1272 {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t begin(float freq = 915.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0); int16_t begin(float freq = 915.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0);
// configuration methods // configuration methods

View file

@ -7,7 +7,7 @@ SX1276::SX1276(Module* mod) : SX1278(mod) {
int16_t SX1276::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) { int16_t SX1276::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) {
// execute common part // execute common part
int16_t state = SX127x::begin(SX1278_CHIP_VERSION, syncWord, preambleLength); int16_t state = SX127x::begin(RADIOLIB_SX1278_CHIP_VERSION, syncWord, preambleLength);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure publicly accessible settings // configure publicly accessible settings
@ -34,7 +34,7 @@ int16_t SX1276::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t sync
int16_t SX1276::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t power, uint16_t preambleLength, bool enableOOK) { int16_t SX1276::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t power, uint16_t preambleLength, bool enableOOK) {
// execute common part // execute common part
int16_t state = SX127x::beginFSK(SX1278_CHIP_VERSION, br, freqDev, rxBw, preambleLength, enableOOK); int16_t state = SX127x::beginFSK(RADIOLIB_SX1278_CHIP_VERSION, br, freqDev, rxBw, preambleLength, enableOOK);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure settings not accessible by API // configure settings not accessible by API
@ -60,11 +60,11 @@ int16_t SX1276::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t
} }
int16_t SX1276::setFrequency(float freq) { int16_t SX1276::setFrequency(float freq) {
RADIOLIB_CHECK_RANGE(freq, 137.0, 1020.0, ERR_INVALID_FREQUENCY); RADIOLIB_CHECK_RANGE(freq, 137.0, 1020.0, RADIOLIB_ERR_INVALID_FREQUENCY);
// set frequency and if successful, save the new setting // set frequency and if successful, save the new setting
int16_t state = SX127x::setFrequencyRaw(freq); int16_t state = SX127x::setFrequencyRaw(freq);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_freq = freq; SX127x::_freq = freq;
} }
return(state); return(state);

View file

@ -49,7 +49,7 @@ class SX1276: public SX1278 {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0); int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0);
/*! /*!
\brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module. \brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module.

View file

@ -7,7 +7,7 @@ SX1277::SX1277(Module* mod) : SX1278(mod) {
int16_t SX1277::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) { int16_t SX1277::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) {
// execute common part // execute common part
int16_t state = SX127x::begin(SX1278_CHIP_VERSION, syncWord, preambleLength); int16_t state = SX127x::begin(RADIOLIB_SX1278_CHIP_VERSION, syncWord, preambleLength);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure publicly accessible settings // configure publicly accessible settings
@ -34,7 +34,7 @@ int16_t SX1277::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t sync
int16_t SX1277::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t power, uint16_t preambleLength, bool enableOOK) { int16_t SX1277::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t power, uint16_t preambleLength, bool enableOOK) {
// execute common part // execute common part
int16_t state = SX127x::beginFSK(SX1278_CHIP_VERSION, br, freqDev, rxBw, preambleLength, enableOOK); int16_t state = SX127x::beginFSK(RADIOLIB_SX1278_CHIP_VERSION, br, freqDev, rxBw, preambleLength, enableOOK);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure settings not accessible by API // configure settings not accessible by API
@ -60,11 +60,11 @@ int16_t SX1277::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t
} }
int16_t SX1277::setFrequency(float freq) { int16_t SX1277::setFrequency(float freq) {
RADIOLIB_CHECK_RANGE(freq, 137.0, 1020.0, ERR_INVALID_FREQUENCY); RADIOLIB_CHECK_RANGE(freq, 137.0, 1020.0, RADIOLIB_ERR_INVALID_FREQUENCY);
// set frequency and if successful, save the new setting // set frequency and if successful, save the new setting
int16_t state = SX127x::setFrequencyRaw(freq); int16_t state = SX127x::setFrequencyRaw(freq);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_freq = freq; SX127x::_freq = freq;
} }
return(state); return(state);
@ -76,24 +76,24 @@ int16_t SX1277::setSpreadingFactor(uint8_t sf) {
// check allowed spreading factor values // check allowed spreading factor values
switch(sf) { switch(sf) {
case 6: case 6:
newSpreadingFactor = SX127X_SF_6; newSpreadingFactor = RADIOLIB_SX127X_SF_6;
break; break;
case 7: case 7:
newSpreadingFactor = SX127X_SF_7; newSpreadingFactor = RADIOLIB_SX127X_SF_7;
break; break;
case 8: case 8:
newSpreadingFactor = SX127X_SF_8; newSpreadingFactor = RADIOLIB_SX127X_SF_8;
break; break;
case 9: case 9:
newSpreadingFactor = SX127X_SF_9; newSpreadingFactor = RADIOLIB_SX127X_SF_9;
break; break;
default: default:
return(ERR_INVALID_SPREADING_FACTOR); return(RADIOLIB_ERR_INVALID_SPREADING_FACTOR);
} }
// set spreading factor and if successful, save the new setting // set spreading factor and if successful, save the new setting
int16_t state = SX1278::setSpreadingFactorRaw(newSpreadingFactor); int16_t state = SX1278::setSpreadingFactorRaw(newSpreadingFactor);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_sf = sf; SX127x::_sf = sf;
} }

View file

@ -49,7 +49,7 @@ class SX1277: public SX1278 {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0); int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0);
/*! /*!
\brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module. \brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module.

View file

@ -7,7 +7,7 @@ SX1278::SX1278(Module* mod) : SX127x(mod) {
int16_t SX1278::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) { int16_t SX1278::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) {
// execute common part // execute common part
int16_t state = SX127x::begin(SX1278_CHIP_VERSION, syncWord, preambleLength); int16_t state = SX127x::begin(RADIOLIB_SX1278_CHIP_VERSION, syncWord, preambleLength);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure publicly accessible settings // configure publicly accessible settings
@ -34,7 +34,7 @@ int16_t SX1278::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t sync
int16_t SX1278::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t power, uint16_t preambleLength, bool enableOOK) { int16_t SX1278::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t power, uint16_t preambleLength, bool enableOOK) {
// execute common part // execute common part
int16_t state = SX127x::beginFSK(SX1278_CHIP_VERSION, br, freqDev, rxBw, preambleLength, enableOOK); int16_t state = SX127x::beginFSK(RADIOLIB_SX1278_CHIP_VERSION, br, freqDev, rxBw, preambleLength, enableOOK);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure settings not accessible by API // configure settings not accessible by API
@ -60,19 +60,19 @@ int16_t SX1278::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t
} }
void SX1278::reset() { void SX1278::reset() {
Module::pinMode(_mod->getRst(), OUTPUT); _mod->pinMode(_mod->getRst(), OUTPUT);
Module::digitalWrite(_mod->getRst(), LOW); _mod->digitalWrite(_mod->getRst(), LOW);
Module::delay(1); _mod->delay(1);
Module::digitalWrite(_mod->getRst(), HIGH); _mod->digitalWrite(_mod->getRst(), HIGH);
Module::delay(5); _mod->delay(5);
} }
int16_t SX1278::setFrequency(float freq) { int16_t SX1278::setFrequency(float freq) {
RADIOLIB_CHECK_RANGE(freq, 137.0, 525.0, ERR_INVALID_FREQUENCY); RADIOLIB_CHECK_RANGE(freq, 137.0, 525.0, RADIOLIB_ERR_INVALID_FREQUENCY);
// set frequency and if successful, save the new setting // set frequency and if successful, save the new setting
int16_t state = SX127x::setFrequencyRaw(freq); int16_t state = SX127x::setFrequencyRaw(freq);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_freq = freq; SX127x::_freq = freq;
} }
return(state); return(state);
@ -80,40 +80,40 @@ int16_t SX1278::setFrequency(float freq) {
int16_t SX1278::setBandwidth(float bw) { int16_t SX1278::setBandwidth(float bw) {
// check active modem // check active modem
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
uint8_t newBandwidth; uint8_t newBandwidth;
// check allowed bandwidth values // check allowed bandwidth values
if(fabs(bw - 7.8) <= 0.001) { if(fabs(bw - 7.8) <= 0.001) {
newBandwidth = SX1278_BW_7_80_KHZ; newBandwidth = RADIOLIB_SX1278_BW_7_80_KHZ;
} else if(fabs(bw - 10.4) <= 0.001) { } else if(fabs(bw - 10.4) <= 0.001) {
newBandwidth = SX1278_BW_10_40_KHZ; newBandwidth = RADIOLIB_SX1278_BW_10_40_KHZ;
} else if(fabs(bw - 15.6) <= 0.001) { } else if(fabs(bw - 15.6) <= 0.001) {
newBandwidth = SX1278_BW_15_60_KHZ; newBandwidth = RADIOLIB_SX1278_BW_15_60_KHZ;
} else if(fabs(bw - 20.8) <= 0.001) { } else if(fabs(bw - 20.8) <= 0.001) {
newBandwidth = SX1278_BW_20_80_KHZ; newBandwidth = RADIOLIB_SX1278_BW_20_80_KHZ;
} else if(fabs(bw - 31.25) <= 0.001) { } else if(fabs(bw - 31.25) <= 0.001) {
newBandwidth = SX1278_BW_31_25_KHZ; newBandwidth = RADIOLIB_SX1278_BW_31_25_KHZ;
} else if(fabs(bw - 41.7) <= 0.001) { } else if(fabs(bw - 41.7) <= 0.001) {
newBandwidth = SX1278_BW_41_70_KHZ; newBandwidth = RADIOLIB_SX1278_BW_41_70_KHZ;
} else if(fabs(bw - 62.5) <= 0.001) { } else if(fabs(bw - 62.5) <= 0.001) {
newBandwidth = SX1278_BW_62_50_KHZ; newBandwidth = RADIOLIB_SX1278_BW_62_50_KHZ;
} else if(fabs(bw - 125.0) <= 0.001) { } else if(fabs(bw - 125.0) <= 0.001) {
newBandwidth = SX1278_BW_125_00_KHZ; newBandwidth = RADIOLIB_SX1278_BW_125_00_KHZ;
} else if(fabs(bw - 250.0) <= 0.001) { } else if(fabs(bw - 250.0) <= 0.001) {
newBandwidth = SX1278_BW_250_00_KHZ; newBandwidth = RADIOLIB_SX1278_BW_250_00_KHZ;
} else if(fabs(bw - 500.0) <= 0.001) { } else if(fabs(bw - 500.0) <= 0.001) {
newBandwidth = SX1278_BW_500_00_KHZ; newBandwidth = RADIOLIB_SX1278_BW_500_00_KHZ;
} else { } else {
return(ERR_INVALID_BANDWIDTH); return(RADIOLIB_ERR_INVALID_BANDWIDTH);
} }
// set bandwidth and if successful, save the new setting // set bandwidth and if successful, save the new setting
int16_t state = SX1278::setBandwidthRaw(newBandwidth); int16_t state = SX1278::setBandwidthRaw(newBandwidth);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_bw = bw; SX127x::_bw = bw;
// calculate symbol length and set low data rate optimization, if auto-configuration is enabled // calculate symbol length and set low data rate optimization, if auto-configuration is enabled
@ -123,9 +123,9 @@ int16_t SX1278::setBandwidth(float bw) {
RADIOLIB_DEBUG_PRINT(symbolLength); RADIOLIB_DEBUG_PRINT(symbolLength);
RADIOLIB_DEBUG_PRINTLN(" ms"); RADIOLIB_DEBUG_PRINTLN(" ms");
if(symbolLength >= 16.0) { if(symbolLength >= 16.0) {
state = _mod->SPIsetRegValue(SX1278_REG_MODEM_CONFIG_3, SX1278_LOW_DATA_RATE_OPT_ON, 3, 3); state = _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_MODEM_CONFIG_3, RADIOLIB_SX1278_LOW_DATA_RATE_OPT_ON, 3, 3);
} else { } else {
state = _mod->SPIsetRegValue(SX1278_REG_MODEM_CONFIG_3, SX1278_LOW_DATA_RATE_OPT_OFF, 3, 3); state = _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_MODEM_CONFIG_3, RADIOLIB_SX1278_LOW_DATA_RATE_OPT_OFF, 3, 3);
} }
} }
} }
@ -134,8 +134,8 @@ int16_t SX1278::setBandwidth(float bw) {
int16_t SX1278::setSpreadingFactor(uint8_t sf) { int16_t SX1278::setSpreadingFactor(uint8_t sf) {
// check active modem // check active modem
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
uint8_t newSpreadingFactor; uint8_t newSpreadingFactor;
@ -143,33 +143,33 @@ int16_t SX1278::setSpreadingFactor(uint8_t sf) {
// check allowed spreading factor values // check allowed spreading factor values
switch(sf) { switch(sf) {
case 6: case 6:
newSpreadingFactor = SX127X_SF_6; newSpreadingFactor = RADIOLIB_SX127X_SF_6;
break; break;
case 7: case 7:
newSpreadingFactor = SX127X_SF_7; newSpreadingFactor = RADIOLIB_SX127X_SF_7;
break; break;
case 8: case 8:
newSpreadingFactor = SX127X_SF_8; newSpreadingFactor = RADIOLIB_SX127X_SF_8;
break; break;
case 9: case 9:
newSpreadingFactor = SX127X_SF_9; newSpreadingFactor = RADIOLIB_SX127X_SF_9;
break; break;
case 10: case 10:
newSpreadingFactor = SX127X_SF_10; newSpreadingFactor = RADIOLIB_SX127X_SF_10;
break; break;
case 11: case 11:
newSpreadingFactor = SX127X_SF_11; newSpreadingFactor = RADIOLIB_SX127X_SF_11;
break; break;
case 12: case 12:
newSpreadingFactor = SX127X_SF_12; newSpreadingFactor = RADIOLIB_SX127X_SF_12;
break; break;
default: default:
return(ERR_INVALID_SPREADING_FACTOR); return(RADIOLIB_ERR_INVALID_SPREADING_FACTOR);
} }
// set spreading factor and if successful, save the new setting // set spreading factor and if successful, save the new setting
int16_t state = SX1278::setSpreadingFactorRaw(newSpreadingFactor); int16_t state = SX1278::setSpreadingFactorRaw(newSpreadingFactor);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_sf = sf; SX127x::_sf = sf;
// calculate symbol length and set low data rate optimization, if auto-configuration is enabled // calculate symbol length and set low data rate optimization, if auto-configuration is enabled
@ -179,9 +179,9 @@ int16_t SX1278::setSpreadingFactor(uint8_t sf) {
RADIOLIB_DEBUG_PRINT(symbolLength); RADIOLIB_DEBUG_PRINT(symbolLength);
RADIOLIB_DEBUG_PRINTLN(" ms"); RADIOLIB_DEBUG_PRINTLN(" ms");
if(symbolLength >= 16.0) { if(symbolLength >= 16.0) {
state = _mod->SPIsetRegValue(SX1278_REG_MODEM_CONFIG_3, SX1278_LOW_DATA_RATE_OPT_ON, 3, 3); state = _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_MODEM_CONFIG_3, RADIOLIB_SX1278_LOW_DATA_RATE_OPT_ON, 3, 3);
} else { } else {
state = _mod->SPIsetRegValue(SX1278_REG_MODEM_CONFIG_3, SX1278_LOW_DATA_RATE_OPT_OFF, 3, 3); state = _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_MODEM_CONFIG_3, RADIOLIB_SX1278_LOW_DATA_RATE_OPT_OFF, 3, 3);
} }
} }
} }
@ -190,8 +190,8 @@ int16_t SX1278::setSpreadingFactor(uint8_t sf) {
int16_t SX1278::setCodingRate(uint8_t cr) { int16_t SX1278::setCodingRate(uint8_t cr) {
// check active modem // check active modem
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
uint8_t newCodingRate; uint8_t newCodingRate;
@ -199,24 +199,24 @@ int16_t SX1278::setCodingRate(uint8_t cr) {
// check allowed coding rate values // check allowed coding rate values
switch(cr) { switch(cr) {
case 5: case 5:
newCodingRate = SX1278_CR_4_5; newCodingRate = RADIOLIB_SX1278_CR_4_5;
break; break;
case 6: case 6:
newCodingRate = SX1278_CR_4_6; newCodingRate = RADIOLIB_SX1278_CR_4_6;
break; break;
case 7: case 7:
newCodingRate = SX1278_CR_4_7; newCodingRate = RADIOLIB_SX1278_CR_4_7;
break; break;
case 8: case 8:
newCodingRate = SX1278_CR_4_8; newCodingRate = RADIOLIB_SX1278_CR_4_8;
break; break;
default: default:
return(ERR_INVALID_CODING_RATE); return(RADIOLIB_ERR_INVALID_CODING_RATE);
} }
// set coding rate and if successful, save the new setting // set coding rate and if successful, save the new setting
int16_t state = SX1278::setCodingRateRaw(newCodingRate); int16_t state = SX1278::setCodingRateRaw(newCodingRate);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_cr = cr; SX127x::_cr = cr;
} }
return(state); return(state);
@ -226,11 +226,11 @@ int16_t SX1278::setOutputPower(int8_t power, bool useRfo) {
// check allowed power range // check allowed power range
if(useRfo) { if(useRfo) {
// RFO output // RFO output
RADIOLIB_CHECK_RANGE(power, -3, 15, ERR_INVALID_OUTPUT_POWER); RADIOLIB_CHECK_RANGE(power, -3, 15, RADIOLIB_ERR_INVALID_OUTPUT_POWER);
} else { } else {
// PA_BOOST output, check high-power operation // PA_BOOST output, check high-power operation
if(power != 20) { if(power != 20) {
RADIOLIB_CHECK_RANGE(power, 2, 17, ERR_INVALID_OUTPUT_POWER); RADIOLIB_CHECK_RANGE(power, 2, 17, RADIOLIB_ERR_INVALID_OUTPUT_POWER);
} }
} }
@ -241,28 +241,28 @@ int16_t SX1278::setOutputPower(int8_t power, bool useRfo) {
uint8_t paCfg = 0; uint8_t paCfg = 0;
if(power < 0) { if(power < 0) {
// low power mode RFO output // low power mode RFO output
paCfg = SX1278_LOW_POWER | (power + 3); paCfg = RADIOLIB_SX1278_LOW_POWER | (power + 3);
} else { } else {
// high power mode RFO output // high power mode RFO output
paCfg = SX1278_MAX_POWER | power; paCfg = RADIOLIB_SX1278_MAX_POWER | power;
} }
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, SX127X_PA_SELECT_RFO, 7, 7); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, RADIOLIB_SX127X_PA_SELECT_RFO, 7, 7);
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, paCfg, 6, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, paCfg, 6, 0);
state |= _mod->SPIsetRegValue(SX1278_REG_PA_DAC, SX127X_PA_BOOST_OFF, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_PA_DAC, RADIOLIB_SX127X_PA_BOOST_OFF, 2, 0);
} else { } else {
if(power != 20) { if(power != 20) {
// power is 2 - 17 dBm, enable PA1 + PA2 on PA_BOOST // power is 2 - 17 dBm, enable PA1 + PA2 on PA_BOOST
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, SX127X_PA_SELECT_BOOST, 7, 7); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, RADIOLIB_SX127X_PA_SELECT_BOOST, 7, 7);
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, SX1278_MAX_POWER | (power - 2), 6, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, RADIOLIB_SX1278_MAX_POWER | (power - 2), 6, 0);
state |= _mod->SPIsetRegValue(SX1278_REG_PA_DAC, SX127X_PA_BOOST_OFF, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_PA_DAC, RADIOLIB_SX127X_PA_BOOST_OFF, 2, 0);
} else { } else {
// power is 20 dBm, enable PA1 + PA2 on PA_BOOST and enable high power control // power is 20 dBm, enable PA1 + PA2 on PA_BOOST and enable high power control
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, SX127X_PA_SELECT_BOOST, 7, 7); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, RADIOLIB_SX127X_PA_SELECT_BOOST, 7, 7);
state |= _mod->SPIsetRegValue(SX127X_REG_PA_CONFIG, SX1278_MAX_POWER | 0x0F, 6, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_CONFIG, RADIOLIB_SX1278_MAX_POWER | 0x0F, 6, 0);
state |= _mod->SPIsetRegValue(SX1278_REG_PA_DAC, SX127X_PA_BOOST_ON, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_PA_DAC, RADIOLIB_SX127X_PA_BOOST_ON, 2, 0);
} }
} }
@ -273,7 +273,7 @@ int16_t SX1278::setOutputPower(int8_t power, bool useRfo) {
int16_t SX1278::setGain(uint8_t gain) { int16_t SX1278::setGain(uint8_t gain) {
// check allowed range // check allowed range
if(gain > 6) { if(gain > 6) {
return(ERR_INVALID_GAIN); return(RADIOLIB_ERR_INVALID_GAIN);
} }
// set mode to standby // set mode to standby
@ -281,24 +281,24 @@ int16_t SX1278::setGain(uint8_t gain) {
// get modem // get modem
int16_t modem = getActiveModem(); int16_t modem = getActiveModem();
if(modem == SX127X_LORA){ if(modem == RADIOLIB_SX127X_LORA){
// set gain // set gain
if(gain == 0) { if(gain == 0) {
// gain set to 0, enable AGC loop // gain set to 0, enable AGC loop
state |= _mod->SPIsetRegValue(SX1278_REG_MODEM_CONFIG_3, SX1278_AGC_AUTO_ON, 2, 2); state |= _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_MODEM_CONFIG_3, RADIOLIB_SX1278_AGC_AUTO_ON, 2, 2);
} else { } else {
state |= _mod->SPIsetRegValue(SX1278_REG_MODEM_CONFIG_3, SX1278_AGC_AUTO_OFF, 2, 2); state |= _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_MODEM_CONFIG_3, RADIOLIB_SX1278_AGC_AUTO_OFF, 2, 2);
state |= _mod->SPIsetRegValue(SX127X_REG_LNA, (gain << 5) | SX127X_LNA_BOOST_ON); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_LNA, (gain << 5) | RADIOLIB_SX127X_LNA_BOOST_ON);
} }
} else if(modem == SX127X_FSK_OOK) { } else if(modem == RADIOLIB_SX127X_FSK_OOK) {
// set gain // set gain
if(gain == 0) { if(gain == 0) {
// gain set to 0, enable AGC loop // gain set to 0, enable AGC loop
state |= _mod->SPIsetRegValue(SX127X_REG_RX_CONFIG, SX127X_AGC_AUTO_ON, 3, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_RX_CONFIG, RADIOLIB_SX127X_AGC_AUTO_ON, 3, 3);
} else { } else {
state |= _mod->SPIsetRegValue(SX127X_REG_RX_CONFIG, SX127X_AGC_AUTO_ON, 3, 3); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_RX_CONFIG, RADIOLIB_SX127X_AGC_AUTO_ON, 3, 3);
state |= _mod->SPIsetRegValue(SX127X_REG_LNA, (gain << 5) | SX127X_LNA_BOOST_ON); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_LNA, (gain << 5) | RADIOLIB_SX127X_LNA_BOOST_ON);
} }
} }
@ -308,13 +308,13 @@ int16_t SX1278::setGain(uint8_t gain) {
int16_t SX1278::setDataShaping(uint8_t sh) { int16_t SX1278::setDataShaping(uint8_t sh) {
// check active modem // check active modem
if(getActiveModem() != SX127X_FSK_OOK) { if(getActiveModem() != RADIOLIB_SX127X_FSK_OOK) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
// check modulation // check modulation
if(SX127x::_ook) { if(SX127x::_ook) {
return(ERR_INVALID_MODULATION); return(RADIOLIB_ERR_INVALID_MODULATION);
} }
// set mode to standby // set mode to standby
@ -324,27 +324,27 @@ int16_t SX1278::setDataShaping(uint8_t sh) {
// set data shaping // set data shaping
switch(sh) { switch(sh) {
case RADIOLIB_SHAPING_NONE: case RADIOLIB_SHAPING_NONE:
return(_mod->SPIsetRegValue(SX127X_REG_PA_RAMP, SX1278_NO_SHAPING, 6, 5)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_RAMP, RADIOLIB_SX1278_NO_SHAPING, 6, 5));
case RADIOLIB_SHAPING_0_3: case RADIOLIB_SHAPING_0_3:
return(_mod->SPIsetRegValue(SX127X_REG_PA_RAMP, SX1278_FSK_GAUSSIAN_0_3, 6, 5)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_RAMP, RADIOLIB_SX1278_FSK_GAUSSIAN_0_3, 6, 5));
case RADIOLIB_SHAPING_0_5: case RADIOLIB_SHAPING_0_5:
return(_mod->SPIsetRegValue(SX127X_REG_PA_RAMP, SX1278_FSK_GAUSSIAN_0_5, 6, 5)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_RAMP, RADIOLIB_SX1278_FSK_GAUSSIAN_0_5, 6, 5));
case RADIOLIB_SHAPING_1_0: case RADIOLIB_SHAPING_1_0:
return(_mod->SPIsetRegValue(SX127X_REG_PA_RAMP, SX1278_FSK_GAUSSIAN_1_0, 6, 5)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_RAMP, RADIOLIB_SX1278_FSK_GAUSSIAN_1_0, 6, 5));
default: default:
return(ERR_INVALID_DATA_SHAPING); return(RADIOLIB_ERR_INVALID_DATA_SHAPING);
} }
} }
int16_t SX1278::setDataShapingOOK(uint8_t sh) { int16_t SX1278::setDataShapingOOK(uint8_t sh) {
// check active modem // check active modem
if(getActiveModem() != SX127X_FSK_OOK) { if(getActiveModem() != RADIOLIB_SX127X_FSK_OOK) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
// check modulation // check modulation
if(!SX127x::_ook) { if(!SX127x::_ook) {
return(ERR_INVALID_MODULATION); return(RADIOLIB_ERR_INVALID_MODULATION);
} }
// set mode to standby // set mode to standby
@ -353,31 +353,31 @@ int16_t SX1278::setDataShapingOOK(uint8_t sh) {
// set data shaping // set data shaping
switch(sh) { switch(sh) {
case 0: case 0:
state |= _mod->SPIsetRegValue(SX127X_REG_PA_RAMP, SX1278_NO_SHAPING, 6, 5); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_RAMP, RADIOLIB_SX1278_NO_SHAPING, 6, 5);
break; break;
case 1: case 1:
state |= _mod->SPIsetRegValue(SX127X_REG_PA_RAMP, SX1278_OOK_FILTER_BR, 6, 5); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_RAMP, RADIOLIB_SX1278_OOK_FILTER_BR, 6, 5);
break; break;
case 2: case 2:
state |= _mod->SPIsetRegValue(SX127X_REG_PA_RAMP, SX1278_OOK_FILTER_2BR, 6, 5); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PA_RAMP, RADIOLIB_SX1278_OOK_FILTER_2BR, 6, 5);
break; break;
default: default:
return(ERR_INVALID_DATA_SHAPING); return(RADIOLIB_ERR_INVALID_DATA_SHAPING);
} }
return(state); return(state);
} }
float SX1278::getRSSI(bool skipReceive) { float SX1278::getRSSI(bool skipReceive) {
if(getActiveModem() == SX127X_LORA) { if(getActiveModem() == RADIOLIB_SX127X_LORA) {
// for LoRa, get RSSI of the last packet // for LoRa, get RSSI of the last packet
float lastPacketRSSI; float lastPacketRSSI;
// RSSI calculation uses different constant for low-frequency and high-frequency ports // RSSI calculation uses different constant for low-frequency and high-frequency ports
if(_freq < 868.0) { if(_freq < 868.0) {
lastPacketRSSI = -164 + _mod->SPIgetRegValue(SX127X_REG_PKT_RSSI_VALUE); lastPacketRSSI = -164 + _mod->SPIgetRegValue(RADIOLIB_SX127X_REG_PKT_RSSI_VALUE);
} else { } else {
lastPacketRSSI = -157 + _mod->SPIgetRegValue(SX127X_REG_PKT_RSSI_VALUE); lastPacketRSSI = -157 + _mod->SPIgetRegValue(RADIOLIB_SX127X_REG_PKT_RSSI_VALUE);
} }
// spread-spectrum modulation signal can be received below noise floor // spread-spectrum modulation signal can be received below noise floor
@ -396,7 +396,7 @@ float SX1278::getRSSI(bool skipReceive) {
} }
// read the value for FSK // read the value for FSK
float rssi = (float)_mod->SPIgetRegValue(SX127X_REG_RSSI_VALUE_FSK) / -2.0; float rssi = (float)_mod->SPIgetRegValue(RADIOLIB_SX127X_REG_RSSI_VALUE_FSK) / -2.0;
// set mode back to standby // set mode back to standby
if(!skipReceive) { if(!skipReceive) {
@ -409,61 +409,61 @@ float SX1278::getRSSI(bool skipReceive) {
} }
int16_t SX1278::setCRC(bool enable, bool mode) { int16_t SX1278::setCRC(bool enable, bool mode) {
if(getActiveModem() == SX127X_LORA) { if(getActiveModem() == RADIOLIB_SX127X_LORA) {
// set LoRa CRC // set LoRa CRC
SX127x::_crcEnabled = enable; SX127x::_crcEnabled = enable;
if(enable) { if(enable) {
return(_mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, SX1278_RX_CRC_MODE_ON, 2, 2)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, RADIOLIB_SX1278_RX_CRC_MODE_ON, 2, 2));
} else { } else {
return(_mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, SX1278_RX_CRC_MODE_OFF, 2, 2)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, RADIOLIB_SX1278_RX_CRC_MODE_OFF, 2, 2));
} }
} else { } else {
// set FSK CRC // set FSK CRC
int16_t state = ERR_NONE; int16_t state = RADIOLIB_ERR_NONE;
if(enable) { if(enable) {
state = _mod->SPIsetRegValue(SX127X_REG_PACKET_CONFIG_1, SX127X_CRC_ON, 4, 4); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PACKET_CONFIG_1, RADIOLIB_SX127X_CRC_ON, 4, 4);
} else { } else {
state = _mod->SPIsetRegValue(SX127X_REG_PACKET_CONFIG_1, SX127X_CRC_OFF, 4, 4); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PACKET_CONFIG_1, RADIOLIB_SX127X_CRC_OFF, 4, 4);
} }
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// set FSK CRC mode // set FSK CRC mode
if(mode) { if(mode) {
return(_mod->SPIsetRegValue(SX127X_REG_PACKET_CONFIG_1, SX127X_CRC_WHITENING_TYPE_IBM, 0, 0)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PACKET_CONFIG_1, RADIOLIB_SX127X_CRC_WHITENING_TYPE_IBM, 0, 0));
} else { } else {
return(_mod->SPIsetRegValue(SX127X_REG_PACKET_CONFIG_1, SX127X_CRC_WHITENING_TYPE_CCITT, 0, 0)); return(_mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PACKET_CONFIG_1, RADIOLIB_SX127X_CRC_WHITENING_TYPE_CCITT, 0, 0));
} }
} }
} }
int16_t SX1278::forceLDRO(bool enable) { int16_t SX1278::forceLDRO(bool enable) {
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
_ldroAuto = false; _ldroAuto = false;
if(enable) { if(enable) {
return(_mod->SPIsetRegValue(SX1278_REG_MODEM_CONFIG_3, SX1278_LOW_DATA_RATE_OPT_ON, 3, 3)); return(_mod->SPIsetRegValue(RADIOLIB_SX1278_REG_MODEM_CONFIG_3, RADIOLIB_SX1278_LOW_DATA_RATE_OPT_ON, 3, 3));
} else { } else {
return(_mod->SPIsetRegValue(SX1278_REG_MODEM_CONFIG_3, SX1278_LOW_DATA_RATE_OPT_OFF, 3, 3)); return(_mod->SPIsetRegValue(RADIOLIB_SX1278_REG_MODEM_CONFIG_3, RADIOLIB_SX1278_LOW_DATA_RATE_OPT_OFF, 3, 3));
} }
} }
int16_t SX1278::autoLDRO() { int16_t SX1278::autoLDRO() {
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
_ldroAuto = true; _ldroAuto = true;
return(ERR_NONE); return(RADIOLIB_ERR_NONE);
} }
int16_t SX1278::implicitHeader(size_t len) { int16_t SX1278::implicitHeader(size_t len) {
return(setHeaderType(SX1278_HEADER_IMPL_MODE, len)); return(setHeaderType(RADIOLIB_SX1278_HEADER_IMPL_MODE, len));
} }
int16_t SX1278::explicitHeader() { int16_t SX1278::explicitHeader() {
return(setHeaderType(SX1278_HEADER_EXPL_MODE)); return(setHeaderType(RADIOLIB_SX1278_HEADER_EXPL_MODE));
} }
int16_t SX1278::setBandwidthRaw(uint8_t newBandwidth) { int16_t SX1278::setBandwidthRaw(uint8_t newBandwidth) {
@ -471,7 +471,7 @@ int16_t SX1278::setBandwidthRaw(uint8_t newBandwidth) {
int16_t state = SX127x::standby(); int16_t state = SX127x::standby();
// write register // write register
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, newBandwidth, 7, 4); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, newBandwidth, 7, 4);
return(state); return(state);
} }
@ -480,16 +480,16 @@ int16_t SX1278::setSpreadingFactorRaw(uint8_t newSpreadingFactor) {
int16_t state = SX127x::standby(); int16_t state = SX127x::standby();
// write registers // write registers
if(newSpreadingFactor == SX127X_SF_6) { if(newSpreadingFactor == RADIOLIB_SX127X_SF_6) {
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1278_HEADER_IMPL_MODE, 0, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1278_HEADER_IMPL_MODE, 0, 0);
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, SX127X_SF_6 | SX127X_TX_MODE_SINGLE | (SX127x::_crcEnabled ? SX1278_RX_CRC_MODE_ON : SX1278_RX_CRC_MODE_OFF), 7, 2); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, RADIOLIB_SX127X_SF_6 | RADIOLIB_SX127X_TX_MODE_SINGLE | (SX127x::_crcEnabled ? RADIOLIB_SX1278_RX_CRC_MODE_ON : RADIOLIB_SX1278_RX_CRC_MODE_OFF), 7, 2);
state |= _mod->SPIsetRegValue(SX127X_REG_DETECT_OPTIMIZE, SX127X_DETECT_OPTIMIZE_SF_6, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_DETECT_OPTIMIZE, RADIOLIB_SX127X_DETECT_OPTIMIZE_SF_6, 2, 0);
state |= _mod->SPIsetRegValue(SX127X_REG_DETECTION_THRESHOLD, SX127X_DETECTION_THRESHOLD_SF_6); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_DETECTION_THRESHOLD, RADIOLIB_SX127X_DETECTION_THRESHOLD_SF_6);
} else { } else {
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, SX1278_HEADER_EXPL_MODE, 0, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, RADIOLIB_SX1278_HEADER_EXPL_MODE, 0, 0);
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_2, newSpreadingFactor | SX127X_TX_MODE_SINGLE | (SX127x::_crcEnabled ? SX1278_RX_CRC_MODE_ON : SX1278_RX_CRC_MODE_OFF), 7, 2); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_2, newSpreadingFactor | RADIOLIB_SX127X_TX_MODE_SINGLE | (SX127x::_crcEnabled ? RADIOLIB_SX1278_RX_CRC_MODE_ON : RADIOLIB_SX1278_RX_CRC_MODE_OFF), 7, 2);
state |= _mod->SPIsetRegValue(SX127X_REG_DETECT_OPTIMIZE, SX127X_DETECT_OPTIMIZE_SF_7_12, 2, 0); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_DETECT_OPTIMIZE, RADIOLIB_SX127X_DETECT_OPTIMIZE_SF_7_12, 2, 0);
state |= _mod->SPIsetRegValue(SX127X_REG_DETECTION_THRESHOLD, SX127X_DETECTION_THRESHOLD_SF_7_12); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_DETECTION_THRESHOLD, RADIOLIB_SX127X_DETECTION_THRESHOLD_SF_7_12);
} }
return(state); return(state);
} }
@ -499,22 +499,22 @@ int16_t SX1278::setCodingRateRaw(uint8_t newCodingRate) {
int16_t state = SX127x::standby(); int16_t state = SX127x::standby();
// write register // write register
state |= _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, newCodingRate, 3, 1); state |= _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, newCodingRate, 3, 1);
return(state); return(state);
} }
int16_t SX1278::setHeaderType(uint8_t headerType, size_t len) { int16_t SX1278::setHeaderType(uint8_t headerType, size_t len) {
// check active modem // check active modem
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return(ERR_WRONG_MODEM); return(RADIOLIB_ERR_WRONG_MODEM);
} }
// set requested packet mode // set requested packet mode
int16_t state = _mod->SPIsetRegValue(SX127X_REG_MODEM_CONFIG_1, headerType, 0, 0); int16_t state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_MODEM_CONFIG_1, headerType, 0, 0);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// set length to register // set length to register
state = _mod->SPIsetRegValue(SX127X_REG_PAYLOAD_LENGTH, len); state = _mod->SPIsetRegValue(RADIOLIB_SX127X_REG_PAYLOAD_LENGTH, len);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// update cached value // update cached value
@ -529,13 +529,13 @@ int16_t SX1278::configFSK() {
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// set fast PLL hop // set fast PLL hop
state = _mod->SPIsetRegValue(SX1278_REG_PLL_HOP, SX127X_FAST_HOP_ON, 7, 7); state = _mod->SPIsetRegValue(RADIOLIB_SX1278_REG_PLL_HOP, RADIOLIB_SX127X_FAST_HOP_ON, 7, 7);
return(state); return(state);
} }
void SX1278::errataFix(bool rx) { void SX1278::errataFix(bool rx) {
// only apply in LoRa mode // only apply in LoRa mode
if(getActiveModem() != SX127X_LORA) { if(getActiveModem() != RADIOLIB_SX127X_LORA) {
return; return;
} }

View file

@ -9,91 +9,91 @@
#include "SX127x.h" #include "SX127x.h"
// SX1278 specific register map // SX1278 specific register map
#define SX1278_REG_MODEM_CONFIG_3 0x26 #define RADIOLIB_SX1278_REG_MODEM_CONFIG_3 0x26
#define SX1278_REG_PLL_HOP 0x44 #define RADIOLIB_SX1278_REG_PLL_HOP 0x44
#define SX1278_REG_TCXO 0x4B #define RADIOLIB_SX1278_REG_TCXO 0x4B
#define SX1278_REG_PA_DAC 0x4D #define RADIOLIB_SX1278_REG_PA_DAC 0x4D
#define SX1278_REG_FORMER_TEMP 0x5B #define RADIOLIB_SX1278_REG_FORMER_TEMP 0x5B
#define SX1278_REG_REG_BIT_RATE_FRAC 0x5D #define RADIOLIB_SX1278_REG_REG_BIT_RATE_FRAC 0x5D
#define SX1278_REG_AGC_REF 0x61 #define RADIOLIB_SX1278_REG_AGC_REF 0x61
#define SX1278_REG_AGC_THRESH_1 0x62 #define RADIOLIB_SX1278_REG_AGC_THRESH_1 0x62
#define SX1278_REG_AGC_THRESH_2 0x63 #define RADIOLIB_SX1278_REG_AGC_THRESH_2 0x63
#define SX1278_REG_AGC_THRESH_3 0x64 #define RADIOLIB_SX1278_REG_AGC_THRESH_3 0x64
#define SX1278_REG_PLL 0x70 #define RADIOLIB_SX1278_REG_PLL 0x70
// SX1278 LoRa modem settings // SX1278 LoRa modem settings
// SX1278_REG_OP_MODE MSB LSB DESCRIPTION // RADIOLIB_SX1278_REG_OP_MODE MSB LSB DESCRIPTION
#define SX1278_HIGH_FREQ 0b00000000 // 3 3 access HF test registers #define RADIOLIB_SX1278_HIGH_FREQ 0b00000000 // 3 3 access HF test registers
#define SX1278_LOW_FREQ 0b00001000 // 3 3 access LF test registers #define RADIOLIB_SX1278_LOW_FREQ 0b00001000 // 3 3 access LF test registers
// SX1278_REG_FRF_MSB + REG_FRF_MID + REG_FRF_LSB // RADIOLIB_SX1278_REG_FRF_MSB + REG_FRF_MID + REG_FRF_LSB
#define SX1278_FRF_MSB 0x6C // 7 0 carrier frequency setting: f_RF = (F(XOSC) * FRF)/2^19 #define RADIOLIB_SX1278_FRF_MSB 0x6C // 7 0 carrier frequency setting: f_RF = (F(XOSC) * FRF)/2^19
#define SX1278_FRF_MID 0x80 // 7 0 where F(XOSC) = 32 MHz #define RADIOLIB_SX1278_FRF_MID 0x80 // 7 0 where F(XOSC) = 32 MHz
#define SX1278_FRF_LSB 0x00 // 7 0 FRF = 3 byte value of FRF registers #define RADIOLIB_SX1278_FRF_LSB 0x00 // 7 0 FRF = 3 byte value of FRF registers
// SX1278_REG_PA_CONFIG // RADIOLIB_SX1278_REG_PA_CONFIG
#define SX1278_MAX_POWER 0b01110000 // 6 4 max power: P_max = 10.8 + 0.6*MAX_POWER [dBm]; P_max(MAX_POWER = 0b111) = 15 dBm #define RADIOLIB_SX1278_MAX_POWER 0b01110000 // 6 4 max power: P_max = 10.8 + 0.6*MAX_POWER [dBm]; P_max(MAX_POWER = 0b111) = 15 dBm
#define SX1278_LOW_POWER 0b00100000 // 6 4 #define RADIOLIB_SX1278_LOW_POWER 0b00100000 // 6 4
// SX1278_REG_LNA // RADIOLIB_SX1278_REG_LNA
#define SX1278_LNA_BOOST_LF_OFF 0b00000000 // 4 3 default LNA current #define RADIOLIB_SX1278_LNA_BOOST_LF_OFF 0b00000000 // 4 3 default LNA current
// SX127X_REG_MODEM_CONFIG_1 // SX127X_REG_MODEM_CONFIG_1
#define SX1278_BW_7_80_KHZ 0b00000000 // 7 4 bandwidth: 7.80 kHz #define RADIOLIB_SX1278_BW_7_80_KHZ 0b00000000 // 7 4 bandwidth: 7.80 kHz
#define SX1278_BW_10_40_KHZ 0b00010000 // 7 4 10.40 kHz #define RADIOLIB_SX1278_BW_10_40_KHZ 0b00010000 // 7 4 10.40 kHz
#define SX1278_BW_15_60_KHZ 0b00100000 // 7 4 15.60 kHz #define RADIOLIB_SX1278_BW_15_60_KHZ 0b00100000 // 7 4 15.60 kHz
#define SX1278_BW_20_80_KHZ 0b00110000 // 7 4 20.80 kHz #define RADIOLIB_SX1278_BW_20_80_KHZ 0b00110000 // 7 4 20.80 kHz
#define SX1278_BW_31_25_KHZ 0b01000000 // 7 4 31.25 kHz #define RADIOLIB_SX1278_BW_31_25_KHZ 0b01000000 // 7 4 31.25 kHz
#define SX1278_BW_41_70_KHZ 0b01010000 // 7 4 41.70 kHz #define RADIOLIB_SX1278_BW_41_70_KHZ 0b01010000 // 7 4 41.70 kHz
#define SX1278_BW_62_50_KHZ 0b01100000 // 7 4 62.50 kHz #define RADIOLIB_SX1278_BW_62_50_KHZ 0b01100000 // 7 4 62.50 kHz
#define SX1278_BW_125_00_KHZ 0b01110000 // 7 4 125.00 kHz #define RADIOLIB_SX1278_BW_125_00_KHZ 0b01110000 // 7 4 125.00 kHz
#define SX1278_BW_250_00_KHZ 0b10000000 // 7 4 250.00 kHz #define RADIOLIB_SX1278_BW_250_00_KHZ 0b10000000 // 7 4 250.00 kHz
#define SX1278_BW_500_00_KHZ 0b10010000 // 7 4 500.00 kHz #define RADIOLIB_SX1278_BW_500_00_KHZ 0b10010000 // 7 4 500.00 kHz
#define SX1278_CR_4_5 0b00000010 // 3 1 error coding rate: 4/5 #define RADIOLIB_SX1278_CR_4_5 0b00000010 // 3 1 error coding rate: 4/5
#define SX1278_CR_4_6 0b00000100 // 3 1 4/6 #define RADIOLIB_SX1278_CR_4_6 0b00000100 // 3 1 4/6
#define SX1278_CR_4_7 0b00000110 // 3 1 4/7 #define RADIOLIB_SX1278_CR_4_7 0b00000110 // 3 1 4/7
#define SX1278_CR_4_8 0b00001000 // 3 1 4/8 #define RADIOLIB_SX1278_CR_4_8 0b00001000 // 3 1 4/8
#define SX1278_HEADER_EXPL_MODE 0b00000000 // 0 0 explicit header mode #define RADIOLIB_SX1278_HEADER_EXPL_MODE 0b00000000 // 0 0 explicit header mode
#define SX1278_HEADER_IMPL_MODE 0b00000001 // 0 0 implicit header mode #define RADIOLIB_SX1278_HEADER_IMPL_MODE 0b00000001 // 0 0 implicit header mode
// SX127X_REG_MODEM_CONFIG_2 // SX127X_REG_MODEM_CONFIG_2
#define SX1278_RX_CRC_MODE_OFF 0b00000000 // 2 2 CRC disabled #define RADIOLIB_SX1278_RX_CRC_MODE_OFF 0b00000000 // 2 2 CRC disabled
#define SX1278_RX_CRC_MODE_ON 0b00000100 // 2 2 CRC enabled #define RADIOLIB_SX1278_RX_CRC_MODE_ON 0b00000100 // 2 2 CRC enabled
// SX1278_REG_MODEM_CONFIG_3 // RADIOLIB_SX1278_REG_MODEM_CONFIG_3
#define SX1278_LOW_DATA_RATE_OPT_OFF 0b00000000 // 3 3 low data rate optimization disabled #define RADIOLIB_SX1278_LOW_DATA_RATE_OPT_OFF 0b00000000 // 3 3 low data rate optimization disabled
#define SX1278_LOW_DATA_RATE_OPT_ON 0b00001000 // 3 3 low data rate optimization enabled #define RADIOLIB_SX1278_LOW_DATA_RATE_OPT_ON 0b00001000 // 3 3 low data rate optimization enabled
#define SX1278_AGC_AUTO_OFF 0b00000000 // 2 2 LNA gain set by REG_LNA #define RADIOLIB_SX1278_AGC_AUTO_OFF 0b00000000 // 2 2 LNA gain set by REG_LNA
#define SX1278_AGC_AUTO_ON 0b00000100 // 2 2 LNA gain set by internal AGC loop #define RADIOLIB_SX1278_AGC_AUTO_ON 0b00000100 // 2 2 LNA gain set by internal AGC loop
// SX127X_REG_VERSION // SX127X_REG_VERSION
#define SX1278_CHIP_VERSION 0x12 #define RADIOLIB_SX1278_CHIP_VERSION 0x12
// SX1278 FSK modem settings // SX1278 FSK modem settings
// SX127X_REG_PA_RAMP // SX127X_REG_PA_RAMP
#define SX1278_NO_SHAPING 0b00000000 // 6 5 data shaping: no shaping (default) #define RADIOLIB_SX1278_NO_SHAPING 0b00000000 // 6 5 data shaping: no shaping (default)
#define SX1278_FSK_GAUSSIAN_1_0 0b00100000 // 6 5 FSK modulation Gaussian filter, BT = 1.0 #define RADIOLIB_SX1278_FSK_GAUSSIAN_1_0 0b00100000 // 6 5 FSK modulation Gaussian filter, BT = 1.0
#define SX1278_FSK_GAUSSIAN_0_5 0b01000000 // 6 5 FSK modulation Gaussian filter, BT = 0.5 #define RADIOLIB_SX1278_FSK_GAUSSIAN_0_5 0b01000000 // 6 5 FSK modulation Gaussian filter, BT = 0.5
#define SX1278_FSK_GAUSSIAN_0_3 0b01100000 // 6 5 FSK modulation Gaussian filter, BT = 0.3 #define RADIOLIB_SX1278_FSK_GAUSSIAN_0_3 0b01100000 // 6 5 FSK modulation Gaussian filter, BT = 0.3
#define SX1278_OOK_FILTER_BR 0b00100000 // 6 5 OOK modulation filter, f_cutoff = BR #define RADIOLIB_SX1278_OOK_FILTER_BR 0b00100000 // 6 5 OOK modulation filter, f_cutoff = BR
#define SX1278_OOK_FILTER_2BR 0b01000000 // 6 5 OOK modulation filter, f_cutoff = 2*BR #define RADIOLIB_SX1278_OOK_FILTER_2BR 0b01000000 // 6 5 OOK modulation filter, f_cutoff = 2*BR
// SX1278_REG_AGC_REF // RADIOLIB_SX1278_REG_AGC_REF
#define SX1278_AGC_REFERENCE_LEVEL_LF 0x19 // 5 0 floor reference for AGC thresholds: AgcRef = -174 + 10*log(2*RxBw) + 8 + AGC_REFERENCE_LEVEL [dBm]: below 525 MHz #define RADIOLIB_SX1278_AGC_REFERENCE_LEVEL_LF 0x19 // 5 0 floor reference for AGC thresholds: AgcRef = -174 + 10*log(2*RxBw) + 8 + AGC_REFERENCE_LEVEL [dBm]: below 525 MHz
#define SX1278_AGC_REFERENCE_LEVEL_HF 0x1C // 5 0 above 779 MHz #define RADIOLIB_SX1278_AGC_REFERENCE_LEVEL_HF 0x1C // 5 0 above 779 MHz
// SX1278_REG_AGC_THRESH_1 // RADIOLIB_SX1278_REG_AGC_THRESH_1
#define SX1278_AGC_STEP_1_LF 0x0C // 4 0 1st AGC threshold: below 525 MHz #define RADIOLIB_SX1278_AGC_STEP_1_LF 0x0C // 4 0 1st AGC threshold: below 525 MHz
#define SX1278_AGC_STEP_1_HF 0x0E // 4 0 above 779 MHz #define RADIOLIB_SX1278_AGC_STEP_1_HF 0x0E // 4 0 above 779 MHz
// SX1278_REG_AGC_THRESH_2 // RADIOLIB_SX1278_REG_AGC_THRESH_2
#define SX1278_AGC_STEP_2_LF 0x40 // 7 4 2nd AGC threshold: below 525 MHz #define RADIOLIB_SX1278_AGC_STEP_2_LF 0x40 // 7 4 2nd AGC threshold: below 525 MHz
#define SX1278_AGC_STEP_2_HF 0x50 // 7 4 above 779 MHz #define RADIOLIB_SX1278_AGC_STEP_2_HF 0x50 // 7 4 above 779 MHz
#define SX1278_AGC_STEP_3 0x0B // 3 0 3rd AGC threshold #define RADIOLIB_SX1278_AGC_STEP_3 0x0B // 3 0 3rd AGC threshold
// SX1278_REG_AGC_THRESH_3 // RADIOLIB_SX1278_REG_AGC_THRESH_3
#define SX1278_AGC_STEP_4 0xC0 // 7 4 4th AGC threshold #define RADIOLIB_SX1278_AGC_STEP_4 0xC0 // 7 4 4th AGC threshold
#define SX1278_AGC_STEP_5 0x0C // 4 0 5th AGC threshold #define RADIOLIB_SX1278_AGC_STEP_5 0x0C // 4 0 5th AGC threshold
/*! /*!
\class SX1278 \class SX1278
@ -138,7 +138,7 @@ class SX1278: public SX127x {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0); int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0);
/*! /*!
\brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module. \brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module.

View file

@ -7,7 +7,7 @@ SX1279::SX1279(Module* mod) : SX1278(mod) {
int16_t SX1279::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) { int16_t SX1279::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t syncWord, int8_t power, uint16_t preambleLength, uint8_t gain) {
// execute common part // execute common part
int16_t state = SX127x::begin(SX1278_CHIP_VERSION, syncWord, preambleLength); int16_t state = SX127x::begin(RADIOLIB_SX1278_CHIP_VERSION, syncWord, preambleLength);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure publicly accessible settings // configure publicly accessible settings
@ -34,7 +34,7 @@ int16_t SX1279::begin(float freq, float bw, uint8_t sf, uint8_t cr, uint8_t sync
int16_t SX1279::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t power, uint16_t preambleLength, bool enableOOK) { int16_t SX1279::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t power, uint16_t preambleLength, bool enableOOK) {
// execute common part // execute common part
int16_t state = SX127x::beginFSK(SX1278_CHIP_VERSION, br, freqDev, rxBw, preambleLength, enableOOK); int16_t state = SX127x::beginFSK(RADIOLIB_SX1278_CHIP_VERSION, br, freqDev, rxBw, preambleLength, enableOOK);
RADIOLIB_ASSERT(state); RADIOLIB_ASSERT(state);
// configure settings not accessible by API // configure settings not accessible by API
@ -60,11 +60,11 @@ int16_t SX1279::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t
} }
int16_t SX1279::setFrequency(float freq) { int16_t SX1279::setFrequency(float freq) {
RADIOLIB_CHECK_RANGE(freq, 137.0, 960.0, ERR_INVALID_FREQUENCY); RADIOLIB_CHECK_RANGE(freq, 137.0, 960.0, RADIOLIB_ERR_INVALID_FREQUENCY);
// set frequency and if successful, save the new setting // set frequency and if successful, save the new setting
int16_t state = SX127x::setFrequencyRaw(freq); int16_t state = SX127x::setFrequencyRaw(freq);
if(state == ERR_NONE) { if(state == RADIOLIB_ERR_NONE) {
SX127x::_freq = freq; SX127x::_freq = freq;
} }
return(state); return(state);

View file

@ -49,7 +49,7 @@ class SX1279: public SX1278 {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0); int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX127X_SYNC_WORD, int8_t power = 10, uint16_t preambleLength = 8, uint8_t gain = 0);
/*! /*!
\brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module. \brief FSK modem initialization method. Must be called at least once from Arduino sketch to initialize the module.

File diff suppressed because it is too large Load diff

View file

@ -10,533 +10,533 @@
#include "../../protocols/PhysicalLayer/PhysicalLayer.h" #include "../../protocols/PhysicalLayer/PhysicalLayer.h"
// SX127x physical layer properties // SX127x physical layer properties
#define SX127X_FREQUENCY_STEP_SIZE 61.03515625 #define RADIOLIB_SX127X_FREQUENCY_STEP_SIZE 61.03515625
#define SX127X_MAX_PACKET_LENGTH 255 #define RADIOLIB_SX127X_MAX_PACKET_LENGTH 255
#define SX127X_MAX_PACKET_LENGTH_FSK 64 #define RADIOLIB_SX127X_MAX_PACKET_LENGTH_FSK 64
#define SX127X_CRYSTAL_FREQ 32.0 #define RADIOLIB_SX127X_CRYSTAL_FREQ 32.0
#define SX127X_DIV_EXPONENT 19 #define RADIOLIB_SX127X_DIV_EXPONENT 19
// SX127x series common LoRa registers // SX127x series common LoRa registers
#define SX127X_REG_FIFO 0x00 #define RADIOLIB_SX127X_REG_FIFO 0x00
#define SX127X_REG_OP_MODE 0x01 #define RADIOLIB_SX127X_REG_OP_MODE 0x01
#define SX127X_REG_FRF_MSB 0x06 #define RADIOLIB_SX127X_REG_FRF_MSB 0x06
#define SX127X_REG_FRF_MID 0x07 #define RADIOLIB_SX127X_REG_FRF_MID 0x07
#define SX127X_REG_FRF_LSB 0x08 #define RADIOLIB_SX127X_REG_FRF_LSB 0x08
#define SX127X_REG_PA_CONFIG 0x09 #define RADIOLIB_SX127X_REG_PA_CONFIG 0x09
#define SX127X_REG_PA_RAMP 0x0A #define RADIOLIB_SX127X_REG_PA_RAMP 0x0A
#define SX127X_REG_OCP 0x0B #define RADIOLIB_SX127X_REG_OCP 0x0B
#define SX127X_REG_LNA 0x0C #define RADIOLIB_SX127X_REG_LNA 0x0C
#define SX127X_REG_FIFO_ADDR_PTR 0x0D #define RADIOLIB_SX127X_REG_FIFO_ADDR_PTR 0x0D
#define SX127X_REG_FIFO_TX_BASE_ADDR 0x0E #define RADIOLIB_SX127X_REG_FIFO_TX_BASE_ADDR 0x0E
#define SX127X_REG_FIFO_RX_BASE_ADDR 0x0F #define RADIOLIB_SX127X_REG_FIFO_RX_BASE_ADDR 0x0F
#define SX127X_REG_FIFO_RX_CURRENT_ADDR 0x10 #define RADIOLIB_SX127X_REG_FIFO_RX_CURRENT_ADDR 0x10
#define SX127X_REG_IRQ_FLAGS_MASK 0x11 #define RADIOLIB_SX127X_REG_IRQ_FLAGS_MASK 0x11
#define SX127X_REG_IRQ_FLAGS 0x12 #define RADIOLIB_SX127X_REG_IRQ_FLAGS 0x12
#define SX127X_REG_RX_NB_BYTES 0x13 #define RADIOLIB_SX127X_REG_RX_NB_BYTES 0x13
#define SX127X_REG_RX_HEADER_CNT_VALUE_MSB 0x14 #define RADIOLIB_SX127X_REG_RX_HEADER_CNT_VALUE_MSB 0x14
#define SX127X_REG_RX_HEADER_CNT_VALUE_LSB 0x15 #define RADIOLIB_SX127X_REG_RX_HEADER_CNT_VALUE_LSB 0x15
#define SX127X_REG_RX_PACKET_CNT_VALUE_MSB 0x16 #define RADIOLIB_SX127X_REG_RX_PACKET_CNT_VALUE_MSB 0x16
#define SX127X_REG_RX_PACKET_CNT_VALUE_LSB 0x17 #define RADIOLIB_SX127X_REG_RX_PACKET_CNT_VALUE_LSB 0x17
#define SX127X_REG_MODEM_STAT 0x18 #define RADIOLIB_SX127X_REG_MODEM_STAT 0x18
#define SX127X_REG_PKT_SNR_VALUE 0x19 #define RADIOLIB_SX127X_REG_PKT_SNR_VALUE 0x19
#define SX127X_REG_PKT_RSSI_VALUE 0x1A #define RADIOLIB_SX127X_REG_PKT_RSSI_VALUE 0x1A
#define SX127X_REG_RSSI_VALUE 0x1B #define RADIOLIB_SX127X_REG_RSSI_VALUE 0x1B
#define SX127X_REG_HOP_CHANNEL 0x1C #define RADIOLIB_SX127X_REG_HOP_CHANNEL 0x1C
#define SX127X_REG_MODEM_CONFIG_1 0x1D #define RADIOLIB_SX127X_REG_MODEM_CONFIG_1 0x1D
#define SX127X_REG_MODEM_CONFIG_2 0x1E #define RADIOLIB_SX127X_REG_MODEM_CONFIG_2 0x1E
#define SX127X_REG_SYMB_TIMEOUT_LSB 0x1F #define RADIOLIB_SX127X_REG_SYMB_TIMEOUT_LSB 0x1F
#define SX127X_REG_PREAMBLE_MSB 0x20 #define RADIOLIB_SX127X_REG_PREAMBLE_MSB 0x20
#define SX127X_REG_PREAMBLE_LSB 0x21 #define RADIOLIB_SX127X_REG_PREAMBLE_LSB 0x21
#define SX127X_REG_PAYLOAD_LENGTH 0x22 #define RADIOLIB_SX127X_REG_PAYLOAD_LENGTH 0x22
#define SX127X_REG_MAX_PAYLOAD_LENGTH 0x23 #define RADIOLIB_SX127X_REG_MAX_PAYLOAD_LENGTH 0x23
#define SX127X_REG_HOP_PERIOD 0x24 #define RADIOLIB_SX127X_REG_HOP_PERIOD 0x24
#define SX127X_REG_FIFO_RX_BYTE_ADDR 0x25 #define RADIOLIB_SX127X_REG_FIFO_RX_BYTE_ADDR 0x25
#define SX127X_REG_FEI_MSB 0x28 #define RADIOLIB_SX127X_REG_FEI_MSB 0x28
#define SX127X_REG_FEI_MID 0x29 #define RADIOLIB_SX127X_REG_FEI_MID 0x29
#define SX127X_REG_FEI_LSB 0x2A #define RADIOLIB_SX127X_REG_FEI_LSB 0x2A
#define SX127X_REG_RSSI_WIDEBAND 0x2C #define RADIOLIB_SX127X_REG_RSSI_WIDEBAND 0x2C
#define SX127X_REG_DETECT_OPTIMIZE 0x31 #define RADIOLIB_SX127X_REG_DETECT_OPTIMIZE 0x31
#define SX127X_REG_INVERT_IQ 0x33 #define RADIOLIB_SX127X_REG_INVERT_IQ 0x33
#define SX127X_REG_DETECTION_THRESHOLD 0x37 #define RADIOLIB_SX127X_REG_DETECTION_THRESHOLD 0x37
#define SX127X_REG_SYNC_WORD 0x39 #define RADIOLIB_SX127X_REG_SYNC_WORD 0x39
#define SX127X_REG_INVERT_IQ2 0x3B #define RADIOLIB_SX127X_REG_INVERT_IQ2 0x3B
#define SX127X_REG_DIO_MAPPING_1 0x40 #define RADIOLIB_SX127X_REG_DIO_MAPPING_1 0x40
#define SX127X_REG_DIO_MAPPING_2 0x41 #define RADIOLIB_SX127X_REG_DIO_MAPPING_2 0x41
#define SX127X_REG_VERSION 0x42 #define RADIOLIB_SX127X_REG_VERSION 0x42
// SX127x common LoRa modem settings // SX127x common LoRa modem settings
// SX127X_REG_OP_MODE MSB LSB DESCRIPTION // SX127X_REG_OP_MODE MSB LSB DESCRIPTION
#define SX127X_FSK_OOK 0b00000000 // 7 7 FSK/OOK mode #define RADIOLIB_SX127X_FSK_OOK 0b00000000 // 7 7 FSK/OOK mode
#define SX127X_LORA 0b10000000 // 7 7 LoRa mode #define RADIOLIB_SX127X_LORA 0b10000000 // 7 7 LoRa mode
#define SX127X_ACCESS_SHARED_REG_OFF 0b00000000 // 6 6 access LoRa registers (0x0D:0x3F) in LoRa mode #define RADIOLIB_SX127X_ACCESS_SHARED_REG_OFF 0b00000000 // 6 6 access LoRa registers (0x0D:0x3F) in LoRa mode
#define SX127X_ACCESS_SHARED_REG_ON 0b01000000 // 6 6 access FSK registers (0x0D:0x3F) in LoRa mode #define RADIOLIB_SX127X_ACCESS_SHARED_REG_ON 0b01000000 // 6 6 access FSK registers (0x0D:0x3F) in LoRa mode
#define SX127X_SLEEP 0b00000000 // 2 0 sleep #define RADIOLIB_SX127X_SLEEP 0b00000000 // 2 0 sleep
#define SX127X_STANDBY 0b00000001 // 2 0 standby #define RADIOLIB_SX127X_STANDBY 0b00000001 // 2 0 standby
#define SX127X_FSTX 0b00000010 // 2 0 frequency synthesis TX #define RADIOLIB_SX127X_FSTX 0b00000010 // 2 0 frequency synthesis TX
#define SX127X_TX 0b00000011 // 2 0 transmit #define RADIOLIB_SX127X_TX 0b00000011 // 2 0 transmit
#define SX127X_FSRX 0b00000100 // 2 0 frequency synthesis RX #define RADIOLIB_SX127X_FSRX 0b00000100 // 2 0 frequency synthesis RX
#define SX127X_RXCONTINUOUS 0b00000101 // 2 0 receive continuous #define RADIOLIB_SX127X_RXCONTINUOUS 0b00000101 // 2 0 receive continuous
#define SX127X_RXSINGLE 0b00000110 // 2 0 receive single #define RADIOLIB_SX127X_RXSINGLE 0b00000110 // 2 0 receive single
#define SX127X_CAD 0b00000111 // 2 0 channel activity detection #define RADIOLIB_SX127X_CAD 0b00000111 // 2 0 channel activity detection
// SX127X_REG_PA_CONFIG // SX127X_REG_PA_CONFIG
#define SX127X_PA_SELECT_RFO 0b00000000 // 7 7 RFO pin output, power limited to +14 dBm #define RADIOLIB_SX127X_PA_SELECT_RFO 0b00000000 // 7 7 RFO pin output, power limited to +14 dBm
#define SX127X_PA_SELECT_BOOST 0b10000000 // 7 7 PA_BOOST pin output, power limited to +20 dBm #define RADIOLIB_SX127X_PA_SELECT_BOOST 0b10000000 // 7 7 PA_BOOST pin output, power limited to +20 dBm
#define SX127X_OUTPUT_POWER 0b00001111 // 3 0 output power: P_out = 2 + OUTPUT_POWER [dBm] for PA_SELECT_BOOST #define RADIOLIB_SX127X_OUTPUT_POWER 0b00001111 // 3 0 output power: P_out = 2 + OUTPUT_POWER [dBm] for PA_SELECT_BOOST
// P_out = -1 + OUTPUT_POWER [dBm] for PA_SELECT_RFO // P_out = -1 + OUTPUT_POWER [dBm] for PA_SELECT_RFO
// SX127X_REG_OCP // SX127X_REG_OCP
#define SX127X_OCP_OFF 0b00000000 // 5 5 PA overload current protection disabled #define RADIOLIB_SX127X_OCP_OFF 0b00000000 // 5 5 PA overload current protection disabled
#define SX127X_OCP_ON 0b00100000 // 5 5 PA overload current protection enabled #define RADIOLIB_SX127X_OCP_ON 0b00100000 // 5 5 PA overload current protection enabled
#define SX127X_OCP_TRIM 0b00001011 // 4 0 OCP current: I_max(OCP_TRIM = 0b1011) = 100 mA #define RADIOLIB_SX127X_OCP_TRIM 0b00001011 // 4 0 OCP current: I_max(OCP_TRIM = 0b1011) = 100 mA
// SX127X_REG_LNA // SX127X_REG_LNA
#define SX127X_LNA_GAIN_1 0b00100000 // 7 5 LNA gain setting: max gain #define RADIOLIB_SX127X_LNA_GAIN_1 0b00100000 // 7 5 LNA gain setting: max gain
#define SX127X_LNA_GAIN_2 0b01000000 // 7 5 . #define RADIOLIB_SX127X_LNA_GAIN_2 0b01000000 // 7 5 .
#define SX127X_LNA_GAIN_3 0b01100000 // 7 5 . #define RADIOLIB_SX127X_LNA_GAIN_3 0b01100000 // 7 5 .
#define SX127X_LNA_GAIN_4 0b10000000 // 7 5 . #define RADIOLIB_SX127X_LNA_GAIN_4 0b10000000 // 7 5 .
#define SX127X_LNA_GAIN_5 0b10100000 // 7 5 . #define RADIOLIB_SX127X_LNA_GAIN_5 0b10100000 // 7 5 .
#define SX127X_LNA_GAIN_6 0b11000000 // 7 5 min gain #define RADIOLIB_SX127X_LNA_GAIN_6 0b11000000 // 7 5 min gain
#define SX127X_LNA_BOOST_OFF 0b00000000 // 1 0 default LNA current #define RADIOLIB_SX127X_LNA_BOOST_OFF 0b00000000 // 1 0 default LNA current
#define SX127X_LNA_BOOST_ON 0b00000011 // 1 0 150% LNA current #define RADIOLIB_SX127X_LNA_BOOST_ON 0b00000011 // 1 0 150% LNA current
// SX127X_REG_MODEM_CONFIG_2 // SX127X_REG_MODEM_CONFIG_2
#define SX127X_SF_6 0b01100000 // 7 4 spreading factor: 64 chips/bit #define RADIOLIB_SX127X_SF_6 0b01100000 // 7 4 spreading factor: 64 chips/bit
#define SX127X_SF_7 0b01110000 // 7 4 128 chips/bit #define RADIOLIB_SX127X_SF_7 0b01110000 // 7 4 128 chips/bit
#define SX127X_SF_8 0b10000000 // 7 4 256 chips/bit #define RADIOLIB_SX127X_SF_8 0b10000000 // 7 4 256 chips/bit
#define SX127X_SF_9 0b10010000 // 7 4 512 chips/bit #define RADIOLIB_SX127X_SF_9 0b10010000 // 7 4 512 chips/bit
#define SX127X_SF_10 0b10100000 // 7 4 1024 chips/bit #define RADIOLIB_SX127X_SF_10 0b10100000 // 7 4 1024 chips/bit
#define SX127X_SF_11 0b10110000 // 7 4 2048 chips/bit #define RADIOLIB_SX127X_SF_11 0b10110000 // 7 4 2048 chips/bit
#define SX127X_SF_12 0b11000000 // 7 4 4096 chips/bit #define RADIOLIB_SX127X_SF_12 0b11000000 // 7 4 4096 chips/bit
#define SX127X_TX_MODE_SINGLE 0b00000000 // 3 3 single TX #define RADIOLIB_SX127X_TX_MODE_SINGLE 0b00000000 // 3 3 single TX
#define SX127X_TX_MODE_CONT 0b00001000 // 3 3 continuous TX #define RADIOLIB_SX127X_TX_MODE_CONT 0b00001000 // 3 3 continuous TX
#define SX127X_RX_TIMEOUT_MSB 0b00000000 // 1 0 #define RADIOLIB_SX127X_RX_TIMEOUT_MSB 0b00000000 // 1 0
// SX127X_REG_SYMB_TIMEOUT_LSB // SX127X_REG_SYMB_TIMEOUT_LSB
#define SX127X_RX_TIMEOUT_LSB 0b01100100 // 7 0 10 bit RX operation timeout #define RADIOLIB_SX127X_RX_TIMEOUT_LSB 0b01100100 // 7 0 10 bit RX operation timeout
// SX127X_REG_PREAMBLE_MSB + REG_PREAMBLE_LSB // SX127X_REG_PREAMBLE_MSB + REG_PREAMBLE_LSB
#define SX127X_PREAMBLE_LENGTH_MSB 0b00000000 // 7 0 2 byte preamble length setting: l_P = PREAMBLE_LENGTH + 4.25 #define RADIOLIB_SX127X_PREAMBLE_LENGTH_MSB 0b00000000 // 7 0 2 byte preamble length setting: l_P = PREAMBLE_LENGTH + 4.25
#define SX127X_PREAMBLE_LENGTH_LSB 0b00001000 // 7 0 where l_p = preamble length #define RADIOLIB_SX127X_PREAMBLE_LENGTH_LSB 0b00001000 // 7 0 where l_p = preamble length
// SX127X_REG_DETECT_OPTIMIZE // SX127X_REG_DETECT_OPTIMIZE
#define SX127X_DETECT_OPTIMIZE_SF_6 0b00000101 // 2 0 SF6 detection optimization #define RADIOLIB_SX127X_DETECT_OPTIMIZE_SF_6 0b00000101 // 2 0 SF6 detection optimization
#define SX127X_DETECT_OPTIMIZE_SF_7_12 0b00000011 // 2 0 SF7 to SF12 detection optimization #define RADIOLIB_SX127X_DETECT_OPTIMIZE_SF_7_12 0b00000011 // 2 0 SF7 to SF12 detection optimization
// SX127X_REG_INVERT_IQ // SX127X_REG_INVERT_IQ
#define SX127X_INVERT_IQ_RXPATH_ON 0b01000000 // 6 6 I and Q signals are inverted #define RADIOLIB_SX127X_INVERT_IQ_RXPATH_ON 0b01000000 // 6 6 I and Q signals are inverted
#define SX127X_INVERT_IQ_RXPATH_OFF 0b00000000 // 6 6 normal mode #define RADIOLIB_SX127X_INVERT_IQ_RXPATH_OFF 0b00000000 // 6 6 normal mode
#define SX127X_INVERT_IQ_TXPATH_ON 0b00000001 // 0 0 I and Q signals are inverted #define RADIOLIB_SX127X_INVERT_IQ_TXPATH_ON 0b00000001 // 0 0 I and Q signals are inverted
#define SX127X_INVERT_IQ_TXPATH_OFF 0b00000000 // 0 0 normal mode #define RADIOLIB_SX127X_INVERT_IQ_TXPATH_OFF 0b00000000 // 0 0 normal mode
// SX127X_REG_DETECTION_THRESHOLD // SX127X_REG_DETECTION_THRESHOLD
#define SX127X_DETECTION_THRESHOLD_SF_6 0b00001100 // 7 0 SF6 detection threshold #define RADIOLIB_SX127X_DETECTION_THRESHOLD_SF_6 0b00001100 // 7 0 SF6 detection threshold
#define SX127X_DETECTION_THRESHOLD_SF_7_12 0b00001010 // 7 0 SF7 to SF12 detection threshold #define RADIOLIB_SX127X_DETECTION_THRESHOLD_SF_7_12 0b00001010 // 7 0 SF7 to SF12 detection threshold
// SX127X_REG_PA_DAC // SX127X_REG_PA_DAC
#define SX127X_PA_BOOST_OFF 0b00000100 // 2 0 PA_BOOST disabled #define RADIOLIB_SX127X_PA_BOOST_OFF 0b00000100 // 2 0 PA_BOOST disabled
#define SX127X_PA_BOOST_ON 0b00000111 // 2 0 +20 dBm on PA_BOOST when OUTPUT_POWER = 0b1111 #define RADIOLIB_SX127X_PA_BOOST_ON 0b00000111 // 2 0 +20 dBm on PA_BOOST when OUTPUT_POWER = 0b1111
// SX127X_REG_HOP_PERIOD // SX127X_REG_HOP_PERIOD
#define SX127X_HOP_PERIOD_OFF 0b00000000 // 7 0 number of periods between frequency hops; 0 = disabled #define RADIOLIB_SX127X_HOP_PERIOD_OFF 0b00000000 // 7 0 number of periods between frequency hops; 0 = disabled
#define SX127X_HOP_PERIOD_MAX 0b11111111 // 7 0 #define RADIOLIB_SX127X_HOP_PERIOD_MAX 0b11111111 // 7 0
// SX127X_REG_DIO_MAPPING_1 // SX127X_REG_DIO_MAPPING_1
#define SX127X_DIO0_RX_DONE 0b00000000 // 7 6 #define RADIOLIB_SX127X_DIO0_RX_DONE 0b00000000 // 7 6
#define SX127X_DIO0_TX_DONE 0b01000000 // 7 6 #define RADIOLIB_SX127X_DIO0_TX_DONE 0b01000000 // 7 6
#define SX127X_DIO0_CAD_DONE 0b10000000 // 7 6 #define RADIOLIB_SX127X_DIO0_CAD_DONE 0b10000000 // 7 6
#define SX127X_DIO1_RX_TIMEOUT 0b00000000 // 5 4 #define RADIOLIB_SX127X_DIO1_RX_TIMEOUT 0b00000000 // 5 4
#define SX127X_DIO1_FHSS_CHANGE_CHANNEL 0b00010000 // 5 4 #define RADIOLIB_SX127X_DIO1_FHSS_CHANGE_CHANNEL 0b00010000 // 5 4
#define SX127X_DIO1_CAD_DETECTED 0b00100000 // 5 4 #define RADIOLIB_SX127X_DIO1_CAD_DETECTED 0b00100000 // 5 4
// SX127X_REG_IRQ_FLAGS // SX127X_REG_IRQ_FLAGS
#define SX127X_CLEAR_IRQ_FLAG_RX_TIMEOUT 0b10000000 // 7 7 timeout #define RADIOLIB_SX127X_CLEAR_IRQ_FLAG_RX_TIMEOUT 0b10000000 // 7 7 timeout
#define SX127X_CLEAR_IRQ_FLAG_RX_DONE 0b01000000 // 6 6 packet reception complete #define RADIOLIB_SX127X_CLEAR_IRQ_FLAG_RX_DONE 0b01000000 // 6 6 packet reception complete
#define SX127X_CLEAR_IRQ_FLAG_PAYLOAD_CRC_ERROR 0b00100000 // 5 5 payload CRC error #define RADIOLIB_SX127X_CLEAR_IRQ_FLAG_PAYLOAD_CRC_ERROR 0b00100000 // 5 5 payload CRC error
#define SX127X_CLEAR_IRQ_FLAG_VALID_HEADER 0b00010000 // 4 4 valid header received #define RADIOLIB_SX127X_CLEAR_IRQ_FLAG_VALID_HEADER 0b00010000 // 4 4 valid header received
#define SX127X_CLEAR_IRQ_FLAG_TX_DONE 0b00001000 // 3 3 payload transmission complete #define RADIOLIB_SX127X_CLEAR_IRQ_FLAG_TX_DONE 0b00001000 // 3 3 payload transmission complete
#define SX127X_CLEAR_IRQ_FLAG_CAD_DONE 0b00000100 // 2 2 CAD complete #define RADIOLIB_SX127X_CLEAR_IRQ_FLAG_CAD_DONE 0b00000100 // 2 2 CAD complete
#define SX127X_CLEAR_IRQ_FLAG_FHSS_CHANGE_CHANNEL 0b00000010 // 1 1 FHSS change channel #define RADIOLIB_SX127X_CLEAR_IRQ_FLAG_FHSS_CHANGE_CHANNEL 0b00000010 // 1 1 FHSS change channel
#define SX127X_CLEAR_IRQ_FLAG_CAD_DETECTED 0b00000001 // 0 0 valid LoRa signal detected during CAD operation #define RADIOLIB_SX127X_CLEAR_IRQ_FLAG_CAD_DETECTED 0b00000001 // 0 0 valid LoRa signal detected during CAD operation
// SX127X_REG_IRQ_FLAGS_MASK // SX127X_REG_IRQ_FLAGS_MASK
#define SX127X_MASK_IRQ_FLAG_RX_TIMEOUT 0b01111111 // 7 7 timeout #define RADIOLIB_SX127X_MASK_IRQ_FLAG_RX_TIMEOUT 0b01111111 // 7 7 timeout
#define SX127X_MASK_IRQ_FLAG_RX_DONE 0b10111111 // 6 6 packet reception complete #define RADIOLIB_SX127X_MASK_IRQ_FLAG_RX_DONE 0b10111111 // 6 6 packet reception complete
#define SX127X_MASK_IRQ_FLAG_PAYLOAD_CRC_ERROR 0b11011111 // 5 5 payload CRC error #define RADIOLIB_SX127X_MASK_IRQ_FLAG_PAYLOAD_CRC_ERROR 0b11011111 // 5 5 payload CRC error
#define SX127X_MASK_IRQ_FLAG_VALID_HEADER 0b11101111 // 4 4 valid header received #define RADIOLIB_SX127X_MASK_IRQ_FLAG_VALID_HEADER 0b11101111 // 4 4 valid header received
#define SX127X_MASK_IRQ_FLAG_TX_DONE 0b11110111 // 3 3 payload transmission complete #define RADIOLIB_SX127X_MASK_IRQ_FLAG_TX_DONE 0b11110111 // 3 3 payload transmission complete
#define SX127X_MASK_IRQ_FLAG_CAD_DONE 0b11111011 // 2 2 CAD complete #define RADIOLIB_SX127X_MASK_IRQ_FLAG_CAD_DONE 0b11111011 // 2 2 CAD complete
#define SX127X_MASK_IRQ_FLAG_FHSS_CHANGE_CHANNEL 0b11111101 // 1 1 FHSS change channel #define RADIOLIB_SX127X_MASK_IRQ_FLAG_FHSS_CHANGE_CHANNEL 0b11111101 // 1 1 FHSS change channel
#define SX127X_MASK_IRQ_FLAG_CAD_DETECTED 0b11111110 // 0 0 valid LoRa signal detected during CAD operation #define RADIOLIB_SX127X_MASK_IRQ_FLAG_CAD_DETECTED 0b11111110 // 0 0 valid LoRa signal detected during CAD operation
// SX127X_REG_FIFO_TX_BASE_ADDR // SX127X_REG_FIFO_TX_BASE_ADDR
#define SX127X_FIFO_TX_BASE_ADDR_MAX 0b00000000 // 7 0 allocate the entire FIFO buffer for TX only #define RADIOLIB_SX127X_FIFO_TX_BASE_ADDR_MAX 0b00000000 // 7 0 allocate the entire FIFO buffer for TX only
// SX127X_REG_FIFO_RX_BASE_ADDR // SX127X_REG_FIFO_RX_BASE_ADDR
#define SX127X_FIFO_RX_BASE_ADDR_MAX 0b00000000 // 7 0 allocate the entire FIFO buffer for RX only #define RADIOLIB_SX127X_FIFO_RX_BASE_ADDR_MAX 0b00000000 // 7 0 allocate the entire FIFO buffer for RX only
// SX127X_REG_SYNC_WORD // SX127X_REG_SYNC_WORD
#define SX127X_SYNC_WORD 0x12 // 7 0 default LoRa sync word #define RADIOLIB_SX127X_SYNC_WORD 0x12 // 7 0 default LoRa sync word
#define SX127X_SYNC_WORD_LORAWAN 0x34 // 7 0 sync word reserved for LoRaWAN networks #define RADIOLIB_SX127X_SYNC_WORD_LORAWAN 0x34 // 7 0 sync word reserved for LoRaWAN networks
// SX127X_REG_INVERT_IQ2 // SX127X_REG_INVERT_IQ2
#define SX127X_IQ2_ENABLE 0x19 // 7 0 enable optimize for inverted IQ #define RADIOLIB_SX127X_IQ2_ENABLE 0x19 // 7 0 enable optimize for inverted IQ
#define SX127X_IQ2_DISABLE 0x1D // 7 0 reset optimize for inverted IQ #define RADIOLIB_SX127X_IQ2_DISABLE 0x1D // 7 0 reset optimize for inverted IQ
// SX127x series common FSK registers // SX127x series common FSK registers
// NOTE: FSK register names that are conflicting with LoRa registers are marked with "_FSK" suffix // NOTE: FSK register names that are conflicting with LoRa registers are marked with "_FSK" suffix
#define SX127X_REG_BITRATE_MSB 0x02 #define RADIOLIB_SX127X_REG_BITRATE_MSB 0x02
#define SX127X_REG_BITRATE_LSB 0x03 #define RADIOLIB_SX127X_REG_BITRATE_LSB 0x03
#define SX127X_REG_FDEV_MSB 0x04 #define RADIOLIB_SX127X_REG_FDEV_MSB 0x04
#define SX127X_REG_FDEV_LSB 0x05 #define RADIOLIB_SX127X_REG_FDEV_LSB 0x05
#define SX127X_REG_RX_CONFIG 0x0D #define RADIOLIB_SX127X_REG_RX_CONFIG 0x0D
#define SX127X_REG_RSSI_CONFIG 0x0E #define RADIOLIB_SX127X_REG_RSSI_CONFIG 0x0E
#define SX127X_REG_RSSI_COLLISION 0x0F #define RADIOLIB_SX127X_REG_RSSI_COLLISION 0x0F
#define SX127X_REG_RSSI_THRESH 0x10 #define RADIOLIB_SX127X_REG_RSSI_THRESH 0x10
#define SX127X_REG_RSSI_VALUE_FSK 0x11 #define RADIOLIB_SX127X_REG_RSSI_VALUE_FSK 0x11
#define SX127X_REG_RX_BW 0x12 #define RADIOLIB_SX127X_REG_RX_BW 0x12
#define SX127X_REG_AFC_BW 0x13 #define RADIOLIB_SX127X_REG_AFC_BW 0x13
#define SX127X_REG_OOK_PEAK 0x14 #define RADIOLIB_SX127X_REG_OOK_PEAK 0x14
#define SX127X_REG_OOK_FIX 0x15 #define RADIOLIB_SX127X_REG_OOK_FIX 0x15
#define SX127X_REG_OOK_AVG 0x16 #define RADIOLIB_SX127X_REG_OOK_AVG 0x16
#define SX127X_REG_AFC_FEI 0x1A #define RADIOLIB_SX127X_REG_AFC_FEI 0x1A
#define SX127X_REG_AFC_MSB 0x1B #define RADIOLIB_SX127X_REG_AFC_MSB 0x1B
#define SX127X_REG_AFC_LSB 0x1C #define RADIOLIB_SX127X_REG_AFC_LSB 0x1C
#define SX127X_REG_FEI_MSB_FSK 0x1D #define RADIOLIB_SX127X_REG_FEI_MSB_FSK 0x1D
#define SX127X_REG_FEI_LSB_FSK 0x1E #define RADIOLIB_SX127X_REG_FEI_LSB_FSK 0x1E
#define SX127X_REG_PREAMBLE_DETECT 0x1F #define RADIOLIB_SX127X_REG_PREAMBLE_DETECT 0x1F
#define SX127X_REG_RX_TIMEOUT_1 0x20 #define RADIOLIB_SX127X_REG_RX_TIMEOUT_1 0x20
#define SX127X_REG_RX_TIMEOUT_2 0x21 #define RADIOLIB_SX127X_REG_RX_TIMEOUT_2 0x21
#define SX127X_REG_RX_TIMEOUT_3 0x22 #define RADIOLIB_SX127X_REG_RX_TIMEOUT_3 0x22
#define SX127X_REG_RX_DELAY 0x23 #define RADIOLIB_SX127X_REG_RX_DELAY 0x23
#define SX127X_REG_OSC 0x24 #define RADIOLIB_SX127X_REG_OSC 0x24
#define SX127X_REG_PREAMBLE_MSB_FSK 0x25 #define RADIOLIB_SX127X_REG_PREAMBLE_MSB_FSK 0x25
#define SX127X_REG_PREAMBLE_LSB_FSK 0x26 #define RADIOLIB_SX127X_REG_PREAMBLE_LSB_FSK 0x26
#define SX127X_REG_SYNC_CONFIG 0x27 #define RADIOLIB_SX127X_REG_SYNC_CONFIG 0x27
#define SX127X_REG_SYNC_VALUE_1 0x28 #define RADIOLIB_SX127X_REG_SYNC_VALUE_1 0x28
#define SX127X_REG_SYNC_VALUE_2 0x29 #define RADIOLIB_SX127X_REG_SYNC_VALUE_2 0x29
#define SX127X_REG_SYNC_VALUE_3 0x2A #define RADIOLIB_SX127X_REG_SYNC_VALUE_3 0x2A
#define SX127X_REG_SYNC_VALUE_4 0x2B #define RADIOLIB_SX127X_REG_SYNC_VALUE_4 0x2B
#define SX127X_REG_SYNC_VALUE_5 0x2C #define RADIOLIB_SX127X_REG_SYNC_VALUE_5 0x2C
#define SX127X_REG_SYNC_VALUE_6 0x2D #define RADIOLIB_SX127X_REG_SYNC_VALUE_6 0x2D
#define SX127X_REG_SYNC_VALUE_7 0x2E #define RADIOLIB_SX127X_REG_SYNC_VALUE_7 0x2E
#define SX127X_REG_SYNC_VALUE_8 0x2F #define RADIOLIB_SX127X_REG_SYNC_VALUE_8 0x2F
#define SX127X_REG_PACKET_CONFIG_1 0x30 #define RADIOLIB_SX127X_REG_PACKET_CONFIG_1 0x30
#define SX127X_REG_PACKET_CONFIG_2 0x31 #define RADIOLIB_SX127X_REG_PACKET_CONFIG_2 0x31
#define SX127X_REG_PAYLOAD_LENGTH_FSK 0x32 #define RADIOLIB_SX127X_REG_PAYLOAD_LENGTH_FSK 0x32
#define SX127X_REG_NODE_ADRS 0x33 #define RADIOLIB_SX127X_REG_NODE_ADRS 0x33
#define SX127X_REG_BROADCAST_ADRS 0x34 #define RADIOLIB_SX127X_REG_BROADCAST_ADRS 0x34
#define SX127X_REG_FIFO_THRESH 0x35 #define RADIOLIB_SX127X_REG_FIFO_THRESH 0x35
#define SX127X_REG_SEQ_CONFIG_1 0x36 #define RADIOLIB_SX127X_REG_SEQ_CONFIG_1 0x36
#define SX127X_REG_SEQ_CONFIG_2 0x37 #define RADIOLIB_SX127X_REG_SEQ_CONFIG_2 0x37
#define SX127X_REG_TIMER_RESOL 0x38 #define RADIOLIB_SX127X_REG_TIMER_RESOL 0x38
#define SX127X_REG_TIMER1_COEF 0x39 #define RADIOLIB_SX127X_REG_TIMER1_COEF 0x39
#define SX127X_REG_TIMER2_COEF 0x3A #define RADIOLIB_SX127X_REG_TIMER2_COEF 0x3A
#define SX127X_REG_IMAGE_CAL 0x3B #define RADIOLIB_SX127X_REG_IMAGE_CAL 0x3B
#define SX127X_REG_TEMP 0x3C #define RADIOLIB_SX127X_REG_TEMP 0x3C
#define SX127X_REG_LOW_BAT 0x3D #define RADIOLIB_SX127X_REG_LOW_BAT 0x3D
#define SX127X_REG_IRQ_FLAGS_1 0x3E #define RADIOLIB_SX127X_REG_IRQ_FLAGS_1 0x3E
#define SX127X_REG_IRQ_FLAGS_2 0x3F #define RADIOLIB_SX127X_REG_IRQ_FLAGS_2 0x3F
// SX127x common FSK modem settings // SX127x common FSK modem settings
// SX127X_REG_OP_MODE // SX127X_REG_OP_MODE
#define SX127X_MODULATION_FSK 0b00000000 // 6 5 FSK modulation scheme #define RADIOLIB_SX127X_MODULATION_FSK 0b00000000 // 6 5 FSK modulation scheme
#define SX127X_MODULATION_OOK 0b00100000 // 6 5 OOK modulation scheme #define RADIOLIB_SX127X_MODULATION_OOK 0b00100000 // 6 5 OOK modulation scheme
#define SX127X_RX 0b00000101 // 2 0 receiver mode #define RADIOLIB_SX127X_RX 0b00000101 // 2 0 receiver mode
// SX127X_REG_BITRATE_MSB + SX127X_REG_BITRATE_LSB // SX127X_REG_BITRATE_MSB + SX127X_REG_BITRATE_LSB
#define SX127X_BITRATE_MSB 0x1A // 7 0 bit rate setting: BitRate = F(XOSC)/(BITRATE + BITRATE_FRAC/16) #define RADIOLIB_SX127X_BITRATE_MSB 0x1A // 7 0 bit rate setting: BitRate = F(XOSC)/(BITRATE + BITRATE_FRAC/16)
#define SX127X_BITRATE_LSB 0x0B // 7 0 default value: 4.8 kbps #define RADIOLIB_SX127X_BITRATE_LSB 0x0B // 7 0 default value: 4.8 kbps
// SX127X_REG_FDEV_MSB + SX127X_REG_FDEV_LSB // SX127X_REG_FDEV_MSB + SX127X_REG_FDEV_LSB
#define SX127X_FDEV_MSB 0x00 // 5 0 frequency deviation: Fdev = Fstep * FDEV #define RADIOLIB_SX127X_FDEV_MSB 0x00 // 5 0 frequency deviation: Fdev = Fstep * FDEV
#define SX127X_FDEV_LSB 0x52 // 7 0 default value: 5 kHz #define RADIOLIB_SX127X_FDEV_LSB 0x52 // 7 0 default value: 5 kHz
// SX127X_REG_RX_CONFIG // SX127X_REG_RX_CONFIG
#define SX127X_RESTART_RX_ON_COLLISION_OFF 0b00000000 // 7 7 automatic receiver restart disabled (default) #define RADIOLIB_SX127X_RESTART_RX_ON_COLLISION_OFF 0b00000000 // 7 7 automatic receiver restart disabled (default)
#define SX127X_RESTART_RX_ON_COLLISION_ON 0b10000000 // 7 7 automatically restart receiver if it gets saturated or on packet collision #define RADIOLIB_SX127X_RESTART_RX_ON_COLLISION_ON 0b10000000 // 7 7 automatically restart receiver if it gets saturated or on packet collision
#define SX127X_RESTART_RX_WITHOUT_PLL_LOCK 0b01000000 // 6 6 manually restart receiver without frequency change #define RADIOLIB_SX127X_RESTART_RX_WITHOUT_PLL_LOCK 0b01000000 // 6 6 manually restart receiver without frequency change
#define SX127X_RESTART_RX_WITH_PLL_LOCK 0b00100000 // 5 5 manually restart receiver with frequency change #define RADIOLIB_SX127X_RESTART_RX_WITH_PLL_LOCK 0b00100000 // 5 5 manually restart receiver with frequency change
#define SX127X_AFC_AUTO_OFF 0b00000000 // 4 4 no AFC performed (default) #define RADIOLIB_SX127X_AFC_AUTO_OFF 0b00000000 // 4 4 no AFC performed (default)
#define SX127X_AFC_AUTO_ON 0b00010000 // 4 4 AFC performed at each receiver startup #define RADIOLIB_SX127X_AFC_AUTO_ON 0b00010000 // 4 4 AFC performed at each receiver startup
#define SX127X_AGC_AUTO_OFF 0b00000000 // 3 3 LNA gain set manually by register #define RADIOLIB_SX127X_AGC_AUTO_OFF 0b00000000 // 3 3 LNA gain set manually by register
#define SX127X_AGC_AUTO_ON 0b00001000 // 3 3 LNA gain controlled by AGC #define RADIOLIB_SX127X_AGC_AUTO_ON 0b00001000 // 3 3 LNA gain controlled by AGC
#define SX127X_RX_TRIGGER_NONE 0b00000000 // 2 0 receiver startup at: none #define RADIOLIB_SX127X_RX_TRIGGER_NONE 0b00000000 // 2 0 receiver startup at: none
#define SX127X_RX_TRIGGER_RSSI_INTERRUPT 0b00000001 // 2 0 RSSI interrupt #define RADIOLIB_SX127X_RX_TRIGGER_RSSI_INTERRUPT 0b00000001 // 2 0 RSSI interrupt
#define SX127X_RX_TRIGGER_PREAMBLE_DETECT 0b00000110 // 2 0 preamble detected #define RADIOLIB_SX127X_RX_TRIGGER_PREAMBLE_DETECT 0b00000110 // 2 0 preamble detected
#define SX127X_RX_TRIGGER_BOTH 0b00000111 // 2 0 RSSI interrupt and preamble detected #define RADIOLIB_SX127X_RX_TRIGGER_BOTH 0b00000111 // 2 0 RSSI interrupt and preamble detected
// SX127X_REG_RSSI_CONFIG // SX127X_REG_RSSI_CONFIG
#define SX127X_RSSI_SMOOTHING_SAMPLES_2 0b00000000 // 2 0 number of samples for RSSI average: 2 #define RADIOLIB_SX127X_RSSI_SMOOTHING_SAMPLES_2 0b00000000 // 2 0 number of samples for RSSI average: 2
#define SX127X_RSSI_SMOOTHING_SAMPLES_4 0b00000001 // 2 0 4 #define RADIOLIB_SX127X_RSSI_SMOOTHING_SAMPLES_4 0b00000001 // 2 0 4
#define SX127X_RSSI_SMOOTHING_SAMPLES_8 0b00000010 // 2 0 8 (default) #define RADIOLIB_SX127X_RSSI_SMOOTHING_SAMPLES_8 0b00000010 // 2 0 8 (default)
#define SX127X_RSSI_SMOOTHING_SAMPLES_16 0b00000011 // 2 0 16 #define RADIOLIB_SX127X_RSSI_SMOOTHING_SAMPLES_16 0b00000011 // 2 0 16
#define SX127X_RSSI_SMOOTHING_SAMPLES_32 0b00000100 // 2 0 32 #define RADIOLIB_SX127X_RSSI_SMOOTHING_SAMPLES_32 0b00000100 // 2 0 32
#define SX127X_RSSI_SMOOTHING_SAMPLES_64 0b00000101 // 2 0 64 #define RADIOLIB_SX127X_RSSI_SMOOTHING_SAMPLES_64 0b00000101 // 2 0 64
#define SX127X_RSSI_SMOOTHING_SAMPLES_128 0b00000110 // 2 0 128 #define RADIOLIB_SX127X_RSSI_SMOOTHING_SAMPLES_128 0b00000110 // 2 0 128
#define SX127X_RSSI_SMOOTHING_SAMPLES_256 0b00000111 // 2 0 256 #define RADIOLIB_SX127X_RSSI_SMOOTHING_SAMPLES_256 0b00000111 // 2 0 256
// SX127X_REG_RSSI_COLLISION // SX127X_REG_RSSI_COLLISION
#define SX127X_RSSI_COLLISION_THRESHOLD 0x0A // 7 0 RSSI threshold in dB that will be considered a collision, default value: 10 dB #define RADIOLIB_SX127X_RSSI_COLLISION_THRESHOLD 0x0A // 7 0 RSSI threshold in dB that will be considered a collision, default value: 10 dB
// SX127X_REG_RSSI_THRESH // SX127X_REG_RSSI_THRESH
#define SX127X_RSSI_THRESHOLD 0xFF // 7 0 RSSI threshold that will trigger RSSI interrupt, RssiThreshold = RSSI_THRESHOLD / 2 [dBm] #define RADIOLIB_SX127X_RSSI_THRESHOLD 0xFF // 7 0 RSSI threshold that will trigger RSSI interrupt, RssiThreshold = RSSI_THRESHOLD / 2 [dBm]
// SX127X_REG_RX_BW // SX127X_REG_RX_BW
#define SX127X_RX_BW_MANT_16 0b00000000 // 4 3 channel filter bandwidth: RxBw = F(XOSC) / (RxBwMant * 2^(RxBwExp + 2)) [kHz] #define RADIOLIB_SX127X_RX_BW_MANT_16 0b00000000 // 4 3 channel filter bandwidth: RxBw = F(XOSC) / (RxBwMant * 2^(RxBwExp + 2)) [kHz]
#define SX127X_RX_BW_MANT_20 0b00001000 // 4 3 #define RADIOLIB_SX127X_RX_BW_MANT_20 0b00001000 // 4 3
#define SX127X_RX_BW_MANT_24 0b00010000 // 4 3 default RxBwMant parameter #define RADIOLIB_SX127X_RX_BW_MANT_24 0b00010000 // 4 3 default RxBwMant parameter
#define SX127X_RX_BW_EXP 0b00000101 // 2 0 default RxBwExp parameter #define RADIOLIB_SX127X_RX_BW_EXP 0b00000101 // 2 0 default RxBwExp parameter
// SX127X_REG_AFC_BW // SX127X_REG_AFC_BW
#define SX127X_RX_BW_MANT_AFC 0b00001000 // 4 3 default RxBwMant parameter used during AFC #define RADIOLIB_SX127X_RX_BW_MANT_AFC 0b00001000 // 4 3 default RxBwMant parameter used during AFC
#define SX127X_RX_BW_EXP_AFC 0b00000011 // 2 0 default RxBwExp parameter used during AFC #define RADIOLIB_SX127X_RX_BW_EXP_AFC 0b00000011 // 2 0 default RxBwExp parameter used during AFC
// SX127X_REG_OOK_PEAK // SX127X_REG_OOK_PEAK
#define SX127X_BIT_SYNC_OFF 0b00000000 // 5 5 bit synchronizer disabled (not allowed in packet mode) #define RADIOLIB_SX127X_BIT_SYNC_OFF 0b00000000 // 5 5 bit synchronizer disabled (not allowed in packet mode)
#define SX127X_BIT_SYNC_ON 0b00100000 // 5 5 bit synchronizer enabled (default) #define RADIOLIB_SX127X_BIT_SYNC_ON 0b00100000 // 5 5 bit synchronizer enabled (default)
#define SX127X_OOK_THRESH_FIXED 0b00000000 // 4 3 OOK threshold type: fixed value #define RADIOLIB_SX127X_OOK_THRESH_FIXED 0b00000000 // 4 3 OOK threshold type: fixed value
#define SX127X_OOK_THRESH_PEAK 0b00001000 // 4 3 peak mode (default) #define RADIOLIB_SX127X_OOK_THRESH_PEAK 0b00001000 // 4 3 peak mode (default)
#define SX127X_OOK_THRESH_AVERAGE 0b00010000 // 4 3 average mode #define RADIOLIB_SX127X_OOK_THRESH_AVERAGE 0b00010000 // 4 3 average mode
#define SX127X_OOK_PEAK_THRESH_STEP_0_5_DB 0b00000000 // 2 0 OOK demodulator step size: 0.5 dB (default) #define RADIOLIB_SX127X_OOK_PEAK_THRESH_STEP_0_5_DB 0b00000000 // 2 0 OOK demodulator step size: 0.5 dB (default)
#define SX127X_OOK_PEAK_THRESH_STEP_1_0_DB 0b00000001 // 2 0 1.0 dB #define RADIOLIB_SX127X_OOK_PEAK_THRESH_STEP_1_0_DB 0b00000001 // 2 0 1.0 dB
#define SX127X_OOK_PEAK_THRESH_STEP_1_5_DB 0b00000010 // 2 0 1.5 dB #define RADIOLIB_SX127X_OOK_PEAK_THRESH_STEP_1_5_DB 0b00000010 // 2 0 1.5 dB
#define SX127X_OOK_PEAK_THRESH_STEP_2_0_DB 0b00000011 // 2 0 2.0 dB #define RADIOLIB_SX127X_OOK_PEAK_THRESH_STEP_2_0_DB 0b00000011 // 2 0 2.0 dB
#define SX127X_OOK_PEAK_THRESH_STEP_3_0_DB 0b00000100 // 2 0 3.0 dB #define RADIOLIB_SX127X_OOK_PEAK_THRESH_STEP_3_0_DB 0b00000100 // 2 0 3.0 dB
#define SX127X_OOK_PEAK_THRESH_STEP_4_0_DB 0b00000101 // 2 0 4.0 dB #define RADIOLIB_SX127X_OOK_PEAK_THRESH_STEP_4_0_DB 0b00000101 // 2 0 4.0 dB
#define SX127X_OOK_PEAK_THRESH_STEP_5_0_DB 0b00000110 // 2 0 5.0 dB #define RADIOLIB_SX127X_OOK_PEAK_THRESH_STEP_5_0_DB 0b00000110 // 2 0 5.0 dB
#define SX127X_OOK_PEAK_THRESH_STEP_6_0_DB 0b00000111 // 2 0 6.0 dB #define RADIOLIB_SX127X_OOK_PEAK_THRESH_STEP_6_0_DB 0b00000111 // 2 0 6.0 dB
// SX127X_REG_OOK_FIX // SX127X_REG_OOK_FIX
#define SX127X_OOK_FIXED_THRESHOLD 0x0C // 7 0 default fixed threshold for OOK data slicer #define RADIOLIB_SX127X_OOK_FIXED_THRESHOLD 0x0C // 7 0 default fixed threshold for OOK data slicer
// SX127X_REG_OOK_AVG // SX127X_REG_OOK_AVG
#define SX127X_OOK_PEAK_THRESH_DEC_1_1_CHIP 0b00000000 // 7 5 OOK demodulator step period: once per chip (default) #define RADIOLIB_SX127X_OOK_PEAK_THRESH_DEC_1_1_CHIP 0b00000000 // 7 5 OOK demodulator step period: once per chip (default)
#define SX127X_OOK_PEAK_THRESH_DEC_1_2_CHIP 0b00100000 // 7 5 once every 2 chips #define RADIOLIB_SX127X_OOK_PEAK_THRESH_DEC_1_2_CHIP 0b00100000 // 7 5 once every 2 chips
#define SX127X_OOK_PEAK_THRESH_DEC_1_4_CHIP 0b01000000 // 7 5 once every 4 chips #define RADIOLIB_SX127X_OOK_PEAK_THRESH_DEC_1_4_CHIP 0b01000000 // 7 5 once every 4 chips
#define SX127X_OOK_PEAK_THRESH_DEC_1_8_CHIP 0b01100000 // 7 5 once every 8 chips #define RADIOLIB_SX127X_OOK_PEAK_THRESH_DEC_1_8_CHIP 0b01100000 // 7 5 once every 8 chips
#define SX127X_OOK_PEAK_THRESH_DEC_2_1_CHIP 0b10000000 // 7 5 2 times per chip #define RADIOLIB_SX127X_OOK_PEAK_THRESH_DEC_2_1_CHIP 0b10000000 // 7 5 2 times per chip
#define SX127X_OOK_PEAK_THRESH_DEC_4_1_CHIP 0b10100000 // 7 5 4 times per chip #define RADIOLIB_SX127X_OOK_PEAK_THRESH_DEC_4_1_CHIP 0b10100000 // 7 5 4 times per chip
#define SX127X_OOK_PEAK_THRESH_DEC_8_1_CHIP 0b11000000 // 7 5 8 times per chip #define RADIOLIB_SX127X_OOK_PEAK_THRESH_DEC_8_1_CHIP 0b11000000 // 7 5 8 times per chip
#define SX127X_OOK_PEAK_THRESH_DEC_16_1_CHIP 0b11100000 // 7 5 16 times per chip #define RADIOLIB_SX127X_OOK_PEAK_THRESH_DEC_16_1_CHIP 0b11100000 // 7 5 16 times per chip
#define SX127X_OOK_AVERAGE_OFFSET_0_DB 0b00000000 // 3 2 OOK average threshold offset: 0.0 dB (default) #define RADIOLIB_SX127X_OOK_AVERAGE_OFFSET_0_DB 0b00000000 // 3 2 OOK average threshold offset: 0.0 dB (default)
#define SX127X_OOK_AVERAGE_OFFSET_2_DB 0b00000100 // 3 2 2.0 dB #define RADIOLIB_SX127X_OOK_AVERAGE_OFFSET_2_DB 0b00000100 // 3 2 2.0 dB
#define SX127X_OOK_AVERAGE_OFFSET_4_DB 0b00001000 // 3 2 4.0 dB #define RADIOLIB_SX127X_OOK_AVERAGE_OFFSET_4_DB 0b00001000 // 3 2 4.0 dB
#define SX127X_OOK_AVERAGE_OFFSET_6_DB 0b00001100 // 3 2 6.0 dB #define RADIOLIB_SX127X_OOK_AVERAGE_OFFSET_6_DB 0b00001100 // 3 2 6.0 dB
#define SX127X_OOK_AVG_THRESH_FILT_32_PI 0b00000000 // 1 0 OOK average filter coefficient: chip rate / 32*pi #define RADIOLIB_SX127X_OOK_AVG_THRESH_FILT_32_PI 0b00000000 // 1 0 OOK average filter coefficient: chip rate / 32*pi
#define SX127X_OOK_AVG_THRESH_FILT_8_PI 0b00000001 // 1 0 chip rate / 8*pi #define RADIOLIB_SX127X_OOK_AVG_THRESH_FILT_8_PI 0b00000001 // 1 0 chip rate / 8*pi
#define SX127X_OOK_AVG_THRESH_FILT_4_PI 0b00000010 // 1 0 chip rate / 4*pi (default) #define RADIOLIB_SX127X_OOK_AVG_THRESH_FILT_4_PI 0b00000010 // 1 0 chip rate / 4*pi (default)
#define SX127X_OOK_AVG_THRESH_FILT_2_PI 0b00000011 // 1 0 chip rate / 2*pi #define RADIOLIB_SX127X_OOK_AVG_THRESH_FILT_2_PI 0b00000011 // 1 0 chip rate / 2*pi
// SX127X_REG_AFC_FEI // SX127X_REG_AFC_FEI
#define SX127X_AGC_START 0b00010000 // 4 4 manually start AGC sequence #define RADIOLIB_SX127X_AGC_START 0b00010000 // 4 4 manually start AGC sequence
#define SX127X_AFC_CLEAR 0b00000010 // 1 1 manually clear AFC register #define RADIOLIB_SX127X_AFC_CLEAR 0b00000010 // 1 1 manually clear AFC register
#define SX127X_AFC_AUTO_CLEAR_OFF 0b00000000 // 0 0 AFC register will not be cleared at the start of AFC (default) #define RADIOLIB_SX127X_AFC_AUTO_CLEAR_OFF 0b00000000 // 0 0 AFC register will not be cleared at the start of AFC (default)
#define SX127X_AFC_AUTO_CLEAR_ON 0b00000001 // 0 0 AFC register will be cleared at the start of AFC #define RADIOLIB_SX127X_AFC_AUTO_CLEAR_ON 0b00000001 // 0 0 AFC register will be cleared at the start of AFC
// SX127X_REG_PREAMBLE_DETECT // SX127X_REG_PREAMBLE_DETECT
#define SX127X_PREAMBLE_DETECTOR_OFF 0b00000000 // 7 7 preamble detection disabled #define RADIOLIB_SX127X_PREAMBLE_DETECTOR_OFF 0b00000000 // 7 7 preamble detection disabled
#define SX127X_PREAMBLE_DETECTOR_ON 0b10000000 // 7 7 preamble detection enabled (default) #define RADIOLIB_SX127X_PREAMBLE_DETECTOR_ON 0b10000000 // 7 7 preamble detection enabled (default)
#define SX127X_PREAMBLE_DETECTOR_1_BYTE 0b00000000 // 6 5 preamble detection size: 1 byte (default) #define RADIOLIB_SX127X_PREAMBLE_DETECTOR_1_BYTE 0b00000000 // 6 5 preamble detection size: 1 byte (default)
#define SX127X_PREAMBLE_DETECTOR_2_BYTE 0b00100000 // 6 5 2 bytes #define RADIOLIB_SX127X_PREAMBLE_DETECTOR_2_BYTE 0b00100000 // 6 5 2 bytes
#define SX127X_PREAMBLE_DETECTOR_3_BYTE 0b01000000 // 6 5 3 bytes #define RADIOLIB_SX127X_PREAMBLE_DETECTOR_3_BYTE 0b01000000 // 6 5 3 bytes
#define SX127X_PREAMBLE_DETECTOR_TOL 0x0A // 4 0 default number of tolerated errors per chip (4 chips per bit) #define RADIOLIB_SX127X_PREAMBLE_DETECTOR_TOL 0x0A // 4 0 default number of tolerated errors per chip (4 chips per bit)
// SX127X_REG_RX_TIMEOUT_1 // SX127X_REG_RX_TIMEOUT_1
#define SX127X_TIMEOUT_RX_RSSI_OFF 0x00 // 7 0 disable receiver timeout when RSSI interrupt doesn't occur (default) #define RADIOLIB_SX127X_TIMEOUT_RX_RSSI_OFF 0x00 // 7 0 disable receiver timeout when RSSI interrupt doesn't occur (default)
// SX127X_REG_RX_TIMEOUT_2 // SX127X_REG_RX_TIMEOUT_2
#define SX127X_TIMEOUT_RX_PREAMBLE_OFF 0x00 // 7 0 disable receiver timeout when preamble interrupt doesn't occur (default) #define RADIOLIB_SX127X_TIMEOUT_RX_PREAMBLE_OFF 0x00 // 7 0 disable receiver timeout when preamble interrupt doesn't occur (default)
// SX127X_REG_RX_TIMEOUT_3 // SX127X_REG_RX_TIMEOUT_3
#define SX127X_TIMEOUT_SIGNAL_SYNC_OFF 0x00 // 7 0 disable receiver timeout when sync address interrupt doesn't occur (default) #define RADIOLIB_SX127X_TIMEOUT_SIGNAL_SYNC_OFF 0x00 // 7 0 disable receiver timeout when sync address interrupt doesn't occur (default)
// SX127X_REG_OSC // SX127X_REG_OSC
#define SX127X_RC_CAL_START 0b00000000 // 3 3 manually start RC oscillator calibration #define RADIOLIB_SX127X_RC_CAL_START 0b00000000 // 3 3 manually start RC oscillator calibration
#define SX127X_CLK_OUT_FXOSC 0b00000000 // 2 0 ClkOut frequency: F(XOSC) #define RADIOLIB_SX127X_CLK_OUT_FXOSC 0b00000000 // 2 0 ClkOut frequency: F(XOSC)
#define SX127X_CLK_OUT_FXOSC_2 0b00000001 // 2 0 F(XOSC) / 2 #define RADIOLIB_SX127X_CLK_OUT_FXOSC_2 0b00000001 // 2 0 F(XOSC) / 2
#define SX127X_CLK_OUT_FXOSC_4 0b00000010 // 2 0 F(XOSC) / 4 #define RADIOLIB_SX127X_CLK_OUT_FXOSC_4 0b00000010 // 2 0 F(XOSC) / 4
#define SX127X_CLK_OUT_FXOSC_8 0b00000011 // 2 0 F(XOSC) / 8 #define RADIOLIB_SX127X_CLK_OUT_FXOSC_8 0b00000011 // 2 0 F(XOSC) / 8
#define SX127X_CLK_OUT_FXOSC_16 0b00000100 // 2 0 F(XOSC) / 16 #define RADIOLIB_SX127X_CLK_OUT_FXOSC_16 0b00000100 // 2 0 F(XOSC) / 16
#define SX127X_CLK_OUT_FXOSC_32 0b00000101 // 2 0 F(XOSC) / 32 #define RADIOLIB_SX127X_CLK_OUT_FXOSC_32 0b00000101 // 2 0 F(XOSC) / 32
#define SX127X_CLK_OUT_RC 0b00000110 // 2 0 RC #define RADIOLIB_SX127X_CLK_OUT_RC 0b00000110 // 2 0 RC
#define SX127X_CLK_OUT_OFF 0b00000111 // 2 0 disabled (default) #define RADIOLIB_SX127X_CLK_OUT_OFF 0b00000111 // 2 0 disabled (default)
// SX127X_REG_PREAMBLE_MSB_FSK + SX127X_REG_PREAMBLE_LSB_FSK // SX127X_REG_PREAMBLE_MSB_FSK + SX127X_REG_PREAMBLE_LSB_FSK
#define SX127X_PREAMBLE_SIZE_MSB 0x00 // 7 0 preamble size in bytes #define RADIOLIB_SX127X_PREAMBLE_SIZE_MSB 0x00 // 7 0 preamble size in bytes
#define SX127X_PREAMBLE_SIZE_LSB 0x03 // 7 0 default value: 3 bytes #define RADIOLIB_SX127X_PREAMBLE_SIZE_LSB 0x03 // 7 0 default value: 3 bytes
// SX127X_REG_SYNC_CONFIG // SX127X_REG_SYNC_CONFIG
#define SX127X_AUTO_RESTART_RX_MODE_OFF 0b00000000 // 7 6 Rx mode restart after packet reception: disabled #define RADIOLIB_SX127X_AUTO_RESTART_RX_MODE_OFF 0b00000000 // 7 6 Rx mode restart after packet reception: disabled
#define SX127X_AUTO_RESTART_RX_MODE_NO_PLL 0b01000000 // 7 6 enabled, don't wait for PLL lock #define RADIOLIB_SX127X_AUTO_RESTART_RX_MODE_NO_PLL 0b01000000 // 7 6 enabled, don't wait for PLL lock
#define SX127X_AUTO_RESTART_RX_MODE_PLL 0b10000000 // 7 6 enabled, wait for PLL lock (default) #define RADIOLIB_SX127X_AUTO_RESTART_RX_MODE_PLL 0b10000000 // 7 6 enabled, wait for PLL lock (default)
#define SX127X_PREAMBLE_POLARITY_AA 0b00000000 // 5 5 preamble polarity: 0xAA = 0b10101010 (default) #define RADIOLIB_SX127X_PREAMBLE_POLARITY_AA 0b00000000 // 5 5 preamble polarity: 0xAA = 0b10101010 (default)
#define SX127X_PREAMBLE_POLARITY_55 0b00100000 // 5 5 0x55 = 0b01010101 #define RADIOLIB_SX127X_PREAMBLE_POLARITY_55 0b00100000 // 5 5 0x55 = 0b01010101
#define SX127X_SYNC_OFF 0b00000000 // 4 4 sync word disabled #define RADIOLIB_SX127X_SYNC_OFF 0b00000000 // 4 4 sync word disabled
#define SX127X_SYNC_ON 0b00010000 // 4 4 sync word enabled (default) #define RADIOLIB_SX127X_SYNC_ON 0b00010000 // 4 4 sync word enabled (default)
#define SX127X_SYNC_SIZE 0x03 // 2 0 sync word size in bytes, SyncSize = SYNC_SIZE + 1 bytes #define RADIOLIB_SX127X_SYNC_SIZE 0x03 // 2 0 sync word size in bytes, SyncSize = SYNC_SIZE + 1 bytes
// SX127X_REG_SYNC_VALUE_1 - SX127X_REG_SYNC_VALUE_8 // SX127X_REG_SYNC_VALUE_1 - SX127X_REG_SYNC_VALUE_8
#define SX127X_SYNC_VALUE_1 0x01 // 7 0 sync word: 1st byte (MSB) #define RADIOLIB_SX127X_SYNC_VALUE_1 0x01 // 7 0 sync word: 1st byte (MSB)
#define SX127X_SYNC_VALUE_2 0x01 // 7 0 2nd byte #define RADIOLIB_SX127X_SYNC_VALUE_2 0x01 // 7 0 2nd byte
#define SX127X_SYNC_VALUE_3 0x01 // 7 0 3rd byte #define RADIOLIB_SX127X_SYNC_VALUE_3 0x01 // 7 0 3rd byte
#define SX127X_SYNC_VALUE_4 0x01 // 7 0 4th byte #define RADIOLIB_SX127X_SYNC_VALUE_4 0x01 // 7 0 4th byte
#define SX127X_SYNC_VALUE_5 0x01 // 7 0 5th byte #define RADIOLIB_SX127X_SYNC_VALUE_5 0x01 // 7 0 5th byte
#define SX127X_SYNC_VALUE_6 0x01 // 7 0 6th byte #define RADIOLIB_SX127X_SYNC_VALUE_6 0x01 // 7 0 6th byte
#define SX127X_SYNC_VALUE_7 0x01 // 7 0 7th byte #define RADIOLIB_SX127X_SYNC_VALUE_7 0x01 // 7 0 7th byte
#define SX127X_SYNC_VALUE_8 0x01 // 7 0 8th byte (LSB) #define RADIOLIB_SX127X_SYNC_VALUE_8 0x01 // 7 0 8th byte (LSB)
// SX127X_REG_PACKET_CONFIG_1 // SX127X_REG_PACKET_CONFIG_1
#define SX127X_PACKET_FIXED 0b00000000 // 7 7 packet format: fixed length #define RADIOLIB_SX127X_PACKET_FIXED 0b00000000 // 7 7 packet format: fixed length
#define SX127X_PACKET_VARIABLE 0b10000000 // 7 7 variable length (default) #define RADIOLIB_SX127X_PACKET_VARIABLE 0b10000000 // 7 7 variable length (default)
#define SX127X_DC_FREE_NONE 0b00000000 // 6 5 DC-free encoding: disabled (default) #define RADIOLIB_SX127X_DC_FREE_NONE 0b00000000 // 6 5 DC-free encoding: disabled (default)
#define SX127X_DC_FREE_MANCHESTER 0b00100000 // 6 5 Manchester #define RADIOLIB_SX127X_DC_FREE_MANCHESTER 0b00100000 // 6 5 Manchester
#define SX127X_DC_FREE_WHITENING 0b01000000 // 6 5 Whitening #define RADIOLIB_SX127X_DC_FREE_WHITENING 0b01000000 // 6 5 Whitening
#define SX127X_CRC_OFF 0b00000000 // 4 4 CRC disabled #define RADIOLIB_SX127X_CRC_OFF 0b00000000 // 4 4 CRC disabled
#define SX127X_CRC_ON 0b00010000 // 4 4 CRC enabled (default) #define RADIOLIB_SX127X_CRC_ON 0b00010000 // 4 4 CRC enabled (default)
#define SX127X_CRC_AUTOCLEAR_OFF 0b00001000 // 3 3 keep FIFO on CRC mismatch, issue payload ready interrupt #define RADIOLIB_SX127X_CRC_AUTOCLEAR_OFF 0b00001000 // 3 3 keep FIFO on CRC mismatch, issue payload ready interrupt
#define SX127X_CRC_AUTOCLEAR_ON 0b00000000 // 3 3 clear FIFO on CRC mismatch, do not issue payload ready interrupt #define RADIOLIB_SX127X_CRC_AUTOCLEAR_ON 0b00000000 // 3 3 clear FIFO on CRC mismatch, do not issue payload ready interrupt
#define SX127X_ADDRESS_FILTERING_OFF 0b00000000 // 2 1 address filtering: none (default) #define RADIOLIB_SX127X_ADDRESS_FILTERING_OFF 0b00000000 // 2 1 address filtering: none (default)
#define SX127X_ADDRESS_FILTERING_NODE 0b00000010 // 2 1 node #define RADIOLIB_SX127X_ADDRESS_FILTERING_NODE 0b00000010 // 2 1 node
#define SX127X_ADDRESS_FILTERING_NODE_BROADCAST 0b00000100 // 2 1 node or broadcast #define RADIOLIB_SX127X_ADDRESS_FILTERING_NODE_BROADCAST 0b00000100 // 2 1 node or broadcast
#define SX127X_CRC_WHITENING_TYPE_CCITT 0b00000000 // 0 0 CRC and whitening algorithms: CCITT CRC with standard whitening (default) #define RADIOLIB_SX127X_CRC_WHITENING_TYPE_CCITT 0b00000000 // 0 0 CRC and whitening algorithms: CCITT CRC with standard whitening (default)
#define SX127X_CRC_WHITENING_TYPE_IBM 0b00000001 // 0 0 IBM CRC with alternate whitening #define RADIOLIB_SX127X_CRC_WHITENING_TYPE_IBM 0b00000001 // 0 0 IBM CRC with alternate whitening
// SX127X_REG_PACKET_CONFIG_2 // SX127X_REG_PACKET_CONFIG_2
#define SX127X_DATA_MODE_PACKET 0b01000000 // 6 6 data mode: packet (default) #define RADIOLIB_SX127X_DATA_MODE_PACKET 0b01000000 // 6 6 data mode: packet (default)
#define SX127X_DATA_MODE_CONTINUOUS 0b00000000 // 6 6 continuous #define RADIOLIB_SX127X_DATA_MODE_CONTINUOUS 0b00000000 // 6 6 continuous
#define SX127X_IO_HOME_OFF 0b00000000 // 5 5 io-homecontrol compatibility disabled (default) #define RADIOLIB_SX127X_IO_HOME_OFF 0b00000000 // 5 5 io-homecontrol compatibility disabled (default)
#define SX127X_IO_HOME_ON 0b00100000 // 5 5 io-homecontrol compatibility enabled #define RADIOLIB_SX127X_IO_HOME_ON 0b00100000 // 5 5 io-homecontrol compatibility enabled
// SX127X_REG_FIFO_THRESH // SX127X_REG_FIFO_THRESH
#define SX127X_TX_START_FIFO_LEVEL 0b00000000 // 7 7 start packet transmission when: number of bytes in FIFO exceeds FIFO_THRESHOLD #define RADIOLIB_SX127X_TX_START_FIFO_LEVEL 0b00000000 // 7 7 start packet transmission when: number of bytes in FIFO exceeds FIFO_THRESHOLD
#define SX127X_TX_START_FIFO_NOT_EMPTY 0b10000000 // 7 7 at least one byte in FIFO (default) #define RADIOLIB_SX127X_TX_START_FIFO_NOT_EMPTY 0b10000000 // 7 7 at least one byte in FIFO (default)
#define SX127X_FIFO_THRESH 0x0F // 5 0 FIFO level threshold #define RADIOLIB_SX127X_FIFO_THRESH 0x0F // 5 0 FIFO level threshold
// SX127X_REG_SEQ_CONFIG_1 // SX127X_REG_SEQ_CONFIG_1
#define SX127X_SEQUENCER_START 0b10000000 // 7 7 manually start sequencer #define RADIOLIB_SX127X_SEQUENCER_START 0b10000000 // 7 7 manually start sequencer
#define SX127X_SEQUENCER_STOP 0b01000000 // 6 6 manually stop sequencer #define RADIOLIB_SX127X_SEQUENCER_STOP 0b01000000 // 6 6 manually stop sequencer
#define SX127X_IDLE_MODE_STANDBY 0b00000000 // 5 5 chip mode during sequencer idle mode: standby (default) #define RADIOLIB_SX127X_IDLE_MODE_STANDBY 0b00000000 // 5 5 chip mode during sequencer idle mode: standby (default)
#define SX127X_IDLE_MODE_SLEEP 0b00100000 // 5 5 sleep #define RADIOLIB_SX127X_IDLE_MODE_SLEEP 0b00100000 // 5 5 sleep
#define SX127X_FROM_START_LP_SELECTION 0b00000000 // 4 3 mode that will be set after starting sequencer: low power selection (default) #define RADIOLIB_SX127X_FROM_START_LP_SELECTION 0b00000000 // 4 3 mode that will be set after starting sequencer: low power selection (default)
#define SX127X_FROM_START_RECEIVE 0b00001000 // 4 3 receive #define RADIOLIB_SX127X_FROM_START_RECEIVE 0b00001000 // 4 3 receive
#define SX127X_FROM_START_TRANSMIT 0b00010000 // 4 3 transmit #define RADIOLIB_SX127X_FROM_START_TRANSMIT 0b00010000 // 4 3 transmit
#define SX127X_FROM_START_TRANSMIT_FIFO_LEVEL 0b00011000 // 4 3 transmit on a FIFO level interrupt #define RADIOLIB_SX127X_FROM_START_TRANSMIT_FIFO_LEVEL 0b00011000 // 4 3 transmit on a FIFO level interrupt
#define SX127X_LP_SELECTION_SEQ_OFF 0b00000000 // 2 2 mode that will be set after exiting low power selection: sequencer off (default) #define RADIOLIB_SX127X_LP_SELECTION_SEQ_OFF 0b00000000 // 2 2 mode that will be set after exiting low power selection: sequencer off (default)
#define SX127X_LP_SELECTION_IDLE 0b00000100 // 2 2 idle state #define RADIOLIB_SX127X_LP_SELECTION_IDLE 0b00000100 // 2 2 idle state
#define SX127X_FROM_IDLE_TRANSMIT 0b00000000 // 1 1 mode that will be set after exiting idle mode: transmit (default) #define RADIOLIB_SX127X_FROM_IDLE_TRANSMIT 0b00000000 // 1 1 mode that will be set after exiting idle mode: transmit (default)
#define SX127X_FROM_IDLE_RECEIVE 0b00000010 // 1 1 receive #define RADIOLIB_SX127X_FROM_IDLE_RECEIVE 0b00000010 // 1 1 receive
#define SX127X_FROM_TRANSMIT_LP_SELECTION 0b00000000 // 0 0 mode that will be set after exiting transmit mode: low power selection (default) #define RADIOLIB_SX127X_FROM_TRANSMIT_LP_SELECTION 0b00000000 // 0 0 mode that will be set after exiting transmit mode: low power selection (default)
#define SX127X_FROM_TRANSMIT_RECEIVE 0b00000001 // 0 0 receive #define RADIOLIB_SX127X_FROM_TRANSMIT_RECEIVE 0b00000001 // 0 0 receive
// SX127X_REG_SEQ_CONFIG_2 // SX127X_REG_SEQ_CONFIG_2
#define SX127X_FROM_RECEIVE_PACKET_RECEIVED_PAYLOAD 0b00100000 // 7 5 mode that will be set after exiting receive mode: packet received on payload ready interrupt (default) #define RADIOLIB_SX127X_FROM_RECEIVE_PACKET_RECEIVED_PAYLOAD 0b00100000 // 7 5 mode that will be set after exiting receive mode: packet received on payload ready interrupt (default)
#define SX127X_FROM_RECEIVE_LP_SELECTION 0b01000000 // 7 5 low power selection #define RADIOLIB_SX127X_FROM_RECEIVE_LP_SELECTION 0b01000000 // 7 5 low power selection
#define SX127X_FROM_RECEIVE_PACKET_RECEIVED_CRC_OK 0b01100000 // 7 5 packet received on CRC OK interrupt #define RADIOLIB_SX127X_FROM_RECEIVE_PACKET_RECEIVED_CRC_OK 0b01100000 // 7 5 packet received on CRC OK interrupt
#define SX127X_FROM_RECEIVE_SEQ_OFF_RSSI 0b10000000 // 7 5 sequencer off on RSSI interrupt #define RADIOLIB_SX127X_FROM_RECEIVE_SEQ_OFF_RSSI 0b10000000 // 7 5 sequencer off on RSSI interrupt
#define SX127X_FROM_RECEIVE_SEQ_OFF_SYNC_ADDR 0b10100000 // 7 5 sequencer off on sync address interrupt #define RADIOLIB_SX127X_FROM_RECEIVE_SEQ_OFF_SYNC_ADDR 0b10100000 // 7 5 sequencer off on sync address interrupt
#define SX127X_FROM_RECEIVE_SEQ_OFF_PREAMBLE_DETECT 0b11000000 // 7 5 sequencer off on preamble detect interrupt #define RADIOLIB_SX127X_FROM_RECEIVE_SEQ_OFF_PREAMBLE_DETECT 0b11000000 // 7 5 sequencer off on preamble detect interrupt
#define SX127X_FROM_RX_TIMEOUT_RECEIVE 0b00000000 // 4 3 mode that will be set after Rx timeout: receive (default) #define RADIOLIB_SX127X_FROM_RX_TIMEOUT_RECEIVE 0b00000000 // 4 3 mode that will be set after Rx timeout: receive (default)
#define SX127X_FROM_RX_TIMEOUT_TRANSMIT 0b00001000 // 4 3 transmit #define RADIOLIB_SX127X_FROM_RX_TIMEOUT_TRANSMIT 0b00001000 // 4 3 transmit
#define SX127X_FROM_RX_TIMEOUT_LP_SELECTION 0b00010000 // 4 3 low power selection #define RADIOLIB_SX127X_FROM_RX_TIMEOUT_LP_SELECTION 0b00010000 // 4 3 low power selection
#define SX127X_FROM_RX_TIMEOUT_SEQ_OFF 0b00011000 // 4 3 sequencer off #define RADIOLIB_SX127X_FROM_RX_TIMEOUT_SEQ_OFF 0b00011000 // 4 3 sequencer off
#define SX127X_FROM_PACKET_RECEIVED_SEQ_OFF 0b00000000 // 2 0 mode that will be set after packet received: sequencer off (default) #define RADIOLIB_SX127X_FROM_PACKET_RECEIVED_SEQ_OFF 0b00000000 // 2 0 mode that will be set after packet received: sequencer off (default)
#define SX127X_FROM_PACKET_RECEIVED_TRANSMIT 0b00000001 // 2 0 transmit #define RADIOLIB_SX127X_FROM_PACKET_RECEIVED_TRANSMIT 0b00000001 // 2 0 transmit
#define SX127X_FROM_PACKET_RECEIVED_LP_SELECTION 0b00000010 // 2 0 low power selection #define RADIOLIB_SX127X_FROM_PACKET_RECEIVED_LP_SELECTION 0b00000010 // 2 0 low power selection
#define SX127X_FROM_PACKET_RECEIVED_RECEIVE_FS 0b00000011 // 2 0 receive via FS #define RADIOLIB_SX127X_FROM_PACKET_RECEIVED_RECEIVE_FS 0b00000011 // 2 0 receive via FS
#define SX127X_FROM_PACKET_RECEIVED_RECEIVE 0b00000100 // 2 0 receive #define RADIOLIB_SX127X_FROM_PACKET_RECEIVED_RECEIVE 0b00000100 // 2 0 receive
// SX127X_REG_TIMER_RESOL // SX127X_REG_TIMER_RESOL
#define SX127X_TIMER1_OFF 0b00000000 // 3 2 timer 1 resolution: disabled (default) #define RADIOLIB_SX127X_TIMER1_OFF 0b00000000 // 3 2 timer 1 resolution: disabled (default)
#define SX127X_TIMER1_RESOLUTION_64_US 0b00000100 // 3 2 64 us #define RADIOLIB_SX127X_TIMER1_RESOLUTION_64_US 0b00000100 // 3 2 64 us
#define SX127X_TIMER1_RESOLUTION_4_1_MS 0b00001000 // 3 2 4.1 ms #define RADIOLIB_SX127X_TIMER1_RESOLUTION_4_1_MS 0b00001000 // 3 2 4.1 ms
#define SX127X_TIMER1_RESOLUTION_262_MS 0b00001100 // 3 2 262 ms #define RADIOLIB_SX127X_TIMER1_RESOLUTION_262_MS 0b00001100 // 3 2 262 ms
#define SX127X_TIMER2_OFF 0b00000000 // 3 2 timer 2 resolution: disabled (default) #define RADIOLIB_SX127X_TIMER2_OFF 0b00000000 // 3 2 timer 2 resolution: disabled (default)
#define SX127X_TIMER2_RESOLUTION_64_US 0b00000001 // 3 2 64 us #define RADIOLIB_SX127X_TIMER2_RESOLUTION_64_US 0b00000001 // 3 2 64 us
#define SX127X_TIMER2_RESOLUTION_4_1_MS 0b00000010 // 3 2 4.1 ms #define RADIOLIB_SX127X_TIMER2_RESOLUTION_4_1_MS 0b00000010 // 3 2 4.1 ms
#define SX127X_TIMER2_RESOLUTION_262_MS 0b00000011 // 3 2 262 ms #define RADIOLIB_SX127X_TIMER2_RESOLUTION_262_MS 0b00000011 // 3 2 262 ms
// SX127X_REG_TIMER1_COEF // SX127X_REG_TIMER1_COEF
#define SX127X_TIMER1_COEFFICIENT 0xF5 // 7 0 multiplication coefficient for timer 1 #define RADIOLIB_SX127X_TIMER1_COEFFICIENT 0xF5 // 7 0 multiplication coefficient for timer 1
// SX127X_REG_TIMER2_COEF // SX127X_REG_TIMER2_COEF
#define SX127X_TIMER2_COEFFICIENT 0x20 // 7 0 multiplication coefficient for timer 2 #define RADIOLIB_SX127X_TIMER2_COEFFICIENT 0x20 // 7 0 multiplication coefficient for timer 2
// SX127X_REG_IMAGE_CAL // SX127X_REG_IMAGE_CAL
#define SX127X_AUTO_IMAGE_CAL_OFF 0b00000000 // 7 7 temperature calibration disabled (default) #define RADIOLIB_SX127X_AUTO_IMAGE_CAL_OFF 0b00000000 // 7 7 temperature calibration disabled (default)
#define SX127X_AUTO_IMAGE_CAL_ON 0b10000000 // 7 7 temperature calibration enabled #define RADIOLIB_SX127X_AUTO_IMAGE_CAL_ON 0b10000000 // 7 7 temperature calibration enabled
#define SX127X_IMAGE_CAL_START 0b01000000 // 6 6 start temperature calibration #define RADIOLIB_SX127X_IMAGE_CAL_START 0b01000000 // 6 6 start temperature calibration
#define SX127X_IMAGE_CAL_RUNNING 0b00100000 // 5 5 temperature calibration is on-going #define RADIOLIB_SX127X_IMAGE_CAL_RUNNING 0b00100000 // 5 5 temperature calibration is on-going
#define SX127X_IMAGE_CAL_COMPLETE 0b00000000 // 5 5 temperature calibration finished #define RADIOLIB_SX127X_IMAGE_CAL_COMPLETE 0b00000000 // 5 5 temperature calibration finished
#define SX127X_TEMP_CHANGED 0b00001000 // 3 3 temperature changed more than TEMP_THRESHOLD since last calibration #define RADIOLIB_SX127X_TEMP_CHANGED 0b00001000 // 3 3 temperature changed more than TEMP_THRESHOLD since last calibration
#define SX127X_TEMP_THRESHOLD_5_DEG_C 0b00000000 // 2 1 temperature change threshold: 5 deg. C #define RADIOLIB_SX127X_TEMP_THRESHOLD_5_DEG_C 0b00000000 // 2 1 temperature change threshold: 5 deg. C
#define SX127X_TEMP_THRESHOLD_10_DEG_C 0b00000010 // 2 1 10 deg. C (default) #define RADIOLIB_SX127X_TEMP_THRESHOLD_10_DEG_C 0b00000010 // 2 1 10 deg. C (default)
#define SX127X_TEMP_THRESHOLD_15_DEG_C 0b00000100 // 2 1 15 deg. C #define RADIOLIB_SX127X_TEMP_THRESHOLD_15_DEG_C 0b00000100 // 2 1 15 deg. C
#define SX127X_TEMP_THRESHOLD_20_DEG_C 0b00000110 // 2 1 20 deg. C #define RADIOLIB_SX127X_TEMP_THRESHOLD_20_DEG_C 0b00000110 // 2 1 20 deg. C
#define SX127X_TEMP_MONITOR_ON 0b00000000 // 0 0 temperature monitoring enabled (default) #define RADIOLIB_SX127X_TEMP_MONITOR_ON 0b00000000 // 0 0 temperature monitoring enabled (default)
#define SX127X_TEMP_MONITOR_OFF 0b00000001 // 0 0 temperature monitoring disabled #define RADIOLIB_SX127X_TEMP_MONITOR_OFF 0b00000001 // 0 0 temperature monitoring disabled
// SX127X_REG_LOW_BAT // SX127X_REG_LOW_BAT
#define SX127X_LOW_BAT_OFF 0b00000000 // 3 3 low battery detector disabled #define RADIOLIB_SX127X_LOW_BAT_OFF 0b00000000 // 3 3 low battery detector disabled
#define SX127X_LOW_BAT_ON 0b00001000 // 3 3 low battery detector enabled #define RADIOLIB_SX127X_LOW_BAT_ON 0b00001000 // 3 3 low battery detector enabled
#define SX127X_LOW_BAT_TRIM_1_695_V 0b00000000 // 2 0 battery voltage threshold: 1.695 V #define RADIOLIB_SX127X_LOW_BAT_TRIM_1_695_V 0b00000000 // 2 0 battery voltage threshold: 1.695 V
#define SX127X_LOW_BAT_TRIM_1_764_V 0b00000001 // 2 0 1.764 V #define RADIOLIB_SX127X_LOW_BAT_TRIM_1_764_V 0b00000001 // 2 0 1.764 V
#define SX127X_LOW_BAT_TRIM_1_835_V 0b00000010 // 2 0 1.835 V (default) #define RADIOLIB_SX127X_LOW_BAT_TRIM_1_835_V 0b00000010 // 2 0 1.835 V (default)
#define SX127X_LOW_BAT_TRIM_1_905_V 0b00000011 // 2 0 1.905 V #define RADIOLIB_SX127X_LOW_BAT_TRIM_1_905_V 0b00000011 // 2 0 1.905 V
#define SX127X_LOW_BAT_TRIM_1_976_V 0b00000100 // 2 0 1.976 V #define RADIOLIB_SX127X_LOW_BAT_TRIM_1_976_V 0b00000100 // 2 0 1.976 V
#define SX127X_LOW_BAT_TRIM_2_045_V 0b00000101 // 2 0 2.045 V #define RADIOLIB_SX127X_LOW_BAT_TRIM_2_045_V 0b00000101 // 2 0 2.045 V
#define SX127X_LOW_BAT_TRIM_2_116_V 0b00000110 // 2 0 2.116 V #define RADIOLIB_SX127X_LOW_BAT_TRIM_2_116_V 0b00000110 // 2 0 2.116 V
#define SX127X_LOW_BAT_TRIM_2_185_V 0b00000111 // 2 0 2.185 V #define RADIOLIB_SX127X_LOW_BAT_TRIM_2_185_V 0b00000111 // 2 0 2.185 V
// SX127X_REG_IRQ_FLAGS_1 // SX127X_REG_IRQ_FLAGS_1
#define SX127X_FLAG_MODE_READY 0b10000000 // 7 7 requested mode is ready #define RADIOLIB_SX127X_FLAG_MODE_READY 0b10000000 // 7 7 requested mode is ready
#define SX127X_FLAG_RX_READY 0b01000000 // 6 6 reception ready (after RSSI, AGC, AFC) #define RADIOLIB_SX127X_FLAG_RX_READY 0b01000000 // 6 6 reception ready (after RSSI, AGC, AFC)
#define SX127X_FLAG_TX_READY 0b00100000 // 5 5 transmission ready (after PA ramp-up) #define RADIOLIB_SX127X_FLAG_TX_READY 0b00100000 // 5 5 transmission ready (after PA ramp-up)
#define SX127X_FLAG_PLL_LOCK 0b00010000 // 4 4 PLL locked #define RADIOLIB_SX127X_FLAG_PLL_LOCK 0b00010000 // 4 4 PLL locked
#define SX127X_FLAG_RSSI 0b00001000 // 3 3 RSSI value exceeds RSSI threshold #define RADIOLIB_SX127X_FLAG_RSSI 0b00001000 // 3 3 RSSI value exceeds RSSI threshold
#define SX127X_FLAG_TIMEOUT 0b00000100 // 2 2 timeout occurred #define RADIOLIB_SX127X_FLAG_TIMEOUT 0b00000100 // 2 2 timeout occurred
#define SX127X_FLAG_PREAMBLE_DETECT 0b00000010 // 1 1 valid preamble was detected #define RADIOLIB_SX127X_FLAG_PREAMBLE_DETECT 0b00000010 // 1 1 valid preamble was detected
#define SX127X_FLAG_SYNC_ADDRESS_MATCH 0b00000001 // 0 0 sync address matched #define RADIOLIB_SX127X_FLAG_SYNC_ADDRESS_MATCH 0b00000001 // 0 0 sync address matched
// SX127X_REG_IRQ_FLAGS_2 // SX127X_REG_IRQ_FLAGS_2
#define SX127X_FLAG_FIFO_FULL 0b10000000 // 7 7 FIFO is full #define RADIOLIB_SX127X_FLAG_FIFO_FULL 0b10000000 // 7 7 FIFO is full
#define SX127X_FLAG_FIFO_EMPTY 0b01000000 // 6 6 FIFO is empty #define RADIOLIB_SX127X_FLAG_FIFO_EMPTY 0b01000000 // 6 6 FIFO is empty
#define SX127X_FLAG_FIFO_LEVEL 0b00100000 // 5 5 number of bytes in FIFO exceeds FIFO_THRESHOLD #define RADIOLIB_SX127X_FLAG_FIFO_LEVEL 0b00100000 // 5 5 number of bytes in FIFO exceeds FIFO_THRESHOLD
#define SX127X_FLAG_FIFO_OVERRUN 0b00010000 // 4 4 FIFO overrun occurred #define RADIOLIB_SX127X_FLAG_FIFO_OVERRUN 0b00010000 // 4 4 FIFO overrun occurred
#define SX127X_FLAG_PACKET_SENT 0b00001000 // 3 3 packet was successfully sent #define RADIOLIB_SX127X_FLAG_PACKET_SENT 0b00001000 // 3 3 packet was successfully sent
#define SX127X_FLAG_PAYLOAD_READY 0b00000100 // 2 2 packet was successfully received #define RADIOLIB_SX127X_FLAG_PAYLOAD_READY 0b00000100 // 2 2 packet was successfully received
#define SX127X_FLAG_CRC_OK 0b00000010 // 1 1 CRC check passed #define RADIOLIB_SX127X_FLAG_CRC_OK 0b00000010 // 1 1 CRC check passed
#define SX127X_FLAG_LOW_BAT 0b00000001 // 0 0 battery voltage dropped below threshold #define RADIOLIB_SX127X_FLAG_LOW_BAT 0b00000001 // 0 0 battery voltage dropped below threshold
// SX127X_REG_DIO_MAPPING_1 // SX127X_REG_DIO_MAPPING_1
#define SX127X_DIO0_CONT_SYNC_ADDRESS 0b00000000 // 7 6 #define RADIOLIB_SX127X_DIO0_CONT_SYNC_ADDRESS 0b00000000 // 7 6
#define SX127X_DIO0_CONT_TX_READY 0b00000000 // 7 6 #define RADIOLIB_SX127X_DIO0_CONT_TX_READY 0b00000000 // 7 6
#define SX127X_DIO0_CONT_RSSI_PREAMBLE_DETECTED 0b01000000 // 7 6 #define RADIOLIB_SX127X_DIO0_CONT_RSSI_RADIOLIB_PREAMBLE_DETECTED 0b01000000 // 7 6
#define SX127X_DIO0_CONT_RX_READY 0b10000000 // 7 6 #define RADIOLIB_SX127X_DIO0_CONT_RX_READY 0b10000000 // 7 6
#define SX127X_DIO0_PACK_PAYLOAD_READY 0b00000000 // 7 6 #define RADIOLIB_SX127X_DIO0_PACK_PAYLOAD_READY 0b00000000 // 7 6
#define SX127X_DIO0_PACK_PACKET_SENT 0b00000000 // 7 6 #define RADIOLIB_SX127X_DIO0_PACK_PACKET_SENT 0b00000000 // 7 6
#define SX127X_DIO0_PACK_CRC_OK 0b01000000 // 7 6 #define RADIOLIB_SX127X_DIO0_PACK_CRC_OK 0b01000000 // 7 6
#define SX127X_DIO0_PACK_TEMP_CHANGE_LOW_BAT 0b11000000 // 7 6 #define RADIOLIB_SX127X_DIO0_PACK_TEMP_CHANGE_LOW_BAT 0b11000000 // 7 6
#define SX127X_DIO1_CONT_DCLK 0b00000000 // 5 4 #define RADIOLIB_SX127X_DIO1_CONT_DCLK 0b00000000 // 5 4
#define SX127X_DIO1_CONT_RSSI_PREAMBLE_DETECTED 0b00010000 // 5 4 #define RADIOLIB_SX127X_DIO1_CONT_RSSI_RADIOLIB_PREAMBLE_DETECTED 0b00010000 // 5 4
#define SX127X_DIO1_PACK_FIFO_LEVEL 0b00000000 // 5 4 #define RADIOLIB_SX127X_DIO1_PACK_FIFO_LEVEL 0b00000000 // 5 4
#define SX127X_DIO1_PACK_FIFO_EMPTY 0b00010000 // 5 4 #define RADIOLIB_SX127X_DIO1_PACK_FIFO_EMPTY 0b00010000 // 5 4
#define SX127X_DIO1_PACK_FIFO_FULL 0b00100000 // 5 4 #define RADIOLIB_SX127X_DIO1_PACK_FIFO_FULL 0b00100000 // 5 4
#define SX127X_DIO2_CONT_DATA 0b00000000 // 3 2 #define RADIOLIB_SX127X_DIO2_CONT_DATA 0b00000000 // 3 2
// SX1272_REG_PLL_HOP + SX1278_REG_PLL_HOP // SX1272_REG_PLL_HOP + SX1278_REG_PLL_HOP
#define SX127X_FAST_HOP_OFF 0b00000000 // 7 7 carrier frequency validated when FRF registers are written #define RADIOLIB_SX127X_FAST_HOP_OFF 0b00000000 // 7 7 carrier frequency validated when FRF registers are written
#define SX127X_FAST_HOP_ON 0b10000000 // 7 7 carrier frequency validated when FS modes are requested #define RADIOLIB_SX127X_FAST_HOP_ON 0b10000000 // 7 7 carrier frequency validated when FS modes are requested
// SX1272_REG_TCXO + SX1278_REG_TCXO // SX1272_REG_TCXO + SX1278_REG_TCXO
#define SX127X_TCXO_INPUT_EXTERNAL 0b00000000 // 4 4 use external crystal oscillator #define RADIOLIB_SX127X_TCXO_INPUT_EXTERNAL 0b00000000 // 4 4 use external crystal oscillator
#define SX127X_TCXO_INPUT_EXTERNAL_CLIPPED 0b00010000 // 4 4 use external crystal oscillator clipped sine connected to XTA pin #define RADIOLIB_SX127X_TCXO_INPUT_EXTERNAL_CLIPPED 0b00010000 // 4 4 use external crystal oscillator clipped sine connected to XTA pin
// SX1272_REG_PLL + SX1278_REG_PLL // SX1272_REG_PLL + SX1278_REG_PLL
#define SX127X_PLL_BANDWIDTH_75_KHZ 0b00000000 // 7 6 PLL bandwidth: 75 kHz #define RADIOLIB_SX127X_PLL_BANDWIDTH_75_KHZ 0b00000000 // 7 6 PLL bandwidth: 75 kHz
#define SX127X_PLL_BANDWIDTH_150_KHZ 0b01000000 // 7 6 150 kHz #define RADIOLIB_SX127X_PLL_BANDWIDTH_150_KHZ 0b01000000 // 7 6 150 kHz
#define SX127X_PLL_BANDWIDTH_225_KHZ 0b10000000 // 7 6 225 kHz #define RADIOLIB_SX127X_PLL_BANDWIDTH_225_KHZ 0b10000000 // 7 6 225 kHz
#define SX127X_PLL_BANDWIDTH_300_KHZ 0b11000000 // 7 6 300 kHz (default) #define RADIOLIB_SX127X_PLL_BANDWIDTH_300_KHZ 0b11000000 // 7 6 300 kHz (default)
/*! /*!
\class SX127x \class SX127x
@ -561,6 +561,8 @@ class SX127x: public PhysicalLayer {
*/ */
SX127x(Module* mod); SX127x(Module* mod);
Module* getMod();
// basic methods // basic methods
/*! /*!
@ -721,7 +723,7 @@ class SX127x: public PhysicalLayer {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t startReceive(uint8_t len = 0, uint8_t mode = SX127X_RXCONTINUOUS); int16_t startReceive(uint8_t len = 0, uint8_t mode = RADIOLIB_SX127X_RXCONTINUOUS);
/*! /*!
\brief Reads data that was received after calling startReceive method. This method reads len characters. \brief Reads data that was received after calling startReceive method. This method reads len characters.
@ -943,7 +945,7 @@ class SX127x: public PhysicalLayer {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t fixedPacketLengthMode(uint8_t len = SX127X_MAX_PACKET_LENGTH_FSK); int16_t fixedPacketLengthMode(uint8_t len = RADIOLIB_SX127X_MAX_PACKET_LENGTH_FSK);
/*! /*!
\brief Set modem in variable packet length mode. Available in FSK mode only. \brief Set modem in variable packet length mode. Available in FSK mode only.
@ -952,7 +954,7 @@ class SX127x: public PhysicalLayer {
\returns \ref status_codes \returns \ref status_codes
*/ */
int16_t variablePacketLengthMode(uint8_t maxLen = SX127X_MAX_PACKET_LENGTH_FSK); int16_t variablePacketLengthMode(uint8_t maxLen = RADIOLIB_SX127X_MAX_PACKET_LENGTH_FSK);
/*! /*!
\brief Sets RSSI measurement configuration in FSK mode. \brief Sets RSSI measurement configuration in FSK mode.
@ -1077,7 +1079,7 @@ class SX127x: public PhysicalLayer {
#endif #endif
float _dataRate = 0; float _dataRate = 0;
bool _packetLengthQueried = false; // FSK packet length is the first byte in FIFO, length can only be queried once bool _packetLengthQueried = false; // FSK packet length is the first byte in FIFO, length can only be queried once
uint8_t _packetLengthConfig = SX127X_PACKET_VARIABLE; uint8_t _packetLengthConfig = RADIOLIB_SX127X_PACKET_VARIABLE;
bool findChip(uint8_t ver); bool findChip(uint8_t ver);
int16_t setMode(uint8_t mode); int16_t setMode(uint8_t mode);