Set SetPPMoffsetReg for both radios on Team900 diversity hardware (#3019)
[ExpressLRS.git] / src / lib / LR1121Driver / LR1121.cpp
blob9181d1c2391554b479812df119c9bf9773e3d624
1 #include "LR1121_Regs.h"
2 #include "LR1121_hal.h"
3 #include "LR1121.h"
4 #include "logging.h"
5 #include <math.h>
7 LR1121Hal hal;
8 LR1121Driver *LR1121Driver::instance = NULL;
10 //DEBUG_LR1121_OTA_TIMING
12 #if defined(DEBUG_LR1121_OTA_TIMING)
13 static uint32_t beginTX;
14 static uint32_t endTX;
15 #endif
17 // RxTimeout is expressed in periods of the 32.768kHz RTC
18 #define RX_TIMEOUT_PERIOD_BASE_NANOS 1000000000 / 32768 // TODO check for LR1121
20 LR1121Driver::LR1121Driver(): SX12xxDriverCommon()
22 useFSK = false;
23 instance = this;
24 timeout = 0xFFFFFF;
25 lastSuccessfulPacketRadio = SX12XX_Radio_1;
26 fallBackMode = LR1121_MODE_FS;
27 useFEC = false;
30 void LR1121Driver::End()
32 SetMode(LR1121_MODE_SLEEP, SX12XX_Radio_All);
33 hal.end();
34 RemoveCallbacks();
37 bool LR1121Driver::Begin(uint32_t minimumFrequency, uint32_t maximumFrequency)
39 hal.init();
40 hal.IsrCallback_1 = &LR1121Driver::IsrCallback_1;
41 hal.IsrCallback_2 = &LR1121Driver::IsrCallback_2;
43 hal.reset();
45 // Validate that the LR1121 is working.
46 uint8_t version[5] = {0};
47 hal.WriteCommand(LR11XX_SYSTEM_GET_VERSION_OC, SX12XX_Radio_1);
48 hal.ReadCommand(version, sizeof(version), SX12XX_Radio_1);
50 DBGLN("Read LR1121 #1 Use Case (0x03 = LR1121): %d", version[2]);
51 if (version[2] != 0x03)
53 DBGLN("LR1121 #1 failed to be detected.");
54 return false;
56 DBGLN("LR1121 #1 Ready");
58 if (GPIO_PIN_NSS_2 != UNDEF_PIN)
60 // Validate that the LR1121 #2 is working.
61 memset(version, 0, sizeof(version));
62 hal.WriteCommand(LR11XX_SYSTEM_GET_VERSION_OC, SX12XX_Radio_2);
63 hal.ReadCommand(version, sizeof(version), SX12XX_Radio_2);
65 DBGLN("Read LR1121 #2 Use Case (0x03 = LR1121): %d", version[2]);
66 if (version[2] != 0x03)
68 DBGLN("LR1121 #2 failed to be detected.");
69 return false;
71 DBGLN("LR1121 #2 Ready");
74 //Clear Errors
75 hal.WriteCommand(LR11XX_SYSTEM_CLEAR_ERRORS_OC, SX12XX_Radio_All); // Remove later? Might not be required???
78 Do not enable for dual radio TX.
79 When AUTOFS is set and tlm received by only 1 of the 2 radios, that radio will go into FS mode and the other
80 into Standby mode. After the following SPI command for tx mode, busy will go high for differing periods of time because 1 is
81 transitioning from FS mode and the other from Standby mode. This causes the tx done dio of the 2 radios to occur at very different times.
83 // 7.2.5 SetRxTxFallbackMode
84 uint8_t FBbuf[1] = {LR11XX_RADIO_FALLBACK_FS};
85 fallBackMode = LR1121_MODE_FS;
86 hal.WriteCommand(LR11XX_RADIO_SET_RX_TX_FALLBACK_MODE_OC, FBbuf, sizeof(FBbuf), SX12XX_Radio_All);
88 // 7.2.12 SetRxBoosted
89 uint8_t abuf[1] = {1};
90 hal.WriteCommand(LR11XX_RADIO_SET_RX_BOOSTED_OC, abuf, sizeof(abuf), SX12XX_Radio_All);
92 SetDioAsRfSwitch();
93 SetDioIrqParams();
95 if (OPT_USE_HARDWARE_DCDC)
97 // 5.1.1 SetRegMode
98 uint8_t RegMode[1] = {1};
99 hal.WriteCommand(LR11XX_SYSTEM_SET_REGMODE_OC, RegMode, sizeof(RegMode), SX12XX_Radio_All); // Enable DCDC converter instead of LDO
102 // 2.1.3.1 CalibImage
103 uint8_t CalImagebuf[2];
104 CalImagebuf[0] = ((minimumFrequency / 1000000 ) - 1) / 4; // Freq1 = floor( (fmin_mhz - 1)/4)
105 CalImagebuf[1] = 1 + ((maximumFrequency / 1000000 ) + 1) / 4; // Freq2 = ceil( (fmax_mhz + 1)/4)
106 hal.WriteCommand(LR11XX_SYSTEM_CALIBRATE_IMAGE_OC, CalImagebuf, sizeof(CalImagebuf), SX12XX_Radio_All);
108 return true;
111 // 12.2.1 SetTxCw
112 void LR1121Driver::startCWTest(uint32_t freq, SX12XX_Radio_Number_t radioNumber)
114 // Set a basic Config that can be used for both 2.4G and SubGHz bands.
115 Config(LR11XX_RADIO_LORA_BW_62, LR11XX_RADIO_LORA_SF6, LR11XX_RADIO_LORA_CR_4_8, freq, 12, false, 8, 0, false, 0, 0, radioNumber);
116 CommitOutputPower();
117 hal.WriteCommand(LR11XX_RADIO_SET_TX_CW_OC, radioNumber);
120 void LR1121Driver::Config(uint8_t bw, uint8_t sf, uint8_t cr, uint32_t regfreq,
121 uint8_t PreambleLength, bool InvertIQ, uint8_t _PayloadLength, uint32_t interval,
122 bool setFSKModulation, uint8_t fskSyncWord1, uint8_t fskSyncWord2,
123 SX12XX_Radio_Number_t radioNumber)
125 PayloadLength = _PayloadLength;
127 bool isSubGHz = regfreq < 1000000000;
129 if (radioNumber & SX12XX_Radio_1)
130 radio1isSubGHz = isSubGHz;
132 if (radioNumber & SX12XX_Radio_2)
133 radio2isSubGHz = isSubGHz;
135 IQinverted = InvertIQ ? LR11XX_RADIO_LORA_IQ_INVERTED : LR11XX_RADIO_LORA_IQ_STANDARD;
136 // IQinverted is always STANDARD for 900 and SX1276
137 if (isSubGHz)
139 IQinverted = LR11XX_RADIO_LORA_IQ_STANDARD;
142 SetRxTimeoutUs(interval);
144 SetMode(LR1121_MODE_STDBY_RC, radioNumber);
146 useFSK = setFSKModulation;
148 // 8.1.1 SetPacketType
149 uint8_t buf[1] = {useFSK ? LR11XX_RADIO_PKT_TYPE_GFSK : LR11XX_RADIO_PKT_TYPE_LORA};
150 hal.WriteCommand(LR11XX_RADIO_SET_PKT_TYPE_OC, buf, sizeof(buf), radioNumber);
152 useFEC = false;
153 if (useFSK)
155 DBGLN("Config FSK");
156 uint32_t bitrate = (uint32_t)bw * 10000;
157 uint8_t bwf = sf;
158 uint32_t fdev = (uint32_t)cr * 1000;
159 ConfigModParamsFSK(bitrate, bwf, fdev, radioNumber);
161 // Increase packet length for FEC used only on 1000Hz 2.5GHz.
162 if (!isSubGHz)
164 useFEC = true;
165 PayloadLength = 14;
168 SetPacketParamsFSK(PreambleLength, PayloadLength, radioNumber);
169 SetFSKSyncWord(fskSyncWord1, fskSyncWord2, radioNumber);
171 else
173 DBGLN("Config LoRa");
174 ConfigModParamsLoRa(bw, sf, cr, radioNumber);
176 #if defined(DEBUG_FREQ_CORRECTION) // TODO Check if this available with the LR1121?
177 lr11xx_RadioLoRaPacketLengthsModes_t packetLengthType = LR1121_LORA_PACKET_VARIABLE_LENGTH;
178 #else
179 lr11xx_RadioLoRaPacketLengthsModes_t packetLengthType = LR1121_LORA_PACKET_FIXED_LENGTH;
180 #endif
182 SetPacketParamsLoRa(PreambleLength, packetLengthType, PayloadLength, IQinverted, radioNumber);
185 SetFrequencyHz(regfreq, radioNumber);
187 pwrForceUpdate = true; // Must be called after changing rf modes between subG and 2.4G. This sets the correct rf amps, and txen pins to be used.
189 ClearIrqStatus(radioNumber);
192 void LR1121Driver::ConfigModParamsFSK(uint32_t Bitrate, uint8_t BWF, uint32_t Fdev, SX12XX_Radio_Number_t radioNumber)
194 // 8.5.1 SetModulationParams
195 uint8_t buf[10];
196 buf[0] = Bitrate >> 24;
197 buf[1] = Bitrate >> 16;
198 buf[2] = Bitrate >> 8;
199 buf[3] = Bitrate >> 0;
200 buf[4] = LR11XX_RADIO_GFSK_PULSE_SHAPE_OFF; // Pulse Shape - 0x00: No filter applied
201 buf[5] = BWF;
202 buf[6] = Fdev >> 24;
203 buf[7] = Fdev >> 16;
204 buf[8] = Fdev >> 8;
205 buf[9] = Fdev >> 0;
206 hal.WriteCommand(LR11XX_RADIO_SET_MODULATION_PARAM_OC, buf, sizeof(buf), radioNumber);
209 void LR1121Driver::SetPacketParamsFSK(uint8_t PreambleLength, uint8_t PayloadLength, SX12XX_Radio_Number_t radioNumber)
211 // 8.5.2 SetPacketParams
212 uint8_t buf[9];
213 buf[0] = 0; // MSB PbLengthTX defines the length of the LoRa packet preamble. Minimum of 12 with SF5 and SF6, and of 8 for other SF advised;
214 buf[1] = PreambleLength; // LSB PbLengthTX defines the length of the LoRa packet preamble. Minimum of 12 with SF5 and SF6, and of 8 for other SF advised;
215 buf[2] = LR11XX_RADIO_GFSK_PREAMBLE_DETECTOR_MIN_8BITS; // Pbl Detect - 0x04: Preamble detector length 8 bits
216 buf[3] = 16; // SyncWordLen defines the length of the Syncword in bits. By default, the Syncword is set to 0x9723522556536564
217 buf[4] = LR11XX_RADIO_GFSK_ADDRESS_FILTERING_DISABLE; // Addr Comp - 0x00: Address Filtering Disabled
218 buf[5] = LR11XX_RADIO_GFSK_PKT_FIX_LEN; // PacketType - 0x00: Packet length is known on both sides
219 buf[6] = PayloadLength; // PayloadLen
220 buf[7] = LR11XX_RADIO_GFSK_CRC_OFF; // CrcType - 0x01: CRC_OFF (No CRC).
221 buf[8] = LR11XX_RADIO_GFSK_DC_FREE_WHITENING; // DcFree - 0x01: SX127x/SX126x/LR11xx compatible whitening enable. 0x03: SX128x compatible whitening enable
222 hal.WriteCommand(LR11XX_RADIO_SET_PKT_PARAM_OC, buf, sizeof(buf), radioNumber);
225 void LR1121Driver::SetFSKSyncWord(uint8_t fskSyncWord1, uint8_t fskSyncWord2, SX12XX_Radio_Number_t radioNumber)
227 // 8.5.3 SetGfskSyncWord
228 // SyncWordLen is 16 bits as set in SetPacketParamsFSK(). Fill the rest with preamble bytes.
229 uint8_t synbuf[8] = {fskSyncWord1, fskSyncWord2, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55};
230 hal.WriteCommand(LR11XX_RADIO_SET_GFSK_SYNC_WORD_OC, synbuf, sizeof(synbuf), radioNumber);
233 void LR1121Driver::SetDioAsRfSwitch()
235 // 4.2.1 SetDioAsRfSwitch
236 uint8_t switchbuf[8];
237 if (LR1121_RFSW_CTRL_COUNT == 8)
239 switchbuf[0] = LR1121_RFSW_CTRL[0]; // RfswEnable
240 switchbuf[1] = LR1121_RFSW_CTRL[1]; // RfSwStbyCfg
241 switchbuf[2] = LR1121_RFSW_CTRL[2]; // RfSwRxCfg
242 switchbuf[3] = LR1121_RFSW_CTRL[3]; // RfSwTxCfg
243 switchbuf[4] = LR1121_RFSW_CTRL[4]; // RfSwTxHPCfg
244 switchbuf[5] = LR1121_RFSW_CTRL[5]; // RfSwTxHfCfg
245 switchbuf[6] = LR1121_RFSW_CTRL[6]; // Unused
246 switchbuf[7] = LR1121_RFSW_CTRL[7]; // RfSwWifiCfg - Each bit indicates the state of the relevant RFSW DIO when in Wi-Fi scanning mode or high frequency RX mode (LR1110_H1_UM_V1-7-1.pdf)
248 else
250 switchbuf[0] = 0b00001111; // RfswEnable
251 switchbuf[1] = 0b00000000; // RfSwStbyCfg
252 switchbuf[2] = 0b00000100; // RfSwRxCfg
253 switchbuf[3] = 0b00001000; // RfSwTxCfg
254 switchbuf[4] = 0b00001000; // RfSwTxHPCfg
255 switchbuf[5] = 0b00000010; // RfSwTxHfCfg
256 switchbuf[6] = 0; // Unused
257 switchbuf[7] = 0b00000001; // RfSwWifiCfg - Each bit indicates the state of the relevant RFSW DIO when in Wi-Fi scanning mode or high frequency RX mode (LR1110_H1_UM_V1-7-1.pdf)
259 hal.WriteCommand(LR11XX_SYSTEM_SET_DIO_AS_RF_SWITCH_OC, switchbuf, sizeof(switchbuf), SX12XX_Radio_All);
262 void LR1121Driver::SetRxTimeoutUs(uint32_t interval)
264 timeout = 0xFFFFFF; // no timeout, continuous mode
265 if (interval)
267 timeout = interval * 1000 / RX_TIMEOUT_PERIOD_BASE_NANOS;
271 void LR1121Driver::CorrectRegisterForSF6(uint8_t sf, SX12XX_Radio_Number_t radioNumber)
273 // 8.3.1 SetModulationParams
274 // - SF6 can be made compatible with the SX127x family in implicit mode via a register setting.
275 // - Set bit 18 of register at address 0xf20414 to 1
276 // - Set bit 23 of register at address 0xf20414 to 0. This information is from Semtech in an email.
277 // 3.7.3 WriteRegMemMask32
279 if ((lr11xx_radio_lora_sf_t)sf == LR11XX_RADIO_LORA_SF6)
281 uint8_t wrbuf[12];
282 // Address
283 wrbuf[0] = 0x00; // MSB
284 wrbuf[1] = 0xf2;
285 wrbuf[2] = 0x04;
286 wrbuf[3] = 0x14;
287 // Mask
288 wrbuf[4] = 0x00; // MSB
289 wrbuf[5] = 0b10000100; // bit18=1 and bit23=0
290 wrbuf[6] = 0x00;
291 wrbuf[7] = 0x00;
292 // Data
293 wrbuf[8] = 0x00; // MSB
294 wrbuf[9] = 0b00000100; // bit18=1 and bit23=0
295 wrbuf[10] = 0x00;
296 wrbuf[11] = 0x00;
297 hal.WriteCommand(LR11XX_REGMEM_WRITE_REGMEM32_MASK_OC, wrbuf, sizeof(wrbuf), radioNumber);
301 /***
302 * @brief: Schedule an output power change after the next transmit
303 ***/
304 void LR1121Driver::SetOutputPower(int8_t power, bool isSubGHz)
306 uint8_t pwrNew;
308 if (isSubGHz)
310 if (OPT_USE_SX1276_RFO_HF)
312 pwrNew = constrain(power, LR1121_POWER_MIN_LP_PA, LR1121_POWER_MAX_LP_PA);
314 else
316 pwrNew = constrain(power, LR1121_POWER_MIN_HP_PA, LR1121_POWER_MAX_HP_PA);
319 if ((pwrPendingLF == PWRPENDING_NONE && pwrCurrentLF != pwrNew) || pwrPendingLF != pwrNew)
321 pwrPendingLF = pwrNew;
324 else
326 pwrNew = constrain(power, LR1121_POWER_MIN_HF_PA, LR1121_POWER_MAX_HF_PA);
328 if ((pwrPendingHF == PWRPENDING_NONE && pwrCurrentHF != pwrNew) || pwrPendingHF != pwrNew)
330 pwrPendingHF = pwrNew;
335 void ICACHE_RAM_ATTR LR1121Driver::CommitOutputPower()
337 if (pwrPendingLF != PWRPENDING_NONE)
339 pwrCurrentLF = pwrPendingLF;
340 pwrPendingLF = PWRPENDING_NONE;
341 pwrForceUpdate = true;
344 if (pwrPendingHF != PWRPENDING_NONE)
346 pwrCurrentHF = pwrPendingHF;
347 pwrPendingHF = PWRPENDING_NONE;
348 pwrForceUpdate = true;
351 if (pwrForceUpdate)
353 WriteOutputPower(radio1isSubGHz ? pwrCurrentLF : pwrCurrentHF, radio1isSubGHz, SX12XX_Radio_1);
354 if (GPIO_PIN_NSS_2 != UNDEF_PIN)
356 WriteOutputPower(radio2isSubGHz ? pwrCurrentLF : pwrCurrentHF, radio2isSubGHz, SX12XX_Radio_2);
358 pwrForceUpdate = false;
362 void ICACHE_RAM_ATTR LR1121Driver::WriteOutputPower(uint8_t power, bool isSubGHz, SX12XX_Radio_Number_t radioNumber)
364 uint8_t Pabuf[4] = {0};
365 uint8_t Txbuf[2] = {power, LR11XX_RADIO_RAMP_48_US};
367 // 9.5.1 SetPaConfig
368 // 9.5.2 SetTxParams
369 if (isSubGHz)
371 // 900M low power RF Amp
372 // Table 9-1: Optimized Settings for LP PA with Same Matching Network
373 // -17dBm (0xEF) to +14dBm (0x0E) by steps of 1dB if the low power PA is selected
374 if (OPT_USE_SX1276_RFO_HF)
376 Pabuf[0] = LR11XX_RADIO_PA_SEL_LP; // PaSel - 0x01: Selects the low power PA
377 Pabuf[1] = LR11XX_RADIO_PA_REG_SUPPLY_VREG; // RegPaSupply - 0x01: Powers the PA from VBAT. The user must use RegPaSupply = 0x01 whenever TxPower > 14
378 Pabuf[2] = 0x07; // PaDutyCycle
380 // 900M high power RF Amp
381 // Table 9-2: Optimized Settings for HP PA with Same Matching Network
382 // -9dBm (0xF7) to +22dBm (0x16) by steps of 1dB if the high power PA is selected
383 else
385 Pabuf[0] = LR11XX_RADIO_PA_SEL_HP; // PaSel - 0x01: Selects the high power PA
386 Pabuf[1] = LR11XX_RADIO_PA_REG_SUPPLY_VBAT; // RegPaSupply - 0x01: Powers the PA from VBAT. The user must use RegPaSupply = 0x01 whenever TxPower > 14
387 Pabuf[2] = 0x04; // PaDutyCycle
388 Pabuf[3] = 0x07; // PaHPSel - In order to reach +22dBm output power, PaHPSel must be set to 7. PaHPSel has no impact on either the low power PA or the high frequency PA.
391 // 2.4G RF Amp
392 // Table 9-3: Optimized Settings for HF PA with Same Matching Network
393 // -18dBm (0xEE) to +13dBm (0x0D) by steps of 1dB if the high frequency PA is selected
394 else
396 Pabuf[0] = LR11XX_RADIO_PA_SEL_HF; // PaSel - 0x02: Selects the high frequency PA
397 Pabuf[1] = LR11XX_RADIO_PA_REG_SUPPLY_VREG; // RegPaSupply - 0x01: Powers the PA from VBAT. The user must use RegPaSupply = 0x01 whenever TxPower > 14
398 Pabuf[2] = 0x00; // PaDutyCycle
399 Pabuf[3] = 0x00; // PaHPSel - In order to reach +22dBm output power, PaHPSel must be set to 7. PaHPSel has no impact on either the low power PA or the high frequency PA.
402 hal.WriteCommand(LR11XX_RADIO_SET_PA_CFG_OC, Pabuf, sizeof(Pabuf), radioNumber);
403 hal.WriteCommand(LR11XX_RADIO_SET_TX_PARAMS_OC, Txbuf, sizeof(Txbuf), radioNumber);
406 void LR1121Driver::SetMode(lr11xx_RadioOperatingModes_t OPmode, SX12XX_Radio_Number_t radioNumber)
408 WORD_ALIGNED_ATTR uint8_t buf[5] = {0};
409 switch (OPmode)
411 case LR1121_MODE_SLEEP:
412 // 2.1.5.1 SetSleep
413 hal.WriteCommand(LR11XX_SYSTEM_SET_SLEEP_OC, buf, 5, radioNumber);
414 break;
416 case LR1121_MODE_STDBY_RC:
417 //2.1.2.1 SetStandby
418 buf[0] = 0x00;
419 hal.WriteCommand(LR11XX_SYSTEM_SET_STANDBY_OC, buf, 1, radioNumber);
420 break;
422 case LR1121_MODE_STDBY_XOSC:
423 //2.1.2.1 SetStandby
424 buf[0] = 0x01;
425 hal.WriteCommand(LR11XX_SYSTEM_SET_STANDBY_OC, buf, 1, radioNumber);
426 break;
428 case LR1121_MODE_FS:
429 // 2.1.9.1 SetFs
430 hal.WriteCommand(LR11XX_SYSTEM_SET_FS_OC, radioNumber);
431 break;
433 case LR1121_MODE_RX:
434 // 7.2.2 SetRx
435 buf[0] = timeout >> 16;
436 buf[1] = timeout >> 8;
437 buf[2] = timeout & 0xFF;
438 hal.WriteCommand(LR11XX_RADIO_SET_RX_OC, buf, 3, radioNumber);
439 break;
441 case LR1121_MODE_RX_CONT:
442 // 7.2.2 SetRx
443 buf[0] = 0xFF;
444 buf[1] = 0xFF;
445 buf[2] = 0xFF;
446 hal.WriteCommand(LR11XX_RADIO_SET_RX_OC, buf, 3, radioNumber);
447 break;
449 case LR1121_MODE_TX:
450 // Table 7-3: SetTx Command
451 hal.WriteCommand(LR11XX_RADIO_SET_TX_OC, buf, 3, radioNumber);
452 break;
454 case LR1121_MODE_CAD:
455 break;
457 default:
458 break;
462 void LR1121Driver::ConfigModParamsLoRa(uint8_t bw, uint8_t sf, uint8_t cr, SX12XX_Radio_Number_t radioNumber)
464 // 8.3.1 SetModulationParams
465 uint8_t buf[4];
466 buf[0] = sf;
467 buf[1] = bw;
468 buf[2] = cr;
469 buf[3] = 0x00; // 0x00: LowDataRateOptimize off
470 hal.WriteCommand(LR11XX_RADIO_SET_MODULATION_PARAM_OC, buf, sizeof(buf), radioNumber);
472 if (radioNumber & SX12XX_Radio_1 && radio1isSubGHz)
473 CorrectRegisterForSF6(sf, SX12XX_Radio_1);
475 if (GPIO_PIN_NSS_2 != UNDEF_PIN)
477 if (radioNumber & SX12XX_Radio_2 && radio2isSubGHz)
478 CorrectRegisterForSF6(sf, SX12XX_Radio_2);
482 void LR1121Driver::SetPacketParamsLoRa(uint8_t PreambleLength, lr11xx_RadioLoRaPacketLengthsModes_t HeaderType,
483 uint8_t PayloadLength, uint8_t InvertIQ, SX12XX_Radio_Number_t radioNumber)
485 // 8.3.2 SetPacketParams
486 uint8_t buf[6];
487 buf[0] = 0; // MSB PbLengthTX defines the length of the LoRa packet preamble. Minimum of 12 with SF5 and SF6, and of 8 for other SF advised;
488 buf[1] = PreambleLength; // LSB PbLengthTX defines the length of the LoRa packet preamble. Minimum of 12 with SF5 and SF6, and of 8 for other SF advised;
489 buf[2] = HeaderType; // HeaderType defines if the header is explicit or implicit
490 buf[3] = PayloadLength; // PayloadLen defines the size of the payload
491 buf[4] = LR11XX_RADIO_LORA_CRC_OFF;
492 buf[5] = InvertIQ;
493 hal.WriteCommand(LR11XX_RADIO_SET_PKT_PARAM_OC, buf, sizeof(buf), radioNumber);
496 void ICACHE_RAM_ATTR LR1121Driver::SetFrequencyHz(uint32_t freq, SX12XX_Radio_Number_t radioNumber)
498 // 7.2.1 SetRfFrequency
499 uint8_t buf[4];
500 buf[0] = freq >> 24;
501 buf[1] = freq >> 16;
502 buf[2] = freq >> 8;
503 buf[3] = freq & 0xFF;
504 hal.WriteCommand(LR11XX_RADIO_SET_RF_FREQUENCY_OC, buf, sizeof(buf), radioNumber);
506 currFreq = freq;
509 void ICACHE_RAM_ATTR LR1121Driver::SetFrequencyReg(uint32_t freq, SX12XX_Radio_Number_t radioNumber)
511 SetFrequencyHz(freq, radioNumber);
514 // 4.1.1 SetDioIrqParams
515 void LR1121Driver::SetDioIrqParams()
517 uint8_t buf[8] = {0};
518 buf[3] = LR1121_IRQ_TX_DONE | LR1121_IRQ_RX_DONE;
519 hal.WriteCommand(LR11XX_SYSTEM_SET_DIOIRQPARAMS_OC, buf, sizeof(buf), SX12XX_Radio_All);
522 // 3.4.1 GetStatus
523 uint32_t ICACHE_RAM_ATTR LR1121Driver::GetIrqStatus(SX12XX_Radio_Number_t radioNumber)
525 uint8_t status[6] = {0};
526 status[0] = LR11XX_SYSTEM_CLEAR_IRQ_OC >> 8;
527 status[1] = LR11XX_SYSTEM_CLEAR_IRQ_OC & 0xFF;
528 status[2] = 0xFF;
529 status[3] = 0xFF;
530 status[4] = 0xFF;
531 status[5] = 0xFF;
532 hal.ReadCommand(status, sizeof(status), radioNumber);
533 return status[2] << 24 | status[3] << 16 | status[4] << 8 | status[5];
536 void ICACHE_RAM_ATTR LR1121Driver::ClearIrqStatus(SX12XX_Radio_Number_t radioNumber)
538 uint8_t buf[4];
539 buf[0] = 0xFF;
540 buf[1] = 0xFF;
541 buf[2] = 0xFF;
542 buf[3] = 0xFF;
543 hal.WriteCommand(LR11XX_SYSTEM_CLEAR_IRQ_OC, buf, sizeof(buf), radioNumber);
546 void ICACHE_RAM_ATTR LR1121Driver::TXnbISR()
548 #ifdef DEBUG_LR1121_OTA_TIMING
549 endTX = micros();
550 DBGLN("TOA: %d", endTX - beginTX);
551 #endif
552 CommitOutputPower();
553 TXdoneCallback();
556 void ICACHE_RAM_ATTR LR1121Driver::TXnb(uint8_t * data, uint8_t size, SX12XX_Radio_Number_t radioNumber)
558 transmittingRadio = radioNumber;
560 // //catch TX timeout
561 // if (currOpmode == SX1280_MODE_TX)
562 // {
563 // DBGLN("Timeout!");
564 // SetMode(SX1280_MODE_FS, SX12XX_Radio_All);
565 // ClearIrqStatus(SX1280_IRQ_RADIO_ALL, SX12XX_Radio_All);
566 // TXnbISR();
567 // return;
568 // }
570 if (radioNumber == SX12XX_Radio_NONE)
572 SetMode(fallBackMode, SX12XX_Radio_All);
573 return;
576 #if defined(DEBUG_RCVR_SIGNAL_STATS)
577 if (radioNumber == SX12XX_Radio_All || radioNumber == SX12XX_Radio_1)
579 instance->rxSignalStats[0].telem_count++;
581 if (radioNumber == SX12XX_Radio_All || radioNumber == SX12XX_Radio_2)
583 instance->rxSignalStats[1].telem_count++;
585 #endif
587 // Normal diversity mode
588 if (GPIO_PIN_NSS_2 != UNDEF_PIN && radioNumber != SX12XX_Radio_All)
590 // Make sure the unused radio is in FS mode and will not receive the tx packet.
591 if (radioNumber == SX12XX_Radio_1)
593 SetMode(fallBackMode, SX12XX_Radio_2);
595 else
597 SetMode(fallBackMode, SX12XX_Radio_1);
601 if (useFEC)
603 uint8_t FECBuffer[PayloadLength] = {0};
604 FECEncode(data, FECBuffer);
606 // 3.7.4 WriteBuffer8
607 hal.WriteCommand(LR11XX_REGMEM_WRITE_BUFFER8_OC, FECBuffer, PayloadLength, radioNumber);
609 else
611 // 3.7.4 WriteBuffer8
612 hal.WriteCommand(LR11XX_REGMEM_WRITE_BUFFER8_OC, data, size, radioNumber);
615 SetMode(LR1121_MODE_TX, radioNumber);
617 #ifdef DEBUG_LLCC68_OTA_TIMING
618 beginTX = micros();
619 #endif
622 bool ICACHE_RAM_ATTR LR1121Driver::RXnbISR(SX12XX_Radio_Number_t radioNumber)
624 // 7.2.11 GetRxBufferStatus
625 uint8_t buf[3] = {0};
626 hal.WriteCommand(LR11XX_RADIO_GET_RXBUFFER_STATUS_OC, radioNumber);
627 hal.ReadCommand(buf, sizeof(buf), radioNumber);
629 uint8_t const PayloadLengthRX = buf[1];
630 uint8_t const RxStartBufferPointer = buf[2];
632 // 3.7.5 ReadBuffer8
633 uint8_t inbuf[2];
634 inbuf[0] = RxStartBufferPointer;
635 inbuf[1] = PayloadLengthRX;
637 uint8_t payloadbuf[PayloadLengthRX + 1] = {0};
638 hal.WriteCommand(LR11XX_REGMEM_READ_BUFFER8_OC, inbuf, sizeof(inbuf), radioNumber);
639 hal.ReadCommand(payloadbuf, sizeof(payloadbuf), radioNumber);
641 if (useFEC)
643 FECDecode(payloadbuf + 1, RXdataBuffer);
645 else
647 memcpy(RXdataBuffer, payloadbuf + 1, PayloadLengthRX);
650 return RXdoneCallback(SX12XX_RX_OK);
653 void ICACHE_RAM_ATTR LR1121Driver::RXnb(lr11xx_RadioOperatingModes_t rxMode)
655 SetMode(LR1121_MODE_RX, SX12XX_Radio_All);
658 bool ICACHE_RAM_ATTR LR1121Driver::GetFrequencyErrorbool(SX12XX_Radio_Number_t radioNumber)
660 return false;
663 // 7.2.8 GetRssiInst
664 int8_t ICACHE_RAM_ATTR LR1121Driver::GetRssiInst(SX12XX_Radio_Number_t radioNumber)
666 uint8_t status[2] = {0};
667 hal.WriteCommand(LR11XX_RADIO_GET_RSSI_INST_OC, radioNumber);
668 hal.ReadCommand(status, sizeof(status), radioNumber);
669 return -(int8_t)(status[1] / 2);
672 void ICACHE_RAM_ATTR LR1121Driver::CheckForSecondPacket()
674 SX12XX_Radio_Number_t radio[2] = {SX12XX_Radio_1, SX12XX_Radio_2};
675 uint8_t processingRadioIdx = (instance->processingPacketRadio == SX12XX_Radio_1) ? 0 : 1;
676 uint8_t secondRadioIdx = !processingRadioIdx;
678 // processingRadio always passed the sanity check here
679 gotRadio[processingRadioIdx] = true;
680 gotRadio[secondRadioIdx] = false;
682 hasSecondRadioGotData = false;
684 if (GPIO_PIN_NSS_2 != UNDEF_PIN)
686 uint32_t secondIrqStatus = instance->GetIrqStatus(radio[secondRadioIdx]);
687 if(secondIrqStatus & LR1121_IRQ_RX_DONE)
689 // 7.2.11 GetRxBufferStatus
690 uint8_t buf[3] = {0};
691 hal.WriteCommand(LR11XX_RADIO_GET_RXBUFFER_STATUS_OC, radio[secondRadioIdx]);
692 hal.ReadCommand(buf, sizeof(buf), radio[secondRadioIdx]);
694 uint8_t const PayloadLengthRX = buf[1];
695 uint8_t const RxStartBufferPointer = buf[2];
697 // 3.7.5 ReadBuffer8
698 uint8_t inbuf[2];
699 inbuf[0] = RxStartBufferPointer;
700 inbuf[1] = PayloadLengthRX;
702 WORD_ALIGNED_ATTR uint8_t TempRXdataBufferSecond[PayloadLengthRX + 1] = {0};
704 hal.WriteCommand(LR11XX_REGMEM_READ_BUFFER8_OC, inbuf, sizeof(inbuf), radio[secondRadioIdx]);
705 hal.ReadCommand(TempRXdataBufferSecond, sizeof(TempRXdataBufferSecond), radio[secondRadioIdx]);
707 if (useFEC)
709 FECDecode(TempRXdataBufferSecond + 1, RXdataBufferSecond);
711 else
713 memcpy(RXdataBufferSecond, TempRXdataBufferSecond + 1, PayloadLength);
716 hasSecondRadioGotData = true;
721 void ICACHE_RAM_ATTR LR1121Driver::GetLastPacketStats()
723 SX12XX_Radio_Number_t radio[2] = {SX12XX_Radio_1, SX12XX_Radio_2};
724 uint8_t processingRadioIdx = (instance->processingPacketRadio == SX12XX_Radio_1) ? 0 : 1;
725 uint8_t secondRadioIdx = !processingRadioIdx;
727 uint8_t status[3];
728 int8_t rssi[2];
729 int8_t snr[2];
731 gotRadio[secondRadioIdx] = hasSecondRadioGotData;
732 #if defined(DEBUG_RCVR_SIGNAL_STATS)
733 if(!hasSecondRadioGotData)
735 instance->rxSignalStats[secondRadioIdx].fail_count++;
737 #endif
739 // Get both radios ready at the same time to return packet stats
740 hal.WriteCommand(LR11XX_RADIO_GET_PKT_STATUS_OC, instance->processingPacketRadio | (gotRadio[secondRadioIdx] ? radio[secondRadioIdx] : 0));
742 for(uint8_t i=0; i<2; i++)
744 if (gotRadio[i])
746 // 8.3.7 GetPacketStatus (LoRa)
747 // 8.5.7 GetPacketStatus (FSK)
748 memset(status, 0, sizeof(status));
749 hal.ReadCommand(status, sizeof(status), radio[i]);
751 // RssiPkt defines the average RSSI over the last packet received. RSSI value in dBm is –RssiPkt/2.
752 rssi[i] = -(int8_t)(status[useFSK ? 2 : 1] / 2);
754 // SignalRssiPkt is an estimation of RSSI of the LoRa signal (after despreading) on last packet received, in two’s
755 // complement format [negated, dBm, fixdt(0,8,1)]. Actual RSSI in dB is -SignalRssiPkt/2.
756 // rssi[i = -(int8_t)(status[3] / 2); // SignalRssiPkt
758 snr[i] = useFSK ? 0 : (int8_t)status[2];
760 // If radio # is 0, update LastPacketRSSI, otherwise LastPacketRSSI2
761 (i == 0) ? LastPacketRSSI = rssi[i] : LastPacketRSSI2 = rssi[i];
762 // Update whatever SNRs we have
763 LastPacketSNRRaw = snr[i];
767 // by default, set the last successful packet radio to be the current processing radio (which got a successful packet)
768 instance->lastSuccessfulPacketRadio = instance->processingPacketRadio;
770 // when both radio got the packet, use the better RSSI one
771 if(gotRadio[0] && gotRadio[1])
773 LastPacketSNRRaw = instance->fuzzy_snr(snr[0], snr[1], instance->FuzzySNRThreshold);
774 // Update the last successful packet radio to be the one with better signal strength
775 instance->lastSuccessfulPacketRadio = (rssi[0]>rssi[1])? radio[0]: radio[1];
778 #if defined(DEBUG_RCVR_SIGNAL_STATS)
779 // stat updates
780 for (uint8_t i = 0; i < 2; i++)
782 if (gotRadio[i])
784 instance->rxSignalStats[i].irq_count++;
785 instance->rxSignalStats[i].rssi_sum += rssi[i];
786 instance->rxSignalStats[i].snr_sum += snr[i];
787 if (snr[i] > instance->rxSignalStats[i].snr_max)
789 instance->rxSignalStats[i].snr_max = snr[i];
791 LastPacketSNRRaw = snr[i];
794 if(gotRadio[0] || gotRadio[1])
796 instance->irq_count_or++;
798 if(gotRadio[0] && gotRadio[1])
800 instance->irq_count_both++;
802 #endif
805 void ICACHE_RAM_ATTR LR1121Driver::IsrCallback_1()
807 if (digitalRead(GPIO_PIN_DIO1))
809 instance->IsrCallback(SX12XX_Radio_1);
813 void ICACHE_RAM_ATTR LR1121Driver::IsrCallback_2()
815 if (digitalRead(GPIO_PIN_DIO1_2))
817 instance->IsrCallback(SX12XX_Radio_2);
821 void ICACHE_RAM_ATTR LR1121Driver::IsrCallback(SX12XX_Radio_Number_t radioNumber)
823 instance->processingPacketRadio = radioNumber;
825 uint32_t irqStatus = instance->GetIrqStatus(radioNumber);
826 if (irqStatus & LR1121_IRQ_TX_DONE)
828 instance->TXnbISR();
829 instance->ClearIrqStatus(SX12XX_Radio_All);
831 else if (irqStatus & LR1121_IRQ_RX_DONE)
833 if (instance->RXnbISR(radioNumber))
836 #if defined(DEBUG_RCVR_SIGNAL_STATS)
837 else
839 instance->rxSignalStats[(radioNumber == SX12XX_Radio_1) ? 0 : 1].fail_count++;
841 #endif