[SX126x] Update to 5.0.0

This commit is contained in:
jgromes 2021-11-14 11:41:53 +01:00
parent bd5d824d73
commit 6f744a8f13
17 changed files with 734 additions and 732 deletions

View file

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

View file

@ -35,7 +35,7 @@ void setup() {
// initialize SX1262 with default settings
Serial.print(F("[SX1262] Initializing ... "));
int state = radio.begin();
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!"));
} else {
Serial.print(F("failed, code "));
@ -50,7 +50,7 @@ void setup() {
// start scanning the channel
Serial.print(F("[SX1262] Starting scan for LoRa preamble ... "));
state = radio.startChannelScan();
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!"));
} else {
Serial.print(F("failed, code "));
@ -91,11 +91,11 @@ void loop() {
// check CAD result
int state = radio.getChannelScanResult();
if (state == LORA_DETECTED) {
if (state == RADIOLIB_LORA_DETECTED) {
// LoRa packet was detected
Serial.println(F("[SX1262] Packet detected!"));
} else if (state == CHANNEL_FREE) {
} else if (state == RADIOLIB_CHANNEL_FREE) {
// channel is free
Serial.println(F("[SX1262] Channel is free!"));
@ -109,7 +109,7 @@ void loop() {
// start scanning the channel again
Serial.print(F("[SX1262] Starting scan for LoRa preamble ... "));
state = radio.startChannelScan();
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!"));
} else {
Serial.print(F("failed, code "));

View file

@ -36,7 +36,7 @@ void setup() {
// initialize SX1262 FSK modem with default settings
Serial.print(F("[SX1262] Initializing ... "));
int state = radio.beginFSK();
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!"));
} else {
Serial.print(F("failed, code "));
@ -61,7 +61,7 @@ void setup() {
uint8_t syncWord[] = {0x01, 0x23, 0x45, 0x67,
0x89, 0xAB, 0xCD, 0xEF};
state = radio.setSyncWord(syncWord, 8);
if (state != ERR_NONE) {
if (state != RADIOLIB_ERR_NONE) {
Serial.print(F("Unable to set configuration, code "));
Serial.println(state);
while (true);
@ -94,11 +94,11 @@ void loop() {
0x89, 0xAB, 0xCD, 0xEF};
int state = radio.transmit(byteArr, 8);
*/
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1262] Packet transmitted successfully!"));
} else if (state == ERR_PACKET_TOO_LONG) {
} else if (state == RADIOLIB_ERR_PACKET_TOO_LONG) {
Serial.println(F("[SX1262] Packet too long!"));
} else if (state == ERR_TX_TIMEOUT) {
} else if (state == RADIOLIB_ERR_TX_TIMEOUT) {
Serial.println(F("[SX1262] Timed out while transmitting!"));
} else {
Serial.println(F("[SX1262] Failed to transmit packet, code "));
@ -112,11 +112,11 @@ void loop() {
byte byteArr[8];
int state = radio.receive(byteArr, 8);
*/
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1262] Received packet!"));
Serial.print(F("[SX1262] Data:\t"));
Serial.println(str);
} else if (state == ERR_RX_TIMEOUT) {
} else if (state == RADIOLIB_ERR_RX_TIMEOUT) {
Serial.println(F("[SX1262] Timed out while waiting for packet!"));
} else {
Serial.println(F("[SX1262] Failed to receive packet, code "));
@ -137,7 +137,7 @@ void loop() {
state = radio.setNodeAddress(0x02);
// set broadcast address to 0xFF
state = radio.setBroadcastAddress(0xFF);
if (state != ERR_NONE) {
if (state != RADIOLIB_ERR_NONE) {
Serial.println(F("[SX1262] Unable to set address filter, code "));
Serial.println(state);
}
@ -147,7 +147,7 @@ void loop() {
// node and broadcast address
/*
state = radio.disableAddressFiltering();
if (state != ERR_NONE) {
if (state != RADIOLIB_ERR_NONE) {
Serial.println(F("Unable to remove address filter, code "));
}
*/

View file

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

View file

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

View file

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

View file

@ -51,7 +51,7 @@ void setup() {
// initialize SX1268 with default settings
Serial.print(F("[SX1262] Initializing ... "));
int state = radio1.begin();
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!"));
} else {
Serial.print(F("failed, code "));
@ -72,7 +72,7 @@ void setup() {
// output power: 2 dBm
// preamble length: 20 symbols
state = radio2.begin(915.0, 500.0, 6, 5, 0x34, 20);
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!"));
} else {
Serial.print(F("failed, code "));
@ -84,56 +84,56 @@ void setup() {
// and check if the configuration was changed successfully
// 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!"));
while (true);
}
// 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!"));
while (true);
}
// 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!"));
while (true);
}
// 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!"));
while (true);
}
// set LoRa sync word to 0xAB
if (radio1.setSyncWord(0xAB) != ERR_NONE) {
if (radio1.setSyncWord(0xAB) != RADIOLIB_ERR_NONE) {
Serial.println(F("Unable to set sync word!"));
while (true);
}
// set output power to 10 dBm (accepted range is -17 - 22 dBm)
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!"));
while (true);
}
// set over current protection limit to 80 mA (accepted range is 45 - 240 mA)
// 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!"));
while (true);
}
// set LoRa preamble length to 15 symbols (accepted range is 0 - 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!"));
while (true);
}
// disable CRC
if (radio1.setCRC(false) == ERR_INVALID_CRC_CONFIGURATION) {
if (radio1.setCRC(false) == RADIOLIB_ERR_INVALID_CRC_CONFIGURATION) {
Serial.println(F("Selected CRC is invalid for this module!"));
while (true);
}
@ -141,7 +141,7 @@ void setup() {
// Some SX126x modules have TCXO (temperature compensated crystal
// oscillator). To configure TCXO reference voltage,
// the following method can be used.
if (radio1.setTCXO(2.4) == ERR_INVALID_TCXO_VOLTAGE) {
if (radio1.setTCXO(2.4) == RADIOLIB_ERR_INVALID_TCXO_VOLTAGE) {
Serial.println(F("Selected TCXO voltage is invalid for this module!"));
while (true);
}
@ -150,7 +150,7 @@ void setup() {
// this feature, the following method can be used.
// NOTE: As long as DIO2 is configured to control RF switch,
// it can't be used as interrupt pin!
if (radio1.setDio2AsRfSwitch() != ERR_NONE) {
if (radio1.setDio2AsRfSwitch() != RADIOLIB_ERR_NONE) {
Serial.println(F("Failed to set DIO2 as RF switch!"));
while (true);
}

View file

@ -36,7 +36,7 @@ void setup() {
// initialize SX1262 with default settings
Serial.print(F("[SX1262] Initializing ... "));
int state = radio.begin();
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
Serial.println(F("success!"));
} else {
Serial.print(F("failed, code "));
@ -71,7 +71,7 @@ void loop() {
int state = radio.transmit(byteArr, 8);
*/
if (state == ERR_NONE) {
if (state == RADIOLIB_ERR_NONE) {
// the packet was successfully transmitted
Serial.println(F("success!"));
@ -80,11 +80,11 @@ void loop() {
Serial.print(radio.getDataRate());
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
Serial.println(F("too long!"));
} else if (state == ERR_TX_TIMEOUT) {
} else if (state == RADIOLIB_ERR_TX_TIMEOUT) {
// timeout occured while transmitting packet
Serial.println(F("timeout!"));

View file

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

View file

@ -6,15 +6,15 @@ SX1261::SX1261(Module* mod): SX1262(mod) {
}
int16_t SX1261::setOutputPower(int8_t power) {
RADIOLIB_CHECK_RANGE(power, -17, 14, ERR_INVALID_OUTPUT_POWER);
RADIOLIB_CHECK_RANGE(power, -17, 14, RADIOLIB_ERR_INVALID_OUTPUT_POWER);
// get current OCP configuration
uint8_t ocp = 0;
int16_t state = readRegister(SX126X_REG_OCP_CONFIGURATION, &ocp, 1);
int16_t state = readRegister(RADIOLIB_SX126X_REG_OCP_CONFIGURATION, &ocp, 1);
RADIOLIB_ASSERT(state);
// set PA config
state = SX126x::setPaConfig(0x04, SX126X_PA_CONFIG_SX1261, 0x00);
state = SX126x::setPaConfig(0x04, RADIOLIB_SX126X_PA_CONFIG_SX1261, 0x00);
RADIOLIB_ASSERT(state);
// set output power
@ -23,7 +23,7 @@ int16_t SX1261::setOutputPower(int8_t power) {
RADIOLIB_ASSERT(state);
// restore OCP configuration
return(writeRegister(SX126X_REG_OCP_CONFIGURATION, &ocp, 1));
return(writeRegister(RADIOLIB_SX126X_REG_OCP_CONFIGURATION, &ocp, 1));
}
#endif

View file

@ -9,8 +9,8 @@
#include "SX126x.h"
#include "SX1262.h"
//SX126X_CMD_SET_PA_CONFIG
#define SX126X_PA_CONFIG_SX1261 0x01
//RADIOLIB_SX126X_CMD_SET_PA_CONFIG
#define RADIOLIB_SX126X_PA_CONFIG_SX1261 0x01
/*!
\class SX1261

View file

@ -42,26 +42,26 @@ int16_t SX1262::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t
}
int16_t SX1262::setFrequency(float freq, bool calibrate) {
RADIOLIB_CHECK_RANGE(freq, 150.0, 960.0, ERR_INVALID_FREQUENCY);
RADIOLIB_CHECK_RANGE(freq, 150.0, 960.0, RADIOLIB_ERR_INVALID_FREQUENCY);
// calibrate image
if(calibrate) {
uint8_t data[2];
if(freq > 900.0) {
data[0] = SX126X_CAL_IMG_902_MHZ_1;
data[1] = SX126X_CAL_IMG_902_MHZ_2;
data[0] = RADIOLIB_SX126X_CAL_IMG_902_MHZ_1;
data[1] = RADIOLIB_SX126X_CAL_IMG_902_MHZ_2;
} else if(freq > 850.0) {
data[0] = SX126X_CAL_IMG_863_MHZ_1;
data[1] = SX126X_CAL_IMG_863_MHZ_2;
data[0] = RADIOLIB_SX126X_CAL_IMG_863_MHZ_1;
data[1] = RADIOLIB_SX126X_CAL_IMG_863_MHZ_2;
} else if(freq > 770.0) {
data[0] = SX126X_CAL_IMG_779_MHZ_1;
data[1] = SX126X_CAL_IMG_779_MHZ_2;
data[0] = RADIOLIB_SX126X_CAL_IMG_779_MHZ_1;
data[1] = RADIOLIB_SX126X_CAL_IMG_779_MHZ_2;
} else if(freq > 460.0) {
data[0] = SX126X_CAL_IMG_470_MHZ_1;
data[1] = SX126X_CAL_IMG_470_MHZ_2;
data[0] = RADIOLIB_SX126X_CAL_IMG_470_MHZ_1;
data[1] = RADIOLIB_SX126X_CAL_IMG_470_MHZ_2;
} else {
data[0] = SX126X_CAL_IMG_430_MHZ_1;
data[1] = SX126X_CAL_IMG_430_MHZ_2;
data[0] = RADIOLIB_SX126X_CAL_IMG_430_MHZ_1;
data[1] = RADIOLIB_SX126X_CAL_IMG_430_MHZ_2;
}
int16_t state = SX126x::calibrateImage(data);
RADIOLIB_ASSERT(state);
@ -72,15 +72,15 @@ int16_t SX1262::setFrequency(float freq, bool calibrate) {
}
int16_t SX1262::setOutputPower(int8_t power) {
RADIOLIB_CHECK_RANGE(power, -17, 22, ERR_INVALID_OUTPUT_POWER);
RADIOLIB_CHECK_RANGE(power, -17, 22, RADIOLIB_ERR_INVALID_OUTPUT_POWER);
// get current OCP configuration
uint8_t ocp = 0;
int16_t state = readRegister(SX126X_REG_OCP_CONFIGURATION, &ocp, 1);
int16_t state = readRegister(RADIOLIB_SX126X_REG_OCP_CONFIGURATION, &ocp, 1);
RADIOLIB_ASSERT(state);
// set PA config
state = SX126x::setPaConfig(0x04, SX126X_PA_CONFIG_SX1262);
state = SX126x::setPaConfig(0x04, RADIOLIB_SX126X_PA_CONFIG_SX1262);
RADIOLIB_ASSERT(state);
// set output power
@ -89,7 +89,7 @@ int16_t SX1262::setOutputPower(int8_t power) {
RADIOLIB_ASSERT(state);
// restore OCP configuration
return(writeRegister(SX126X_REG_OCP_CONFIGURATION, &ocp, 1));
return(writeRegister(RADIOLIB_SX126X_REG_OCP_CONFIGURATION, &ocp, 1));
}
#endif

View file

@ -8,8 +8,8 @@
#include "../../Module.h"
#include "SX126x.h"
//SX126X_CMD_SET_PA_CONFIG
#define SX126X_PA_CONFIG_SX1262 0x00
//RADIOLIB_SX126X_CMD_SET_PA_CONFIG
#define RADIOLIB_SX126X_PA_CONFIG_SX1262 0x00
/*!
\class SX1262
@ -38,7 +38,7 @@ class SX1262: public SX126x {
\param cr LoRa coding rate denominator. Defaults to 7 (coding rate 4/7).
\param syncWord 2-byte LoRa sync word. Defaults to SX126X_SYNC_WORD_PRIVATE (0x12).
\param syncWord 2-byte LoRa sync word. Defaults to RADIOLIB_SX126X_SYNC_WORD_PRIVATE (0x12).
\param power Output power in dBm. Defaults to 10 dBm.
@ -48,7 +48,7 @@ class SX1262: public SX126x {
\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 = SX126X_SYNC_WORD_PRIVATE, int8_t power = 10, uint16_t preambleLength = 8, float tcxoVoltage = 1.6, bool useRegulatorLDO = false);
int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX126X_SYNC_WORD_PRIVATE, int8_t power = 10, uint16_t preambleLength = 8, float tcxoVoltage = 1.6, bool useRegulatorLDO = false);
/*!
\brief Initialization method for FSK modem.

View file

@ -43,20 +43,20 @@ int16_t SX1268::beginFSK(float freq, float br, float freqDev, float rxBw, int8_t
/// \todo integers only (all modules - frequency, data rate, bandwidth etc.)
int16_t SX1268::setFrequency(float freq, bool calibrate) {
RADIOLIB_CHECK_RANGE(freq, 410.0, 810.0, ERR_INVALID_FREQUENCY);
RADIOLIB_CHECK_RANGE(freq, 410.0, 810.0, RADIOLIB_ERR_INVALID_FREQUENCY);
// calibrate image
if(calibrate) {
uint8_t data[2];
if(freq > 770.0) {
data[0] = SX126X_CAL_IMG_779_MHZ_1;
data[1] = SX126X_CAL_IMG_779_MHZ_2;
data[0] = RADIOLIB_SX126X_CAL_IMG_779_MHZ_1;
data[1] = RADIOLIB_SX126X_CAL_IMG_779_MHZ_2;
} else if(freq > 460.0) {
data[0] = SX126X_CAL_IMG_470_MHZ_1;
data[1] = SX126X_CAL_IMG_470_MHZ_2;
data[0] = RADIOLIB_SX126X_CAL_IMG_470_MHZ_1;
data[1] = RADIOLIB_SX126X_CAL_IMG_470_MHZ_2;
} else {
data[0] = SX126X_CAL_IMG_430_MHZ_1;
data[1] = SX126X_CAL_IMG_430_MHZ_2;
data[0] = RADIOLIB_SX126X_CAL_IMG_430_MHZ_1;
data[1] = RADIOLIB_SX126X_CAL_IMG_430_MHZ_2;
}
int16_t state = SX126x::calibrateImage(data);
RADIOLIB_ASSERT(state);
@ -67,15 +67,15 @@ int16_t SX1268::setFrequency(float freq, bool calibrate) {
}
int16_t SX1268::setOutputPower(int8_t power) {
RADIOLIB_CHECK_RANGE(power, -9, 22, ERR_INVALID_OUTPUT_POWER);
RADIOLIB_CHECK_RANGE(power, -9, 22, RADIOLIB_ERR_INVALID_OUTPUT_POWER);
// get current OCP configuration
uint8_t ocp = 0;
int16_t state = readRegister(SX126X_REG_OCP_CONFIGURATION, &ocp, 1);
int16_t state = readRegister(RADIOLIB_SX126X_REG_OCP_CONFIGURATION, &ocp, 1);
RADIOLIB_ASSERT(state);
// set PA config
state = SX126x::setPaConfig(0x04, SX126X_PA_CONFIG_SX1268);
state = SX126x::setPaConfig(0x04, RADIOLIB_SX126X_PA_CONFIG_SX1268);
RADIOLIB_ASSERT(state);
// set output power
@ -84,7 +84,7 @@ int16_t SX1268::setOutputPower(int8_t power) {
RADIOLIB_ASSERT(state);
// restore OCP configuration
return(writeRegister(SX126X_REG_OCP_CONFIGURATION, &ocp, 1));
return(writeRegister(RADIOLIB_SX126X_REG_OCP_CONFIGURATION, &ocp, 1));
}
#endif

View file

@ -8,8 +8,8 @@
#include "../../Module.h"
#include "SX126x.h"
//SX126X_CMD_SET_PA_CONFIG
#define SX126X_PA_CONFIG_SX1268 0x00
//RADIOLIB_SX126X_CMD_SET_PA_CONFIG
#define RADIOLIB_SX126X_PA_CONFIG_SX1268 0x00
/*!
\class SX1268
@ -38,7 +38,7 @@ class SX1268: public SX126x {
\param cr LoRa coding rate denominator. Defaults to 7 (coding rate 4/7).
\param syncWord 2-byte LoRa sync word. Defaults to SX126X_SYNC_WORD_PRIVATE (0x12).
\param syncWord 2-byte LoRa sync word. Defaults to RADIOLIB_SX126X_SYNC_WORD_PRIVATE (0x12).
\param power Output power in dBm. Defaults to 10 dBm.
@ -48,7 +48,7 @@ class SX1268: public SX126x {
\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 = SX126X_SYNC_WORD_PRIVATE, int8_t power = 10, uint16_t preambleLength = 8, float tcxoVoltage = 1.6, bool useRegulatorLDO = false);
int16_t begin(float freq = 434.0, float bw = 125.0, uint8_t sf = 9, uint8_t cr = 7, uint8_t syncWord = RADIOLIB_SX126X_SYNC_WORD_PRIVATE, int8_t power = 10, uint16_t preambleLength = 8, float tcxoVoltage = 1.6, bool useRegulatorLDO = false);
/*!
\brief Initialization method for FSK modem.

File diff suppressed because it is too large Load diff

View file

@ -10,327 +10,327 @@
#include "../../protocols/PhysicalLayer/PhysicalLayer.h"
// SX126X physical layer properties
#define SX126X_FREQUENCY_STEP_SIZE 0.9536743164
#define SX126X_MAX_PACKET_LENGTH 255
#define SX126X_CRYSTAL_FREQ 32.0
#define SX126X_DIV_EXPONENT 25
#define RADIOLIB_SX126X_FREQUENCY_STEP_SIZE 0.9536743164
#define RADIOLIB_SX126X_MAX_PACKET_LENGTH 255
#define RADIOLIB_SX126X_CRYSTAL_FREQ 32.0
#define RADIOLIB_SX126X_DIV_EXPONENT 25
// SX126X SPI commands
// operational modes commands
#define SX126X_CMD_NOP 0x00
#define SX126X_CMD_SET_SLEEP 0x84
#define SX126X_CMD_SET_STANDBY 0x80
#define SX126X_CMD_SET_FS 0xC1
#define SX126X_CMD_SET_TX 0x83
#define SX126X_CMD_SET_RX 0x82
#define SX126X_CMD_STOP_TIMER_ON_PREAMBLE 0x9F
#define SX126X_CMD_SET_RX_DUTY_CYCLE 0x94
#define SX126X_CMD_SET_CAD 0xC5
#define SX126X_CMD_SET_TX_CONTINUOUS_WAVE 0xD1
#define SX126X_CMD_SET_TX_INFINITE_PREAMBLE 0xD2
#define SX126X_CMD_SET_REGULATOR_MODE 0x96
#define SX126X_CMD_CALIBRATE 0x89
#define SX126X_CMD_CALIBRATE_IMAGE 0x98
#define SX126X_CMD_SET_PA_CONFIG 0x95
#define SX126X_CMD_SET_RX_TX_FALLBACK_MODE 0x93
#define RADIOLIB_SX126X_CMD_NOP 0x00
#define RADIOLIB_SX126X_CMD_SET_SLEEP 0x84
#define RADIOLIB_SX126X_CMD_SET_STANDBY 0x80
#define RADIOLIB_SX126X_CMD_SET_FS 0xC1
#define RADIOLIB_SX126X_CMD_SET_TX 0x83
#define RADIOLIB_SX126X_CMD_SET_RX 0x82
#define RADIOLIB_SX126X_CMD_STOP_TIMER_ON_PREAMBLE 0x9F
#define RADIOLIB_SX126X_CMD_SET_RX_DUTY_CYCLE 0x94
#define RADIOLIB_SX126X_CMD_SET_CAD 0xC5
#define RADIOLIB_SX126X_CMD_SET_TX_CONTINUOUS_WAVE 0xD1
#define RADIOLIB_SX126X_CMD_SET_TX_INFINITE_PREAMBLE 0xD2
#define RADIOLIB_SX126X_CMD_SET_REGULATOR_MODE 0x96
#define RADIOLIB_SX126X_CMD_CALIBRATE 0x89
#define RADIOLIB_SX126X_CMD_CALIBRATE_IMAGE 0x98
#define RADIOLIB_SX126X_CMD_SET_PA_CONFIG 0x95
#define RADIOLIB_SX126X_CMD_SET_RX_TX_FALLBACK_MODE 0x93
// register and buffer access commands
#define SX126X_CMD_WRITE_REGISTER 0x0D
#define SX126X_CMD_READ_REGISTER 0x1D
#define SX126X_CMD_WRITE_BUFFER 0x0E
#define SX126X_CMD_READ_BUFFER 0x1E
#define RADIOLIB_SX126X_CMD_WRITE_REGISTER 0x0D
#define RADIOLIB_SX126X_CMD_READ_REGISTER 0x1D
#define RADIOLIB_SX126X_CMD_WRITE_BUFFER 0x0E
#define RADIOLIB_SX126X_CMD_READ_BUFFER 0x1E
// DIO and IRQ control
#define SX126X_CMD_SET_DIO_IRQ_PARAMS 0x08
#define SX126X_CMD_GET_IRQ_STATUS 0x12
#define SX126X_CMD_CLEAR_IRQ_STATUS 0x02
#define SX126X_CMD_SET_DIO2_AS_RF_SWITCH_CTRL 0x9D
#define SX126X_CMD_SET_DIO3_AS_TCXO_CTRL 0x97
#define RADIOLIB_SX126X_CMD_SET_DIO_IRQ_PARAMS 0x08
#define RADIOLIB_SX126X_CMD_GET_IRQ_STATUS 0x12
#define RADIOLIB_SX126X_CMD_CLEAR_IRQ_STATUS 0x02
#define RADIOLIB_SX126X_CMD_SET_DIO2_AS_RF_SWITCH_CTRL 0x9D
#define RADIOLIB_SX126X_CMD_SET_DIO3_AS_TCXO_CTRL 0x97
// RF, modulation and packet commands
#define SX126X_CMD_SET_RF_FREQUENCY 0x86
#define SX126X_CMD_SET_PACKET_TYPE 0x8A
#define SX126X_CMD_GET_PACKET_TYPE 0x11
#define SX126X_CMD_SET_TX_PARAMS 0x8E
#define SX126X_CMD_SET_MODULATION_PARAMS 0x8B
#define SX126X_CMD_SET_PACKET_PARAMS 0x8C
#define SX126X_CMD_SET_CAD_PARAMS 0x88
#define SX126X_CMD_SET_BUFFER_BASE_ADDRESS 0x8F
#define SX126X_CMD_SET_LORA_SYMB_NUM_TIMEOUT 0x0A
#define RADIOLIB_SX126X_CMD_SET_RF_FREQUENCY 0x86
#define RADIOLIB_SX126X_CMD_SET_PACKET_TYPE 0x8A
#define RADIOLIB_SX126X_CMD_GET_PACKET_TYPE 0x11
#define RADIOLIB_SX126X_CMD_SET_TX_PARAMS 0x8E
#define RADIOLIB_SX126X_CMD_SET_MODULATION_PARAMS 0x8B
#define RADIOLIB_SX126X_CMD_SET_PACKET_PARAMS 0x8C
#define RADIOLIB_SX126X_CMD_SET_CAD_PARAMS 0x88
#define RADIOLIB_SX126X_CMD_SET_BUFFER_BASE_ADDRESS 0x8F
#define RADIOLIB_SX126X_CMD_SET_LORA_SYMB_NUM_TIMEOUT 0x0A
// status commands
#define SX126X_CMD_GET_STATUS 0xC0
#define SX126X_CMD_GET_RSSI_INST 0x15
#define SX126X_CMD_GET_RX_BUFFER_STATUS 0x13
#define SX126X_CMD_GET_PACKET_STATUS 0x14
#define SX126X_CMD_GET_DEVICE_ERRORS 0x17
#define SX126X_CMD_CLEAR_DEVICE_ERRORS 0x07
#define SX126X_CMD_GET_STATS 0x10
#define SX126X_CMD_RESET_STATS 0x00
#define RADIOLIB_SX126X_CMD_GET_STATUS 0xC0
#define RADIOLIB_SX126X_CMD_GET_RSSI_INST 0x15
#define RADIOLIB_SX126X_CMD_GET_RX_BUFFER_STATUS 0x13
#define RADIOLIB_SX126X_CMD_GET_PACKET_STATUS 0x14
#define RADIOLIB_SX126X_CMD_GET_DEVICE_ERRORS 0x17
#define RADIOLIB_SX126X_CMD_CLEAR_DEVICE_ERRORS 0x07
#define RADIOLIB_SX126X_CMD_GET_STATS 0x10
#define RADIOLIB_SX126X_CMD_RESET_STATS 0x00
// SX126X register map
#define SX126X_REG_WHITENING_INITIAL_MSB 0x06B8
#define SX126X_REG_WHITENING_INITIAL_LSB 0x06B9
#define SX126X_REG_CRC_INITIAL_MSB 0x06BC
#define SX126X_REG_CRC_INITIAL_LSB 0x06BD
#define SX126X_REG_CRC_POLYNOMIAL_MSB 0x06BE
#define SX126X_REG_CRC_POLYNOMIAL_LSB 0x06BF
#define SX126X_REG_SYNC_WORD_0 0x06C0
#define SX126X_REG_SYNC_WORD_1 0x06C1
#define SX126X_REG_SYNC_WORD_2 0x06C2
#define SX126X_REG_SYNC_WORD_3 0x06C3
#define SX126X_REG_SYNC_WORD_4 0x06C4
#define SX126X_REG_SYNC_WORD_5 0x06C5
#define SX126X_REG_SYNC_WORD_6 0x06C6
#define SX126X_REG_SYNC_WORD_7 0x06C7
#define SX126X_REG_NODE_ADDRESS 0x06CD
#define SX126X_REG_BROADCAST_ADDRESS 0x06CE
#define SX126X_REG_LORA_SYNC_WORD_MSB 0x0740
#define SX126X_REG_LORA_SYNC_WORD_LSB 0x0741
#define SX126X_REG_RANDOM_NUMBER_0 0x0819
#define SX126X_REG_RANDOM_NUMBER_1 0x081A
#define SX126X_REG_RANDOM_NUMBER_2 0x081B
#define SX126X_REG_RANDOM_NUMBER_3 0x081C
#define SX126X_REG_RX_GAIN 0x08AC
#define SX126X_REG_OCP_CONFIGURATION 0x08E7
#define SX126X_REG_XTA_TRIM 0x0911
#define SX126X_REG_XTB_TRIM 0x0912
#define RADIOLIB_SX126X_REG_WHITENING_INITIAL_MSB 0x06B8
#define RADIOLIB_SX126X_REG_WHITENING_INITIAL_LSB 0x06B9
#define RADIOLIB_SX126X_REG_CRC_INITIAL_MSB 0x06BC
#define RADIOLIB_SX126X_REG_CRC_INITIAL_LSB 0x06BD
#define RADIOLIB_SX126X_REG_CRC_POLYNOMIAL_MSB 0x06BE
#define RADIOLIB_SX126X_REG_CRC_POLYNOMIAL_LSB 0x06BF
#define RADIOLIB_SX126X_REG_SYNC_WORD_0 0x06C0
#define RADIOLIB_SX126X_REG_SYNC_WORD_1 0x06C1
#define RADIOLIB_SX126X_REG_SYNC_WORD_2 0x06C2
#define RADIOLIB_SX126X_REG_SYNC_WORD_3 0x06C3
#define RADIOLIB_SX126X_REG_SYNC_WORD_4 0x06C4
#define RADIOLIB_SX126X_REG_SYNC_WORD_5 0x06C5
#define RADIOLIB_SX126X_REG_SYNC_WORD_6 0x06C6
#define RADIOLIB_SX126X_REG_SYNC_WORD_7 0x06C7
#define RADIOLIB_SX126X_REG_NODE_ADDRESS 0x06CD
#define RADIOLIB_SX126X_REG_BROADCAST_ADDRESS 0x06CE
#define RADIOLIB_SX126X_REG_LORA_SYNC_WORD_MSB 0x0740
#define RADIOLIB_SX126X_REG_LORA_SYNC_WORD_LSB 0x0741
#define RADIOLIB_SX126X_REG_RANDOM_NUMBER_0 0x0819
#define RADIOLIB_SX126X_REG_RANDOM_NUMBER_1 0x081A
#define RADIOLIB_SX126X_REG_RANDOM_NUMBER_2 0x081B
#define RADIOLIB_SX126X_REG_RANDOM_NUMBER_3 0x081C
#define RADIOLIB_SX126X_REG_RX_GAIN 0x08AC
#define RADIOLIB_SX126X_REG_OCP_CONFIGURATION 0x08E7
#define RADIOLIB_SX126X_REG_XTA_TRIM 0x0911
#define RADIOLIB_SX126X_REG_XTB_TRIM 0x0912
// undocumented registers
#define SX126X_REG_SENSITIVITY_CONFIG 0x0889 // SX1268 datasheet v1.1, section 15.1
#define SX126X_REG_TX_CLAMP_CONFIG 0x08D8 // SX1268 datasheet v1.1, section 15.2
#define SX126X_REG_RTC_STOP 0x0920 // SX1268 datasheet v1.1, section 15.3
#define SX126X_REG_RTC_EVENT 0x0944 // SX1268 datasheet v1.1, section 15.3
#define SX126X_REG_IQ_CONFIG 0x0736 // SX1268 datasheet v1.1, section 15.4
#define SX126X_REG_RX_GAIN_RETENTION_0 0x029F // SX1268 datasheet v1.1, section 9.6
#define SX126X_REG_RX_GAIN_RETENTION_1 0x02A0 // SX1268 datasheet v1.1, section 9.6
#define SX126X_REG_RX_GAIN_RETENTION_2 0x02A1 // SX1268 datasheet v1.1, section 9.6
#define RADIOLIB_SX126X_REG_SENSITIVITY_CONFIG 0x0889 // SX1268 datasheet v1.1, section 15.1
#define RADIOLIB_SX126X_REG_TX_CLAMP_CONFIG 0x08D8 // SX1268 datasheet v1.1, section 15.2
#define RADIOLIB_SX126X_REG_RTC_STOP 0x0920 // SX1268 datasheet v1.1, section 15.3
#define RADIOLIB_SX126X_REG_RTC_EVENT 0x0944 // SX1268 datasheet v1.1, section 15.3
#define RADIOLIB_SX126X_REG_IQ_CONFIG 0x0736 // SX1268 datasheet v1.1, section 15.4
#define RADIOLIB_SX126X_REG_RX_GAIN_RETENTION_0 0x029F // SX1268 datasheet v1.1, section 9.6
#define RADIOLIB_SX126X_REG_RX_GAIN_RETENTION_1 0x02A0 // SX1268 datasheet v1.1, section 9.6
#define RADIOLIB_SX126X_REG_RX_GAIN_RETENTION_2 0x02A1 // SX1268 datasheet v1.1, section 9.6
// SX126X SPI command variables
//SX126X_CMD_SET_SLEEP MSB LSB DESCRIPTION
#define SX126X_SLEEP_START_COLD 0b00000000 // 2 2 sleep mode: cold start, configuration is lost (default)
#define SX126X_SLEEP_START_WARM 0b00000100 // 2 2 warm start, configuration is retained
#define SX126X_SLEEP_RTC_OFF 0b00000000 // 0 0 wake on RTC timeout: disabled
#define SX126X_SLEEP_RTC_ON 0b00000001 // 0 0 enabled
//RADIOLIB_SX126X_CMD_SET_SLEEP MSB LSB DESCRIPTION
#define RADIOLIB_SX126X_SLEEP_START_COLD 0b00000000 // 2 2 sleep mode: cold start, configuration is lost (default)
#define RADIOLIB_SX126X_SLEEP_START_WARM 0b00000100 // 2 2 warm start, configuration is retained
#define RADIOLIB_SX126X_SLEEP_RTC_OFF 0b00000000 // 0 0 wake on RTC timeout: disabled
#define RADIOLIB_SX126X_SLEEP_RTC_ON 0b00000001 // 0 0 enabled
//SX126X_CMD_SET_STANDBY
#define SX126X_STANDBY_RC 0x00 // 7 0 standby mode: 13 MHz RC oscillator
#define SX126X_STANDBY_XOSC 0x01 // 7 0 32 MHz crystal oscillator
//RADIOLIB_SX126X_CMD_SET_STANDBY
#define RADIOLIB_SX126X_STANDBY_RC 0x00 // 7 0 standby mode: 13 MHz RC oscillator
#define RADIOLIB_SX126X_STANDBY_XOSC 0x01 // 7 0 32 MHz crystal oscillator
//SX126X_CMD_SET_RX
#define SX126X_RX_TIMEOUT_NONE 0x000000 // 23 0 Rx timeout duration: no timeout (Rx single mode)
#define SX126X_RX_TIMEOUT_INF 0xFFFFFF // 23 0 infinite (Rx continuous mode)
//RADIOLIB_SX126X_CMD_SET_RX
#define RADIOLIB_SX126X_RX_TIMEOUT_NONE 0x000000 // 23 0 Rx timeout duration: no timeout (Rx single mode)
#define RADIOLIB_SX126X_RX_TIMEOUT_INF 0xFFFFFF // 23 0 infinite (Rx continuous mode)
//SX126X_CMD_SET_TX
#define SX126X_TX_TIMEOUT_NONE 0x000000 // 23 0 Tx timeout duration: no timeout (Tx single mode)
//RADIOLIB_SX126X_CMD_SET_TX
#define RADIOLIB_SX126X_TX_TIMEOUT_NONE 0x000000 // 23 0 Tx timeout duration: no timeout (Tx single mode)
//SX126X_CMD_STOP_TIMER_ON_PREAMBLE
#define SX126X_STOP_ON_PREAMBLE_OFF 0x00 // 7 0 stop timer on: sync word or header (default)
#define SX126X_STOP_ON_PREAMBLE_ON 0x01 // 7 0 preamble detection
//RADIOLIB_SX126X_CMD_STOP_TIMER_ON_PREAMBLE
#define RADIOLIB_SX126X_STOP_ON_PREAMBLE_OFF 0x00 // 7 0 stop timer on: sync word or header (default)
#define RADIOLIB_SX126X_STOP_ON_PREAMBLE_ON 0x01 // 7 0 preamble detection
//SX126X_CMD_SET_REGULATOR_MODE
#define SX126X_REGULATOR_LDO 0x00 // 7 0 set regulator mode: LDO (default)
#define SX126X_REGULATOR_DC_DC 0x01 // 7 0 DC-DC
//RADIOLIB_SX126X_CMD_SET_REGULATOR_MODE
#define RADIOLIB_SX126X_REGULATOR_LDO 0x00 // 7 0 set regulator mode: LDO (default)
#define RADIOLIB_SX126X_REGULATOR_DC_DC 0x01 // 7 0 DC-DC
//SX126X_CMD_CALIBRATE
#define SX126X_CALIBRATE_IMAGE_OFF 0b00000000 // 6 6 image calibration: disabled
#define SX126X_CALIBRATE_IMAGE_ON 0b01000000 // 6 6 enabled
#define SX126X_CALIBRATE_ADC_BULK_P_OFF 0b00000000 // 5 5 ADC bulk P calibration: disabled
#define SX126X_CALIBRATE_ADC_BULK_P_ON 0b00100000 // 5 5 enabled
#define SX126X_CALIBRATE_ADC_BULK_N_OFF 0b00000000 // 4 4 ADC bulk N calibration: disabled
#define SX126X_CALIBRATE_ADC_BULK_N_ON 0b00010000 // 4 4 enabled
#define SX126X_CALIBRATE_ADC_PULSE_OFF 0b00000000 // 3 3 ADC pulse calibration: disabled
#define SX126X_CALIBRATE_ADC_PULSE_ON 0b00001000 // 3 3 enabled
#define SX126X_CALIBRATE_PLL_OFF 0b00000000 // 2 2 PLL calibration: disabled
#define SX126X_CALIBRATE_PLL_ON 0b00000100 // 2 2 enabled
#define SX126X_CALIBRATE_RC13M_OFF 0b00000000 // 1 1 13 MHz RC osc. calibration: disabled
#define SX126X_CALIBRATE_RC13M_ON 0b00000010 // 1 1 enabled
#define SX126X_CALIBRATE_RC64K_OFF 0b00000000 // 0 0 64 kHz RC osc. calibration: disabled
#define SX126X_CALIBRATE_RC64K_ON 0b00000001 // 0 0 enabled
#define SX126X_CALIBRATE_ALL 0b01111111 // 6 0 calibrate all blocks
//RADIOLIB_SX126X_CMD_CALIBRATE
#define RADIOLIB_SX126X_CALIBRATE_IMAGE_OFF 0b00000000 // 6 6 image calibration: disabled
#define RADIOLIB_SX126X_CALIBRATE_IMAGE_ON 0b01000000 // 6 6 enabled
#define RADIOLIB_SX126X_CALIBRATE_ADC_BULK_P_OFF 0b00000000 // 5 5 ADC bulk P calibration: disabled
#define RADIOLIB_SX126X_CALIBRATE_ADC_BULK_P_ON 0b00100000 // 5 5 enabled
#define RADIOLIB_SX126X_CALIBRATE_ADC_BULK_N_OFF 0b00000000 // 4 4 ADC bulk N calibration: disabled
#define RADIOLIB_SX126X_CALIBRATE_ADC_BULK_N_ON 0b00010000 // 4 4 enabled
#define RADIOLIB_SX126X_CALIBRATE_ADC_PULSE_OFF 0b00000000 // 3 3 ADC pulse calibration: disabled
#define RADIOLIB_SX126X_CALIBRATE_ADC_PULSE_ON 0b00001000 // 3 3 enabled
#define RADIOLIB_SX126X_CALIBRATE_PLL_OFF 0b00000000 // 2 2 PLL calibration: disabled
#define RADIOLIB_SX126X_CALIBRATE_PLL_ON 0b00000100 // 2 2 enabled
#define RADIOLIB_SX126X_CALIBRATE_RC13M_OFF 0b00000000 // 1 1 13 MHz RC osc. calibration: disabled
#define RADIOLIB_SX126X_CALIBRATE_RC13M_ON 0b00000010 // 1 1 enabled
#define RADIOLIB_SX126X_CALIBRATE_RC64K_OFF 0b00000000 // 0 0 64 kHz RC osc. calibration: disabled
#define RADIOLIB_SX126X_CALIBRATE_RC64K_ON 0b00000001 // 0 0 enabled
#define RADIOLIB_SX126X_CALIBRATE_ALL 0b01111111 // 6 0 calibrate all blocks
//SX126X_CMD_CALIBRATE_IMAGE
#define SX126X_CAL_IMG_430_MHZ_1 0x6B
#define SX126X_CAL_IMG_430_MHZ_2 0x6F
#define SX126X_CAL_IMG_470_MHZ_1 0x75
#define SX126X_CAL_IMG_470_MHZ_2 0x81
#define SX126X_CAL_IMG_779_MHZ_1 0xC1
#define SX126X_CAL_IMG_779_MHZ_2 0xC5
#define SX126X_CAL_IMG_863_MHZ_1 0xD7
#define SX126X_CAL_IMG_863_MHZ_2 0xDB
#define SX126X_CAL_IMG_902_MHZ_1 0xE1
#define SX126X_CAL_IMG_902_MHZ_2 0xE9
//RADIOLIB_SX126X_CMD_CALIBRATE_IMAGE
#define RADIOLIB_SX126X_CAL_IMG_430_MHZ_1 0x6B
#define RADIOLIB_SX126X_CAL_IMG_430_MHZ_2 0x6F
#define RADIOLIB_SX126X_CAL_IMG_470_MHZ_1 0x75
#define RADIOLIB_SX126X_CAL_IMG_470_MHZ_2 0x81
#define RADIOLIB_SX126X_CAL_IMG_779_MHZ_1 0xC1
#define RADIOLIB_SX126X_CAL_IMG_779_MHZ_2 0xC5
#define RADIOLIB_SX126X_CAL_IMG_863_MHZ_1 0xD7
#define RADIOLIB_SX126X_CAL_IMG_863_MHZ_2 0xDB
#define RADIOLIB_SX126X_CAL_IMG_902_MHZ_1 0xE1
#define RADIOLIB_SX126X_CAL_IMG_902_MHZ_2 0xE9
//SX126X_CMD_SET_PA_CONFIG
#define SX126X_PA_CONFIG_HP_MAX 0x07
#define SX126X_PA_CONFIG_PA_LUT 0x01
#define SX126X_PA_CONFIG_SX1262_8 0x00
//RADIOLIB_SX126X_CMD_SET_PA_CONFIG
#define RADIOLIB_SX126X_PA_CONFIG_HP_MAX 0x07
#define RADIOLIB_SX126X_PA_CONFIG_PA_LUT 0x01
#define RADIOLIB_SX126X_PA_CONFIG_SX1262_8 0x00
//SX126X_CMD_SET_RX_TX_FALLBACK_MODE
#define SX126X_RX_TX_FALLBACK_MODE_FS 0x40 // 7 0 after Rx/Tx go to: FS mode
#define SX126X_RX_TX_FALLBACK_MODE_STDBY_XOSC 0x30 // 7 0 standby with crystal oscillator
#define SX126X_RX_TX_FALLBACK_MODE_STDBY_RC 0x20 // 7 0 standby with RC oscillator (default)
//RADIOLIB_SX126X_CMD_SET_RX_TX_FALLBACK_MODE
#define RADIOLIB_SX126X_RX_TX_FALLBACK_MODE_FS 0x40 // 7 0 after Rx/Tx go to: FS mode
#define RADIOLIB_SX126X_RX_TX_FALLBACK_MODE_STDBY_XOSC 0x30 // 7 0 standby with crystal oscillator
#define RADIOLIB_SX126X_RX_TX_FALLBACK_MODE_STDBY_RC 0x20 // 7 0 standby with RC oscillator (default)
//SX126X_CMD_SET_DIO_IRQ_PARAMS
#define SX126X_IRQ_TIMEOUT 0b1000000000 // 9 9 Rx or Tx timeout
#define SX126X_IRQ_CAD_DETECTED 0b0100000000 // 8 8 channel activity detected
#define SX126X_IRQ_CAD_DONE 0b0010000000 // 7 7 channel activity detection finished
#define SX126X_IRQ_CRC_ERR 0b0001000000 // 6 6 wrong CRC received
#define SX126X_IRQ_HEADER_ERR 0b0000100000 // 5 5 LoRa header CRC error
#define SX126X_IRQ_HEADER_VALID 0b0000010000 // 4 4 valid LoRa header received
#define SX126X_IRQ_SYNC_WORD_VALID 0b0000001000 // 3 3 valid sync word detected
#define SX126X_IRQ_PREAMBLE_DETECTED 0b0000000100 // 2 2 preamble detected
#define SX126X_IRQ_RX_DONE 0b0000000010 // 1 1 packet received
#define SX126X_IRQ_TX_DONE 0b0000000001 // 0 0 packet transmission completed
#define SX126X_IRQ_ALL 0b1111111111 // 9 0 all interrupts
#define SX126X_IRQ_NONE 0b0000000000 // 9 0 no interrupts
//RADIOLIB_SX126X_CMD_SET_DIO_IRQ_PARAMS
#define RADIOLIB_SX126X_IRQ_TIMEOUT 0b1000000000 // 9 9 Rx or Tx timeout
#define RADIOLIB_SX126X_IRQ_CAD_DETECTED 0b0100000000 // 8 8 channel activity detected
#define RADIOLIB_SX126X_IRQ_CAD_DONE 0b0010000000 // 7 7 channel activity detection finished
#define RADIOLIB_SX126X_IRQ_CRC_ERR 0b0001000000 // 6 6 wrong CRC received
#define RADIOLIB_SX126X_IRQ_HEADER_ERR 0b0000100000 // 5 5 LoRa header CRC error
#define RADIOLIB_SX126X_IRQ_HEADER_VALID 0b0000010000 // 4 4 valid LoRa header received
#define RADIOLIB_SX126X_IRQ_SYNC_WORD_VALID 0b0000001000 // 3 3 valid sync word detected
#define RADIOLIB_SX126X_IRQ_RADIOLIB_PREAMBLE_DETECTED 0b0000000100 // 2 2 preamble detected
#define RADIOLIB_SX126X_IRQ_RX_DONE 0b0000000010 // 1 1 packet received
#define RADIOLIB_SX126X_IRQ_TX_DONE 0b0000000001 // 0 0 packet transmission completed
#define RADIOLIB_SX126X_IRQ_ALL 0b1111111111 // 9 0 all interrupts
#define RADIOLIB_SX126X_IRQ_NONE 0b0000000000 // 9 0 no interrupts
//SX126X_CMD_SET_DIO2_AS_RF_SWITCH_CTRL
#define SX126X_DIO2_AS_IRQ 0x00 // 7 0 DIO2 configuration: IRQ
#define SX126X_DIO2_AS_RF_SWITCH 0x01 // 7 0 RF switch control
//RADIOLIB_SX126X_CMD_SET_DIO2_AS_RF_SWITCH_CTRL
#define RADIOLIB_SX126X_DIO2_AS_IRQ 0x00 // 7 0 DIO2 configuration: IRQ
#define RADIOLIB_SX126X_DIO2_AS_RF_SWITCH 0x01 // 7 0 RF switch control
//SX126X_CMD_SET_DIO3_AS_TCXO_CTRL
#define SX126X_DIO3_OUTPUT_1_6 0x00 // 7 0 DIO3 voltage output for TCXO: 1.6 V
#define SX126X_DIO3_OUTPUT_1_7 0x01 // 7 0 1.7 V
#define SX126X_DIO3_OUTPUT_1_8 0x02 // 7 0 1.8 V
#define SX126X_DIO3_OUTPUT_2_2 0x03 // 7 0 2.2 V
#define SX126X_DIO3_OUTPUT_2_4 0x04 // 7 0 2.4 V
#define SX126X_DIO3_OUTPUT_2_7 0x05 // 7 0 2.7 V
#define SX126X_DIO3_OUTPUT_3_0 0x06 // 7 0 3.0 V
#define SX126X_DIO3_OUTPUT_3_3 0x07 // 7 0 3.3 V
//RADIOLIB_SX126X_CMD_SET_DIO3_AS_TCXO_CTRL
#define RADIOLIB_SX126X_DIO3_OUTPUT_1_6 0x00 // 7 0 DIO3 voltage output for TCXO: 1.6 V
#define RADIOLIB_SX126X_DIO3_OUTPUT_1_7 0x01 // 7 0 1.7 V
#define RADIOLIB_SX126X_DIO3_OUTPUT_1_8 0x02 // 7 0 1.8 V
#define RADIOLIB_SX126X_DIO3_OUTPUT_2_2 0x03 // 7 0 2.2 V
#define RADIOLIB_SX126X_DIO3_OUTPUT_2_4 0x04 // 7 0 2.4 V
#define RADIOLIB_SX126X_DIO3_OUTPUT_2_7 0x05 // 7 0 2.7 V
#define RADIOLIB_SX126X_DIO3_OUTPUT_3_0 0x06 // 7 0 3.0 V
#define RADIOLIB_SX126X_DIO3_OUTPUT_3_3 0x07 // 7 0 3.3 V
//SX126X_CMD_SET_PACKET_TYPE
#define SX126X_PACKET_TYPE_GFSK 0x00 // 7 0 packet type: GFSK
#define SX126X_PACKET_TYPE_LORA 0x01 // 7 0 LoRa
//RADIOLIB_SX126X_CMD_SET_PACKET_TYPE
#define RADIOLIB_SX126X_PACKET_TYPE_GFSK 0x00 // 7 0 packet type: GFSK
#define RADIOLIB_SX126X_PACKET_TYPE_LORA 0x01 // 7 0 LoRa
//SX126X_CMD_SET_TX_PARAMS
#define SX126X_PA_RAMP_10U 0x00 // 7 0 ramp time: 10 us
#define SX126X_PA_RAMP_20U 0x01 // 7 0 20 us
#define SX126X_PA_RAMP_40U 0x02 // 7 0 40 us
#define SX126X_PA_RAMP_80U 0x03 // 7 0 80 us
#define SX126X_PA_RAMP_200U 0x04 // 7 0 200 us
#define SX126X_PA_RAMP_800U 0x05 // 7 0 800 us
#define SX126X_PA_RAMP_1700U 0x06 // 7 0 1700 us
#define SX126X_PA_RAMP_3400U 0x07 // 7 0 3400 us
//RADIOLIB_SX126X_CMD_SET_TX_PARAMS
#define RADIOLIB_SX126X_PA_RAMP_10U 0x00 // 7 0 ramp time: 10 us
#define RADIOLIB_SX126X_PA_RAMP_20U 0x01 // 7 0 20 us
#define RADIOLIB_SX126X_PA_RAMP_40U 0x02 // 7 0 40 us
#define RADIOLIB_SX126X_PA_RAMP_80U 0x03 // 7 0 80 us
#define RADIOLIB_SX126X_PA_RAMP_200U 0x04 // 7 0 200 us
#define RADIOLIB_SX126X_PA_RAMP_800U 0x05 // 7 0 800 us
#define RADIOLIB_SX126X_PA_RAMP_1700U 0x06 // 7 0 1700 us
#define RADIOLIB_SX126X_PA_RAMP_3400U 0x07 // 7 0 3400 us
//SX126X_CMD_SET_MODULATION_PARAMS
#define SX126X_GFSK_FILTER_NONE 0x00 // 7 0 GFSK filter: none
#define SX126X_GFSK_FILTER_GAUSS_0_3 0x08 // 7 0 Gaussian, BT = 0.3
#define SX126X_GFSK_FILTER_GAUSS_0_5 0x09 // 7 0 Gaussian, BT = 0.5
#define SX126X_GFSK_FILTER_GAUSS_0_7 0x0A // 7 0 Gaussian, BT = 0.7
#define SX126X_GFSK_FILTER_GAUSS_1 0x0B // 7 0 Gaussian, BT = 1
#define SX126X_GFSK_RX_BW_4_8 0x1F // 7 0 GFSK Rx bandwidth: 4.8 kHz
#define SX126X_GFSK_RX_BW_5_8 0x17 // 7 0 5.8 kHz
#define SX126X_GFSK_RX_BW_7_3 0x0F // 7 0 7.3 kHz
#define SX126X_GFSK_RX_BW_9_7 0x1E // 7 0 9.7 kHz
#define SX126X_GFSK_RX_BW_11_7 0x16 // 7 0 11.7 kHz
#define SX126X_GFSK_RX_BW_14_6 0x0E // 7 0 14.6 kHz
#define SX126X_GFSK_RX_BW_19_5 0x1D // 7 0 19.5 kHz
#define SX126X_GFSK_RX_BW_23_4 0x15 // 7 0 23.4 kHz
#define SX126X_GFSK_RX_BW_29_3 0x0D // 7 0 29.3 kHz
#define SX126X_GFSK_RX_BW_39_0 0x1C // 7 0 39.0 kHz
#define SX126X_GFSK_RX_BW_46_9 0x14 // 7 0 46.9 kHz
#define SX126X_GFSK_RX_BW_58_6 0x0C // 7 0 58.6 kHz
#define SX126X_GFSK_RX_BW_78_2 0x1B // 7 0 78.2 kHz
#define SX126X_GFSK_RX_BW_93_8 0x13 // 7 0 93.8 kHz
#define SX126X_GFSK_RX_BW_117_3 0x0B // 7 0 117.3 kHz
#define SX126X_GFSK_RX_BW_156_2 0x1A // 7 0 156.2 kHz
#define SX126X_GFSK_RX_BW_187_2 0x12 // 7 0 187.2 kHz
#define SX126X_GFSK_RX_BW_234_3 0x0A // 7 0 234.3 kHz
#define SX126X_GFSK_RX_BW_312_0 0x19 // 7 0 312.0 kHz
#define SX126X_GFSK_RX_BW_373_6 0x11 // 7 0 373.6 kHz
#define SX126X_GFSK_RX_BW_467_0 0x09 // 7 0 467.0 kHz
#define SX126X_LORA_BW_7_8 0x00 // 7 0 LoRa bandwidth: 7.8 kHz
#define SX126X_LORA_BW_10_4 0x08 // 7 0 10.4 kHz
#define SX126X_LORA_BW_15_6 0x01 // 7 0 15.6 kHz
#define SX126X_LORA_BW_20_8 0x09 // 7 0 20.8 kHz
#define SX126X_LORA_BW_31_25 0x02 // 7 0 31.25 kHz
#define SX126X_LORA_BW_41_7 0x0A // 7 0 41.7 kHz
#define SX126X_LORA_BW_62_5 0x03 // 7 0 62.5 kHz
#define SX126X_LORA_BW_125_0 0x04 // 7 0 125.0 kHz
#define SX126X_LORA_BW_250_0 0x05 // 7 0 250.0 kHz
#define SX126X_LORA_BW_500_0 0x06 // 7 0 500.0 kHz
#define SX126X_LORA_CR_4_5 0x01 // 7 0 LoRa coding rate: 4/5
#define SX126X_LORA_CR_4_6 0x02 // 7 0 4/6
#define SX126X_LORA_CR_4_7 0x03 // 7 0 4/7
#define SX126X_LORA_CR_4_8 0x04 // 7 0 4/8
#define SX126X_LORA_LOW_DATA_RATE_OPTIMIZE_OFF 0x00 // 7 0 LoRa low data rate optimization: disabled
#define SX126X_LORA_LOW_DATA_RATE_OPTIMIZE_ON 0x01 // 7 0 enabled
//RADIOLIB_SX126X_CMD_SET_MODULATION_PARAMS
#define RADIOLIB_SX126X_GFSK_FILTER_NONE 0x00 // 7 0 GFSK filter: none
#define RADIOLIB_SX126X_GFSK_FILTER_GAUSS_0_3 0x08 // 7 0 Gaussian, BT = 0.3
#define RADIOLIB_SX126X_GFSK_FILTER_GAUSS_0_5 0x09 // 7 0 Gaussian, BT = 0.5
#define RADIOLIB_SX126X_GFSK_FILTER_GAUSS_0_7 0x0A // 7 0 Gaussian, BT = 0.7
#define RADIOLIB_SX126X_GFSK_FILTER_GAUSS_1 0x0B // 7 0 Gaussian, BT = 1
#define RADIOLIB_SX126X_GFSK_RX_BW_4_8 0x1F // 7 0 GFSK Rx bandwidth: 4.8 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_5_8 0x17 // 7 0 5.8 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_7_3 0x0F // 7 0 7.3 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_9_7 0x1E // 7 0 9.7 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_11_7 0x16 // 7 0 11.7 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_14_6 0x0E // 7 0 14.6 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_19_5 0x1D // 7 0 19.5 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_23_4 0x15 // 7 0 23.4 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_29_3 0x0D // 7 0 29.3 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_39_0 0x1C // 7 0 39.0 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_46_9 0x14 // 7 0 46.9 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_58_6 0x0C // 7 0 58.6 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_78_2 0x1B // 7 0 78.2 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_93_8 0x13 // 7 0 93.8 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_117_3 0x0B // 7 0 117.3 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_156_2 0x1A // 7 0 156.2 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_187_2 0x12 // 7 0 187.2 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_234_3 0x0A // 7 0 234.3 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_312_0 0x19 // 7 0 312.0 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_373_6 0x11 // 7 0 373.6 kHz
#define RADIOLIB_SX126X_GFSK_RX_BW_467_0 0x09 // 7 0 467.0 kHz
#define RADIOLIB_SX126X_LORA_BW_7_8 0x00 // 7 0 LoRa bandwidth: 7.8 kHz
#define RADIOLIB_SX126X_LORA_BW_10_4 0x08 // 7 0 10.4 kHz
#define RADIOLIB_SX126X_LORA_BW_15_6 0x01 // 7 0 15.6 kHz
#define RADIOLIB_SX126X_LORA_BW_20_8 0x09 // 7 0 20.8 kHz
#define RADIOLIB_SX126X_LORA_BW_31_25 0x02 // 7 0 31.25 kHz
#define RADIOLIB_SX126X_LORA_BW_41_7 0x0A // 7 0 41.7 kHz
#define RADIOLIB_SX126X_LORA_BW_62_5 0x03 // 7 0 62.5 kHz
#define RADIOLIB_SX126X_LORA_BW_125_0 0x04 // 7 0 125.0 kHz
#define RADIOLIB_SX126X_LORA_BW_250_0 0x05 // 7 0 250.0 kHz
#define RADIOLIB_SX126X_LORA_BW_500_0 0x06 // 7 0 500.0 kHz
#define RADIOLIB_SX126X_LORA_CR_4_5 0x01 // 7 0 LoRa coding rate: 4/5
#define RADIOLIB_SX126X_LORA_CR_4_6 0x02 // 7 0 4/6
#define RADIOLIB_SX126X_LORA_CR_4_7 0x03 // 7 0 4/7
#define RADIOLIB_SX126X_LORA_CR_4_8 0x04 // 7 0 4/8
#define RADIOLIB_SX126X_LORA_LOW_DATA_RATE_OPTIMIZE_OFF 0x00 // 7 0 LoRa low data rate optimization: disabled
#define RADIOLIB_SX126X_LORA_LOW_DATA_RATE_OPTIMIZE_ON 0x01 // 7 0 enabled
//SX126X_CMD_SET_PACKET_PARAMS
#define SX126X_GFSK_PREAMBLE_DETECT_OFF 0x00 // 7 0 GFSK minimum preamble length before reception starts: detector disabled
#define SX126X_GFSK_PREAMBLE_DETECT_8 0x04 // 7 0 8 bits
#define SX126X_GFSK_PREAMBLE_DETECT_16 0x05 // 7 0 16 bits
#define SX126X_GFSK_PREAMBLE_DETECT_24 0x06 // 7 0 24 bits
#define SX126X_GFSK_PREAMBLE_DETECT_32 0x07 // 7 0 32 bits
#define SX126X_GFSK_ADDRESS_FILT_OFF 0x00 // 7 0 GFSK address filtering: disabled
#define SX126X_GFSK_ADDRESS_FILT_NODE 0x01 // 7 0 node only
#define SX126X_GFSK_ADDRESS_FILT_NODE_BROADCAST 0x02 // 7 0 node and broadcast
#define SX126X_GFSK_PACKET_FIXED 0x00 // 7 0 GFSK packet type: fixed (payload length known in advance to both sides)
#define SX126X_GFSK_PACKET_VARIABLE 0x01 // 7 0 variable (payload length added to packet)
#define SX126X_GFSK_CRC_OFF 0x01 // 7 0 GFSK packet CRC: disabled
#define SX126X_GFSK_CRC_1_BYTE 0x00 // 7 0 1 byte
#define SX126X_GFSK_CRC_2_BYTE 0x02 // 7 0 2 byte
#define SX126X_GFSK_CRC_1_BYTE_INV 0x04 // 7 0 1 byte, inverted
#define SX126X_GFSK_CRC_2_BYTE_INV 0x06 // 7 0 2 byte, inverted
#define SX126X_GFSK_WHITENING_OFF 0x00 // 7 0 GFSK data whitening: disabled
#define SX126X_GFSK_WHITENING_ON 0x01 // 7 0 enabled
#define SX126X_LORA_HEADER_EXPLICIT 0x00 // 7 0 LoRa header mode: explicit
#define SX126X_LORA_HEADER_IMPLICIT 0x01 // 7 0 implicit
#define SX126X_LORA_CRC_OFF 0x00 // 7 0 LoRa CRC mode: disabled
#define SX126X_LORA_CRC_ON 0x01 // 7 0 enabled
#define SX126X_LORA_IQ_STANDARD 0x00 // 7 0 LoRa IQ setup: standard
#define SX126X_LORA_IQ_INVERTED 0x01 // 7 0 inverted
//RADIOLIB_SX126X_CMD_SET_PACKET_PARAMS
#define RADIOLIB_SX126X_GFSK_PREAMBLE_DETECT_OFF 0x00 // 7 0 GFSK minimum preamble length before reception starts: detector disabled
#define RADIOLIB_SX126X_GFSK_PREAMBLE_DETECT_8 0x04 // 7 0 8 bits
#define RADIOLIB_SX126X_GFSK_PREAMBLE_DETECT_16 0x05 // 7 0 16 bits
#define RADIOLIB_SX126X_GFSK_PREAMBLE_DETECT_24 0x06 // 7 0 24 bits
#define RADIOLIB_SX126X_GFSK_PREAMBLE_DETECT_32 0x07 // 7 0 32 bits
#define RADIOLIB_SX126X_GFSK_ADDRESS_FILT_OFF 0x00 // 7 0 GFSK address filtering: disabled
#define RADIOLIB_SX126X_GFSK_ADDRESS_FILT_NODE 0x01 // 7 0 node only
#define RADIOLIB_SX126X_GFSK_ADDRESS_FILT_NODE_BROADCAST 0x02 // 7 0 node and broadcast
#define RADIOLIB_SX126X_GFSK_PACKET_FIXED 0x00 // 7 0 GFSK packet type: fixed (payload length known in advance to both sides)
#define RADIOLIB_SX126X_GFSK_PACKET_VARIABLE 0x01 // 7 0 variable (payload length added to packet)
#define RADIOLIB_SX126X_GFSK_CRC_OFF 0x01 // 7 0 GFSK packet CRC: disabled
#define RADIOLIB_SX126X_GFSK_CRC_1_BYTE 0x00 // 7 0 1 byte
#define RADIOLIB_SX126X_GFSK_CRC_2_BYTE 0x02 // 7 0 2 byte
#define RADIOLIB_SX126X_GFSK_CRC_1_BYTE_INV 0x04 // 7 0 1 byte, inverted
#define RADIOLIB_SX126X_GFSK_CRC_2_BYTE_INV 0x06 // 7 0 2 byte, inverted
#define RADIOLIB_SX126X_GFSK_WHITENING_OFF 0x00 // 7 0 GFSK data whitening: disabled
#define RADIOLIB_SX126X_GFSK_WHITENING_ON 0x01 // 7 0 enabled
#define RADIOLIB_SX126X_LORA_HEADER_EXPLICIT 0x00 // 7 0 LoRa header mode: explicit
#define RADIOLIB_SX126X_LORA_HEADER_IMPLICIT 0x01 // 7 0 implicit
#define RADIOLIB_SX126X_LORA_CRC_OFF 0x00 // 7 0 LoRa CRC mode: disabled
#define RADIOLIB_SX126X_LORA_CRC_ON 0x01 // 7 0 enabled
#define RADIOLIB_SX126X_LORA_IQ_STANDARD 0x00 // 7 0 LoRa IQ setup: standard
#define RADIOLIB_SX126X_LORA_IQ_INVERTED 0x01 // 7 0 inverted
//SX126X_CMD_SET_CAD_PARAMS
#define SX126X_CAD_ON_1_SYMB 0x00 // 7 0 number of symbols used for CAD: 1
#define SX126X_CAD_ON_2_SYMB 0x01 // 7 0 2
#define SX126X_CAD_ON_4_SYMB 0x02 // 7 0 4
#define SX126X_CAD_ON_8_SYMB 0x03 // 7 0 8
#define SX126X_CAD_ON_16_SYMB 0x04 // 7 0 16
#define SX126X_CAD_GOTO_STDBY 0x00 // 7 0 after CAD is done, always go to STDBY_RC mode
#define SX126X_CAD_GOTO_RX 0x01 // 7 0 after CAD is done, go to Rx mode if activity is detected
//RADIOLIB_SX126X_CMD_SET_CAD_PARAMS
#define RADIOLIB_SX126X_CAD_ON_1_SYMB 0x00 // 7 0 number of symbols used for CAD: 1
#define RADIOLIB_SX126X_CAD_ON_2_SYMB 0x01 // 7 0 2
#define RADIOLIB_SX126X_CAD_ON_4_SYMB 0x02 // 7 0 4
#define RADIOLIB_SX126X_CAD_ON_8_SYMB 0x03 // 7 0 8
#define RADIOLIB_SX126X_CAD_ON_16_SYMB 0x04 // 7 0 16
#define RADIOLIB_SX126X_CAD_GOTO_STDBY 0x00 // 7 0 after CAD is done, always go to STDBY_RC mode
#define RADIOLIB_SX126X_CAD_GOTO_RX 0x01 // 7 0 after CAD is done, go to Rx mode if activity is detected
//SX126X_CMD_GET_STATUS
#define SX126X_STATUS_MODE_STDBY_RC 0b00100000 // 6 4 current chip mode: STDBY_RC
#define SX126X_STATUS_MODE_STDBY_XOSC 0b00110000 // 6 4 STDBY_XOSC
#define SX126X_STATUS_MODE_FS 0b01000000 // 6 4 FS
#define SX126X_STATUS_MODE_RX 0b01010000 // 6 4 RX
#define SX126X_STATUS_MODE_TX 0b01100000 // 6 4 TX
#define SX126X_STATUS_DATA_AVAILABLE 0b00000100 // 3 1 command status: packet received and data can be retrieved
#define SX126X_STATUS_CMD_TIMEOUT 0b00000110 // 3 1 SPI command timed out
#define SX126X_STATUS_CMD_INVALID 0b00001000 // 3 1 invalid SPI command
#define SX126X_STATUS_CMD_FAILED 0b00001010 // 3 1 SPI command failed to execute
#define SX126X_STATUS_TX_DONE 0b00001100 // 3 1 packet transmission done
#define SX126X_STATUS_SPI_FAILED 0b11111111 // 7 0 SPI transaction failed
//RADIOLIB_SX126X_CMD_GET_STATUS
#define RADIOLIB_SX126X_STATUS_MODE_STDBY_RC 0b00100000 // 6 4 current chip mode: STDBY_RC
#define RADIOLIB_SX126X_STATUS_MODE_STDBY_XOSC 0b00110000 // 6 4 STDBY_XOSC
#define RADIOLIB_SX126X_STATUS_MODE_FS 0b01000000 // 6 4 FS
#define RADIOLIB_SX126X_STATUS_MODE_RX 0b01010000 // 6 4 RX
#define RADIOLIB_SX126X_STATUS_MODE_TX 0b01100000 // 6 4 TX
#define RADIOLIB_SX126X_STATUS_DATA_AVAILABLE 0b00000100 // 3 1 command status: packet received and data can be retrieved
#define RADIOLIB_SX126X_STATUS_CMD_TIMEOUT 0b00000110 // 3 1 SPI command timed out
#define RADIOLIB_SX126X_STATUS_CMD_INVALID 0b00001000 // 3 1 invalid SPI command
#define RADIOLIB_SX126X_STATUS_CMD_FAILED 0b00001010 // 3 1 SPI command failed to execute
#define RADIOLIB_SX126X_STATUS_TX_DONE 0b00001100 // 3 1 packet transmission done
#define RADIOLIB_SX126X_STATUS_SPI_FAILED 0b11111111 // 7 0 SPI transaction failed
//SX126X_CMD_GET_PACKET_STATUS
#define SX126X_GFSK_RX_STATUS_PREAMBLE_ERR 0b10000000 // 7 7 GFSK Rx status: preamble error
#define SX126X_GFSK_RX_STATUS_SYNC_ERR 0b01000000 // 6 6 sync word error
#define SX126X_GFSK_RX_STATUS_ADRS_ERR 0b00100000 // 5 5 address error
#define SX126X_GFSK_RX_STATUS_CRC_ERR 0b00010000 // 4 4 CRC error
#define SX126X_GFSK_RX_STATUS_LENGTH_ERR 0b00001000 // 3 3 length error
#define SX126X_GFSK_RX_STATUS_ABORT_ERR 0b00000100 // 2 2 abort error
#define SX126X_GFSK_RX_STATUS_PACKET_RECEIVED 0b00000010 // 2 2 packet received
#define SX126X_GFSK_RX_STATUS_PACKET_SENT 0b00000001 // 2 2 packet sent
//RADIOLIB_SX126X_CMD_GET_PACKET_STATUS
#define RADIOLIB_SX126X_GFSK_RX_STATUS_PREAMBLE_ERR 0b10000000 // 7 7 GFSK Rx status: preamble error
#define RADIOLIB_SX126X_GFSK_RX_STATUS_SYNC_ERR 0b01000000 // 6 6 sync word error
#define RADIOLIB_SX126X_GFSK_RX_STATUS_ADRS_ERR 0b00100000 // 5 5 address error
#define RADIOLIB_SX126X_GFSK_RX_STATUS_CRC_ERR 0b00010000 // 4 4 CRC error
#define RADIOLIB_SX126X_GFSK_RX_STATUS_LENGTH_ERR 0b00001000 // 3 3 length error
#define RADIOLIB_SX126X_GFSK_RX_STATUS_ABORT_ERR 0b00000100 // 2 2 abort error
#define RADIOLIB_SX126X_GFSK_RX_STATUS_PACKET_RECEIVED 0b00000010 // 2 2 packet received
#define RADIOLIB_SX126X_GFSK_RX_STATUS_PACKET_SENT 0b00000001 // 2 2 packet sent
//SX126X_CMD_GET_DEVICE_ERRORS
#define SX126X_PA_RAMP_ERR 0b100000000 // 8 8 device errors: PA ramping failed
#define SX126X_PLL_LOCK_ERR 0b001000000 // 6 6 PLL failed to lock
#define SX126X_XOSC_START_ERR 0b000100000 // 5 5 crystal oscillator failed to start
#define SX126X_IMG_CALIB_ERR 0b000010000 // 4 4 image calibration failed
#define SX126X_ADC_CALIB_ERR 0b000001000 // 3 3 ADC calibration failed
#define SX126X_PLL_CALIB_ERR 0b000000100 // 2 2 PLL calibration failed
#define SX126X_RC13M_CALIB_ERR 0b000000010 // 1 1 RC13M calibration failed
#define SX126X_RC64K_CALIB_ERR 0b000000001 // 0 0 RC64K calibration failed
//RADIOLIB_SX126X_CMD_GET_DEVICE_ERRORS
#define RADIOLIB_SX126X_PA_RAMP_ERR 0b100000000 // 8 8 device errors: PA ramping failed
#define RADIOLIB_SX126X_PLL_LOCK_ERR 0b001000000 // 6 6 PLL failed to lock
#define RADIOLIB_SX126X_XOSC_START_ERR 0b000100000 // 5 5 crystal oscillator failed to start
#define RADIOLIB_SX126X_IMG_CALIB_ERR 0b000010000 // 4 4 image calibration failed
#define RADIOLIB_SX126X_ADC_CALIB_ERR 0b000001000 // 3 3 ADC calibration failed
#define RADIOLIB_SX126X_PLL_CALIB_ERR 0b000000100 // 2 2 PLL calibration failed
#define RADIOLIB_SX126X_RC13M_CALIB_ERR 0b000000010 // 1 1 RC13M calibration failed
#define RADIOLIB_SX126X_RC64K_CALIB_ERR 0b000000001 // 0 0 RC64K calibration failed
// SX126X SPI register variables
//SX126X_REG_LORA_SYNC_WORD_MSB + LSB
#define SX126X_SYNC_WORD_PUBLIC 0x34 // actually 0x3444 NOTE: The low nibbles in each byte (0x_4_4) are masked out since apparently, they're reserved.
#define SX126X_SYNC_WORD_PRIVATE 0x12 // actually 0x1424 You couldn't make this up if you tried.
//RADIOLIB_SX126X_REG_LORA_SYNC_WORD_MSB + LSB
#define RADIOLIB_SX126X_SYNC_WORD_PUBLIC 0x34 // actually 0x3444 NOTE: The low nibbles in each byte (0x_4_4) are masked out since apparently, they're reserved.
#define RADIOLIB_SX126X_SYNC_WORD_PRIVATE 0x12 // actually 0x1424 You couldn't make this up if you tried.
/*!
@ -354,6 +354,8 @@ class SX126x: public PhysicalLayer {
*/
SX126x(Module* mod);
Module* getMod();
// basic methods
/*!
@ -443,7 +445,7 @@ class SX126x: public PhysicalLayer {
/*!
\brief Starts direct mode reception. Only implemented for PhysicalLayer compatibility, as %SX126x series does not support direct mode reception.
Will always return ERR_UNKNOWN.
Will always return RADIOLIB_ERR_UNKNOWN.
\returns \ref status_codes
*/
@ -475,7 +477,7 @@ class SX126x: public PhysicalLayer {
/*!
\brief Sets the module to standby mode.
\param mode Oscillator to be used in standby mode. Can be set to SX126X_STANDBY_RC (13 MHz RC oscillator) or SX126X_STANDBY_XOSC (32 MHz external crystal oscillator).
\param mode Oscillator to be used in standby mode. Can be set to RADIOLIB_SX126X_STANDBY_RC (13 MHz RC oscillator) or RADIOLIB_SX126X_STANDBY_XOSC (32 MHz external crystal oscillator).
\returns \ref status_codes
*/
@ -512,11 +514,11 @@ class SX126x: public PhysicalLayer {
/*!
\brief Interrupt-driven receive method. DIO1 will be activated when full packet is received.
\param timeout Raw timeout value, expressed as multiples of 15.625 us. Defaults to SX126X_RX_TIMEOUT_INF for infinite timeout (Rx continuous mode), set to SX126X_RX_TIMEOUT_NONE for no timeout (Rx single mode).
\param timeout Raw timeout value, expressed as multiples of 15.625 us. Defaults to RADIOLIB_SX126X_RX_TIMEOUT_INF for infinite timeout (Rx continuous mode), set to RADIOLIB_SX126X_RX_TIMEOUT_NONE for no timeout (Rx single mode).
\returns \ref status_codes
*/
int16_t startReceive(uint32_t timeout = SX126X_RX_TIMEOUT_INF);
int16_t startReceive(uint32_t timeout = RADIOLIB_SX126X_RX_TIMEOUT_INF);
/*!
\brief Interrupt-driven receive method where the device mostly sleeps and periodically wakes to listen.
@ -800,7 +802,7 @@ class SX126x: public PhysicalLayer {
\returns \ref status_codes
*/
int16_t fixedPacketLengthMode(uint8_t len = SX126X_MAX_PACKET_LENGTH);
int16_t fixedPacketLengthMode(uint8_t len = RADIOLIB_SX126X_MAX_PACKET_LENGTH);
/*!
\brief Set modem in variable packet length mode. Available in FSK mode only.
@ -809,7 +811,7 @@ class SX126x: public PhysicalLayer {
\returns \ref status_codes
*/
int16_t variablePacketLengthMode(uint8_t maxLen = SX126X_MAX_PACKET_LENGTH);
int16_t variablePacketLengthMode(uint8_t maxLen = RADIOLIB_SX126X_MAX_PACKET_LENGTH);
/*!
\brief Get expected time-on-air for a given size of payload
@ -915,29 +917,29 @@ class SX126x: public PhysicalLayer {
*/
void readBit(RADIOLIB_PIN_TYPE pin);
#ifndef RADIOLIB_GODMODE
#if !defined(RADIOLIB_GODMODE)
protected:
#endif
// SX126x SPI command implementations
int16_t setTx(uint32_t timeout = 0);
int16_t setRx(uint32_t timeout);
int16_t setCad();
int16_t setPaConfig(uint8_t paDutyCycle, uint8_t deviceSel, uint8_t hpMax = SX126X_PA_CONFIG_HP_MAX, uint8_t paLut = SX126X_PA_CONFIG_PA_LUT);
int16_t setPaConfig(uint8_t paDutyCycle, uint8_t deviceSel, uint8_t hpMax = RADIOLIB_SX126X_PA_CONFIG_HP_MAX, uint8_t paLut = RADIOLIB_SX126X_PA_CONFIG_PA_LUT);
int16_t writeRegister(uint16_t addr, uint8_t* data, uint8_t numBytes);
int16_t readRegister(uint16_t addr, uint8_t* data, uint8_t numBytes);
int16_t writeBuffer(uint8_t* data, uint8_t numBytes, uint8_t offset = 0x00);
int16_t readBuffer(uint8_t* data, uint8_t numBytes);
int16_t setDioIrqParams(uint16_t irqMask, uint16_t dio1Mask, uint16_t dio2Mask = SX126X_IRQ_NONE, uint16_t dio3Mask = SX126X_IRQ_NONE);
int16_t setDioIrqParams(uint16_t irqMask, uint16_t dio1Mask, uint16_t dio2Mask = RADIOLIB_SX126X_IRQ_NONE, uint16_t dio3Mask = RADIOLIB_SX126X_IRQ_NONE);
uint16_t getIrqStatus();
int16_t clearIrqStatus(uint16_t clearIrqParams = SX126X_IRQ_ALL);
int16_t clearIrqStatus(uint16_t clearIrqParams = RADIOLIB_SX126X_IRQ_ALL);
int16_t setRfFrequency(uint32_t frf);
int16_t calibrateImage(uint8_t* data);
uint8_t getPacketType();
int16_t setTxParams(uint8_t power, uint8_t rampTime = SX126X_PA_RAMP_200U);
int16_t setTxParams(uint8_t power, uint8_t rampTime = RADIOLIB_SX126X_PA_RAMP_200U);
int16_t setModulationParams(uint8_t sf, uint8_t bw, uint8_t cr, uint8_t ldro);
int16_t setModulationParamsFSK(uint32_t br, uint8_t pulseShape, uint8_t rxBw, uint32_t freqDev);
int16_t setPacketParams(uint16_t preambleLength, uint8_t crcType, uint8_t payloadLength, uint8_t headerType, uint8_t invertIQ = SX126X_LORA_IQ_STANDARD);
int16_t setPacketParamsFSK(uint16_t preambleLength, uint8_t crcType, uint8_t syncWordLength, uint8_t addrComp, uint8_t whitening, uint8_t packetType = SX126X_GFSK_PACKET_VARIABLE, uint8_t payloadLength = 0xFF, uint8_t preambleDetectorLength = SX126X_GFSK_PREAMBLE_DETECT_16);
int16_t setPacketParams(uint16_t preambleLength, uint8_t crcType, uint8_t payloadLength, uint8_t headerType, uint8_t invertIQ = RADIOLIB_SX126X_LORA_IQ_STANDARD);
int16_t setPacketParamsFSK(uint16_t preambleLength, uint8_t crcType, uint8_t syncWordLength, uint8_t addrComp, uint8_t whitening, uint8_t packetType = RADIOLIB_SX126X_GFSK_PACKET_VARIABLE, uint8_t payloadLength = 0xFF, uint8_t preambleDetectorLength = RADIOLIB_SX126X_GFSK_PREAMBLE_DETECT_16);
int16_t setBufferBaseAddress(uint8_t txBaseAddress = 0x00, uint8_t rxBaseAddress = 0x00);
int16_t setRegulatorMode(uint8_t mode);
uint8_t getStatus();