Gemini/Diversity 900 (#1993)
[ExpressLRS.git] / src / lib / SX127xDriver / SX127x.cpp
blob7da5f6e617e438f73fd4323edbb3f97596d72ee6
1 #include "SX127x.h"
2 #include "logging.h"
3 #include "RFAMP_hal.h"
5 SX127xHal hal;
6 SX127xDriver *SX127xDriver::instance = NULL;
8 RFAMP_hal RFAMP;
10 #ifdef USE_SX1276_RFO_HF
11 #ifndef OPT_USE_SX1276_RFO_HF
12 #define OPT_USE_SX1276_RFO_HF true
13 #endif
14 #else
15 #define OPT_USE_SX1276_RFO_HF false
16 #endif
18 const uint8_t SX127x_AllowedSyncwords[105] =
19 {0, 5, 6, 7, 11, 12, 13, 15, 18,
20 21, 23, 26, 29, 30, 31, 33, 34,
21 37, 38, 39, 40, 42, 44, 50, 51,
22 54, 55, 57, 58, 59, 61, 63, 65,
23 67, 68, 71, 77, 78, 79, 80, 82,
24 84, 86, 89, 92, 94, 96, 97, 99,
25 101, 102, 105, 106, 109, 111, 113, 115,
26 117, 118, 119, 121, 122, 124, 126, 127,
27 129, 130, 138, 143, 161, 170, 172, 173,
28 175, 180, 181, 182, 187, 190, 191, 192,
29 193, 196, 199, 201, 204, 205, 208, 209,
30 212, 213, 219, 220, 221, 223, 227, 229,
31 235, 239, 240, 242, 243, 246, 247, 255};
33 //////////////////////////////////////////////
35 SX127xDriver::SX127xDriver(): SX12xxDriverCommon()
37 instance = this;
38 // default values from datasheet
39 currSyncWord = SX127X_SYNC_WORD;
40 currBW =SX127x_BW_125_00_KHZ;
41 currSF = SX127x_SF_7;
42 currCR = SX127x_CR_4_5;
43 currOpmode = SX127x_OPMODE_SLEEP;
44 ModFSKorLoRa = SX127x_OPMODE_LORA;
45 // Dummy default values which are overwritten during setup
46 currPreambleLen = 0;
47 PayloadLength = 8;
48 currFreq = 0;
49 headerExplMode = false;
50 crcEnabled = false;
51 lowFrequencyMode = SX1278_HIGH_FREQ;
54 bool SX127xDriver::Begin()
56 hal.init();
57 hal.IsrCallback_1 = &SX127xDriver::IsrCallback_1;
58 hal.IsrCallback_2 = &SX127xDriver::IsrCallback_2;
60 hal.reset();
61 DBGLN("SX127x Begin");
63 RFAMP.init();
65 // currFreq must be set before calling Radio.Begin so that lowFrequencyMode can be set correctly.
66 if (currFreq < (uint32_t)((double)525000000 / (double)FREQ_STEP))
68 lowFrequencyMode = SX1278_LOW_FREQ;
69 DBGLN("Setting 'lowFrequencyMode' used for 433MHz.");
72 SetMode(SX127x_OPMODE_STANDBY, SX12XX_Radio_All);
74 if (!DetectChip(SX12XX_Radio_1))
76 return false;
79 if (GPIO_PIN_NSS_2 != UNDEF_PIN)
81 if (!DetectChip(SX12XX_Radio_2))
83 return false;
87 ConfigLoraDefaults();
88 // Force the next power update
89 pwrCurrent = PWRPENDING_NONE;
90 SetOutputPower(0);
91 CommitOutputPower();
93 return true;
96 void SX127xDriver::End()
98 SetMode(SX127x_OPMODE_SLEEP, SX12XX_Radio_All);
99 hal.end();
100 RFAMP.TXRXdisable();
101 RemoveCallbacks();
104 void SX127xDriver::ConfigLoraDefaults()
106 hal.writeRegister(SX127X_REG_OP_MODE, SX127x_OPMODE_SLEEP, SX12XX_Radio_All);
107 hal.writeRegister(SX127X_REG_OP_MODE, ModFSKorLoRa, SX12XX_Radio_All); //must be written in sleep mode
108 SetMode(SX127x_OPMODE_STANDBY, SX12XX_Radio_All);
110 hal.writeRegister(SX127X_REG_PAYLOAD_LENGTH, PayloadLength, SX12XX_Radio_All);
111 SetSyncWord(currSyncWord);
112 hal.writeRegister(SX127X_REG_FIFO_TX_BASE_ADDR, SX127X_FIFO_TX_BASE_ADDR_MAX, SX12XX_Radio_All);
113 hal.writeRegister(SX127X_REG_FIFO_RX_BASE_ADDR, SX127X_FIFO_RX_BASE_ADDR_MAX, SX12XX_Radio_All);
114 hal.writeRegisterBits(SX127X_REG_DIO_MAPPING_1, SX127X_DIO0_RXTX_DONE, SX127X_DIO0_MASK, SX12XX_Radio_All); //undocumented "hack", looking at Table 18 from datasheet SX127X_REG_DIO_MAPPING_1 = 11 appears to be unspported by infact it generates an intterupt on both RXdone and TXdone, this saves switching modes.
115 hal.writeRegister(SX127X_REG_LNA, SX127X_LNA_BOOST_ON, SX12XX_Radio_All);
116 hal.writeRegister(SX1278_REG_MODEM_CONFIG_3, SX1278_AGC_AUTO_ON | SX1278_LOW_DATA_RATE_OPT_OFF, SX12XX_Radio_All);
117 hal.writeRegisterBits(SX127X_REG_OCP, SX127X_OCP_ON | SX127X_OCP_150MA, SX127X_OCP_MASK, SX12XX_Radio_All); //150ma max current
118 SetPreambleLength(SX127X_PREAMBLE_LENGTH_LSB);
121 void SX127xDriver::SetBandwidthCodingRate(SX127x_Bandwidth bw, SX127x_CodingRate cr)
123 if ((currBW != bw) || (currCR != cr))
125 if (currSF == SX127x_SF_6) // set SF6 optimizations
127 hal.writeRegister(SX127X_REG_MODEM_CONFIG_1, bw | cr | SX1278_HEADER_IMPL_MODE, SX12XX_Radio_All);
128 hal.writeRegisterBits(SX127X_REG_MODEM_CONFIG_2, SX1278_RX_CRC_MODE_OFF, SX1278_RX_CRC_MODE_MASK, SX12XX_Radio_All);
130 else
132 if (headerExplMode)
134 hal.writeRegister(SX127X_REG_MODEM_CONFIG_1, bw | cr | SX1278_HEADER_EXPL_MODE, SX12XX_Radio_All);
136 else
138 hal.writeRegister(SX127X_REG_MODEM_CONFIG_1, bw | cr | SX1278_HEADER_IMPL_MODE, SX12XX_Radio_All);
141 if (crcEnabled)
144 hal.writeRegisterBits(SX127X_REG_MODEM_CONFIG_2, SX1278_RX_CRC_MODE_ON, SX1278_RX_CRC_MODE_MASK, SX12XX_Radio_All);
146 else
148 hal.writeRegisterBits(SX127X_REG_MODEM_CONFIG_2, SX1278_RX_CRC_MODE_OFF, SX1278_RX_CRC_MODE_MASK, SX12XX_Radio_All);
152 if (bw == SX127x_BW_500_00_KHZ)
154 //datasheet errata reconmendation http://caxapa.ru/thumbs/972894/SX1276_77_8_ErrataNote_1.1_STD.pdf
155 hal.writeRegister(0x36, 0x02, SX12XX_Radio_All);
156 hal.writeRegister(0x3a, lowFrequencyMode ? 0x7F : 0x64, SX12XX_Radio_All);
158 else
160 hal.writeRegister(0x36, 0x03, SX12XX_Radio_All);
162 currCR = cr;
163 currBW = bw;
167 bool SyncWordOk(uint8_t syncWord)
169 for (unsigned int i = 0; i < sizeof(SX127x_AllowedSyncwords); i++)
171 if (syncWord == SX127x_AllowedSyncwords[i])
173 return true;
176 return false;
179 void SX127xDriver::SetSyncWord(uint8_t syncWord)
181 uint8_t _syncWord = syncWord;
183 while (SyncWordOk(_syncWord) == false)
185 _syncWord++;
188 if(syncWord != _syncWord){
189 DBGLN("Using syncword: %d instead of: %d", _syncWord, syncWord);
192 hal.writeRegister(SX127X_REG_SYNC_WORD, _syncWord, SX12XX_Radio_All);
193 currSyncWord = _syncWord;
196 /***
197 * @brief: Schedule an output power change after the next transmit
198 * The radio must be in SX127x_OPMODE_STANDBY to change the power
199 ***/
200 void SX127xDriver::SetOutputPower(uint8_t Power)
202 uint8_t pwrNew;
203 if (OPT_USE_SX1276_RFO_HF)
205 pwrNew = SX127X_PA_SELECT_RFO | SX127X_MAX_OUTPUT_POWER_RFO_HF | Power;
207 else
209 pwrNew = SX127X_PA_SELECT_BOOST | SX127X_MAX_OUTPUT_POWER | Power;
212 if ((pwrPending == PWRPENDING_NONE && pwrCurrent != pwrNew) || pwrPending != pwrNew)
214 pwrPending = pwrNew;
218 void ICACHE_RAM_ATTR SX127xDriver::CommitOutputPower()
220 if (pwrPending == PWRPENDING_NONE)
221 return;
223 pwrCurrent = pwrPending;
224 pwrPending = PWRPENDING_NONE;
225 hal.writeRegister(SX127X_REG_PA_CONFIG, pwrCurrent, SX12XX_Radio_All);
228 void SX127xDriver::SetPreambleLength(uint8_t PreambleLen)
230 if (currPreambleLen != PreambleLen)
232 hal.writeRegister(SX127X_REG_PREAMBLE_LSB, PreambleLen, SX12XX_Radio_All);
233 currPreambleLen = PreambleLen;
237 void SX127xDriver::SetSpreadingFactor(SX127x_SpreadingFactor sf)
239 if (currSF != sf)
241 hal.writeRegisterBits(SX127X_REG_MODEM_CONFIG_2, sf | SX127X_TX_MODE_SINGLE, SX127X_SPREADING_FACTOR_MASK | SX127X_TX_MODE_MASK, SX12XX_Radio_All);
242 if (sf == SX127x_SF_6)
244 hal.writeRegisterBits(SX127X_REG_DETECT_OPTIMIZE, SX127X_DETECT_OPTIMIZE_SF_6, SX127X_DETECT_OPTIMIZE_SF_MASK, SX12XX_Radio_All);
245 hal.writeRegister(SX127X_REG_DETECTION_THRESHOLD, SX127X_DETECTION_THRESHOLD_SF_6, SX12XX_Radio_All);
247 else
249 hal.writeRegisterBits(SX127X_REG_DETECT_OPTIMIZE, SX127X_DETECT_OPTIMIZE_SF_7_12, SX127X_DETECT_OPTIMIZE_SF_MASK, SX12XX_Radio_All);
250 hal.writeRegister(SX127X_REG_DETECTION_THRESHOLD, SX127X_DETECTION_THRESHOLD_SF_7_12, SX12XX_Radio_All);
252 currSF = sf;
256 void ICACHE_RAM_ATTR SX127xDriver::SetFrequencyHz(uint32_t freq, SX12XX_Radio_Number_t radioNumber)
258 int32_t regfreq = ((uint32_t)((double)freq / (double)FREQ_STEP));
260 SetFrequencyReg(regfreq, radioNumber);
263 void ICACHE_RAM_ATTR SX127xDriver::SetFrequencyReg(uint32_t regfreq, SX12XX_Radio_Number_t radioNumber)
265 currFreq = regfreq;
266 SetMode(SX127x_OPMODE_STANDBY, radioNumber);
268 uint8_t FRQ_MSB = (uint8_t)((regfreq >> 16) & 0xFF);
269 uint8_t FRQ_MID = (uint8_t)((regfreq >> 8) & 0xFF);
270 uint8_t FRQ_LSB = (uint8_t)(regfreq & 0xFF);
272 WORD_ALIGNED_ATTR uint8_t outbuff[3] = {FRQ_MSB, FRQ_MID, FRQ_LSB}; //check speedup
274 hal.writeRegister(SX127X_REG_FRF_MSB, outbuff, sizeof(outbuff), radioNumber);
277 void ICACHE_RAM_ATTR SX127xDriver::SetRxTimeoutUs(uint32_t interval)
279 timeoutSymbols = 0; // no timeout i.e. use continuous mode
280 if (interval)
282 unsigned int spread = 0;
283 switch (currSF)
285 case SX127x_SF_6:
286 spread = 6;
287 break;
288 case SX127x_SF_7:
289 spread = 7;
290 break;
291 case SX127x_SF_8:
292 spread = 8;
293 break;
294 case SX127x_SF_9:
295 spread = 9;
296 break;
297 case SX127x_SF_10:
298 spread = 10;
299 break;
300 case SX127x_SF_11:
301 spread = 11;
302 break;
303 case SX127x_SF_12:
304 spread = 12;
305 break;
307 uint32_t symbolTimeUs = ((uint32_t)(1 << spread)) * 1000000 / GetCurrBandwidth();
308 timeoutSymbols = interval / symbolTimeUs;
309 hal.writeRegisterBits(SX127X_REG_SYMB_TIMEOUT_MSB, timeoutSymbols >> 8, SX127X_REG_SYMB_TIMEOUT_MSB_MASK, SX12XX_Radio_All); // set the timeout MSB
310 hal.writeRegister(SX127X_REG_SYMB_TIMEOUT_LSB, timeoutSymbols & 0xFF, SX12XX_Radio_All);
311 DBGLN("SetRxTimeout(%u), symbolTime=%uus symbols=%u", interval, (uint32_t)symbolTimeUs, timeoutSymbols)
315 bool SX127xDriver::DetectChip(SX12XX_Radio_Number_t radioNumber)
317 DBG("Detecting radio %x... ", radioNumber);
318 uint8_t i = 0;
319 bool flagFound = false;
320 while ((i < 3) && !flagFound)
322 uint8_t version = hal.readRegister(SX127X_REG_VERSION, radioNumber);
323 DBG("%x", version);
324 if (version == 0x12)
326 flagFound = true;
328 else
330 DBGLN(" not found! (%d of 3 tries) REG_VERSION == 0x%x", i+1, version);
331 delay(200);
332 i++;
336 if (!flagFound)
338 DBGLN(" not found!");
339 return false;
341 else
343 DBGLN(" found! (match by REG_VERSION == 0x12)");
345 return true;
348 /////////////////////////////////////TX functions/////////////////////////////////////////
350 void ICACHE_RAM_ATTR SX127xDriver::TXnbISR()
352 currOpmode = SX127x_OPMODE_STANDBY; //goes into standby after transmission
353 //TXdoneMicros = micros();
354 // The power level must be changed when in SX127x_OPMODE_STANDBY, so this lags power
355 // changes by at most 1 packet, but does not interrupt any pending RX/TX
356 CommitOutputPower();
357 TXdoneCallback();
360 void ICACHE_RAM_ATTR SX127xDriver::TXnb(uint8_t * data, uint8_t size, SX12XX_Radio_Number_t radioNumber)
362 // if (currOpmode == SX127x_OPMODE_TX)
363 // {
364 // DBGLN("abort TX");
365 // return; // we were already TXing so abort. this should never happen!!!
366 // }
367 SetMode(SX127x_OPMODE_STANDBY, SX12XX_Radio_All);
369 if (radioNumber == SX12XX_Radio_Default)
371 radioNumber = lastSuccessfulPacketRadio;
374 RFAMP.TXenable(radioNumber);
375 hal.writeRegister(SX127X_REG_FIFO_ADDR_PTR, SX127X_FIFO_TX_BASE_ADDR_MAX, radioNumber);
376 hal.writeRegister(SX127X_REG_FIFO, data, size, radioNumber);
378 SetMode(SX127x_OPMODE_TX, radioNumber);
381 ///////////////////////////////////RX Functions Non-Blocking///////////////////////////////////////////
383 bool ICACHE_RAM_ATTR SX127xDriver::RXnbISR(SX12XX_Radio_Number_t radioNumber)
385 uint8_t const FIFOaddr = hal.readRegister(SX127X_REG_FIFO_RX_CURRENT_ADDR, radioNumber);
386 hal.writeRegister(SX127X_REG_FIFO_ADDR_PTR, FIFOaddr, radioNumber);
387 hal.readRegister(SX127X_REG_FIFO, RXdataBuffer, PayloadLength, radioNumber);
389 if (timeoutSymbols)
391 // From page 42 of the datasheet rev 7
392 // In Rx Single mode, the device will return to Standby mode as soon as the interrupt occurs
393 currOpmode = SX127x_OPMODE_STANDBY;
396 return RXdoneCallback(SX12XX_RX_OK);
399 void ICACHE_RAM_ATTR SX127xDriver::RXnb()
401 RFAMP.RXenable();
403 if (timeoutSymbols)
405 SetMode(SX127x_OPMODE_RXSINGLE, SX12XX_Radio_All);
407 else
409 SetMode(SX127x_OPMODE_RXCONTINUOUS, SX12XX_Radio_All);
413 void ICACHE_RAM_ATTR SX127xDriver::GetLastPacketStats()
415 LastPacketRSSI = GetLastPacketRSSI();
416 LastPacketSNRRaw = GetLastPacketSNRRaw();
417 // https://www.mouser.com/datasheet/2/761/sx1276-1278113.pdf
418 // Section 3.5.5 (page 87)
419 int8_t negOffset = (LastPacketSNRRaw < 0) ? (LastPacketSNRRaw / RADIO_SNR_SCALE) : 0;
420 LastPacketRSSI += negOffset;
423 void ICACHE_RAM_ATTR SX127xDriver::SetMode(SX127x_RadioOPmodes mode, SX12XX_Radio_Number_t radioNumber)
426 Comment out since it is difficult to keep track of dual radios.
427 When checking SPI it is also useful to see every possible SPI transaction to make sure it fits when required.
429 // if (mode == currOpmode)
430 // {
431 // return;
432 // }
434 hal.writeRegister(SX127X_REG_OP_MODE, mode | lowFrequencyMode, radioNumber);
435 currOpmode = mode;
438 void SX127xDriver::Config(uint8_t bw, uint8_t sf, uint8_t cr, uint32_t freq, uint8_t preambleLen, bool InvertIQ, uint8_t _PayloadLength, uint32_t interval)
440 Config(bw, sf, cr, freq, preambleLen, currSyncWord, InvertIQ, _PayloadLength, interval);
443 void SX127xDriver::Config(uint8_t bw, uint8_t sf, uint8_t cr, uint32_t freq, uint8_t preambleLen, uint8_t syncWord, bool InvertIQ, uint8_t _PayloadLength, uint32_t interval)
445 PayloadLength = _PayloadLength;
446 ConfigLoraDefaults();
447 SetPreambleLength(preambleLen);
448 SetSpreadingFactor((SX127x_SpreadingFactor)sf);
449 SetBandwidthCodingRate((SX127x_Bandwidth)bw, (SX127x_CodingRate)cr);
450 SetFrequencyReg(freq);
451 SetRxTimeoutUs(interval);
454 uint32_t ICACHE_RAM_ATTR SX127xDriver::GetCurrBandwidth()
456 switch (currBW)
458 case SX127x_BW_7_80_KHZ:
459 return 7.8E3;
460 case SX127x_BW_10_40_KHZ:
461 return 10.4E3;
462 case SX127x_BW_15_60_KHZ:
463 return 15.6E3;
464 case SX127x_BW_20_80_KHZ:
465 return 20.8E3;
466 case SX127x_BW_31_25_KHZ:
467 return 31.25E3;
468 case SX127x_BW_41_70_KHZ:
469 return 41.7E3;
470 case SX127x_BW_62_50_KHZ:
471 return 62.5E3;
472 case SX127x_BW_125_00_KHZ:
473 return 125E3;
474 case SX127x_BW_250_00_KHZ:
475 return 250E3;
476 case SX127x_BW_500_00_KHZ:
477 return 500E3;
479 return -1;
482 uint32_t ICACHE_RAM_ATTR SX127xDriver::GetCurrBandwidthNormalisedShifted() // this is basically just used for speedier calc of the freq offset, pre compiled for 32mhz xtal
485 switch (currBW)
487 case SX127x_BW_7_80_KHZ:
488 return 1026;
489 case SX127x_BW_10_40_KHZ:
490 return 769;
491 case SX127x_BW_15_60_KHZ:
492 return 513;
493 case SX127x_BW_20_80_KHZ:
494 return 385;
495 case SX127x_BW_31_25_KHZ:
496 return 256;
497 case SX127x_BW_41_70_KHZ:
498 return 192;
499 case SX127x_BW_62_50_KHZ:
500 return 128;
501 case SX127x_BW_125_00_KHZ:
502 return 64;
503 case SX127x_BW_250_00_KHZ:
504 return 32;
505 case SX127x_BW_500_00_KHZ:
506 return 16;
508 return -1;
512 * Set the PPMcorrection register to adjust data rate to frequency error
513 * @param offset is in Hz or FREQ_STEP (FREQ_HZ_TO_REG_VAL) units, whichever
514 * was used to SetFrequencyHz/SetFrequencyReg
516 void ICACHE_RAM_ATTR SX127xDriver::SetPPMoffsetReg(int32_t offset)
518 int8_t offsetPPM = (offset * 1e6 / currFreq) * 95 / 100;
519 hal.writeRegister(SX127x_PPMOFFSET, (uint8_t)offsetPPM, processingPacketRadio);
522 bool ICACHE_RAM_ATTR SX127xDriver::GetFrequencyErrorbool()
524 return (hal.readRegister(SX127X_REG_FEI_MSB, processingPacketRadio) & 0b1000) >> 3; // returns true if pos freq error, neg if false
527 int32_t ICACHE_RAM_ATTR SX127xDriver::GetFrequencyError()
530 WORD_ALIGNED_ATTR uint8_t reg[3] = {0x0, 0x0, 0x0};
531 hal.readRegister(SX127X_REG_FEI_MSB, reg, sizeof(reg), processingPacketRadio);
533 uint32_t RegFei = ((reg[0] & 0b0111) << 16) + (reg[1] << 8) + reg[2];
535 int32_t intFreqError = RegFei;
537 if ((reg[0] & 0b1000) >> 3)
539 intFreqError -= 524288; // Sign bit is on
542 int32_t fErrorHZ = (intFreqError >> 3) * (SX127xDriver::GetCurrBandwidthNormalisedShifted()); // bit shift hackery so we don't have to use floaty bois; the >> 3 is intentional and is a simplification of the formula on page 114 of sx1276 datasheet
543 fErrorHZ >>= 4;
545 return fErrorHZ;
548 uint8_t ICACHE_RAM_ATTR SX127xDriver::UnsignedGetLastPacketRSSI(SX12XX_Radio_Number_t radioNumber)
550 return hal.readRegister(SX127X_REG_PKT_RSSI_VALUE, radioNumber);
553 int8_t ICACHE_RAM_ATTR SX127xDriver::GetLastPacketRSSI()
555 return ((lowFrequencyMode ? -164 : -157) + hal.readRegister(SX127X_REG_PKT_RSSI_VALUE, processingPacketRadio));
558 int8_t ICACHE_RAM_ATTR SX127xDriver::GetCurrRSSI(SX12XX_Radio_Number_t radioNumber)
560 return ((lowFrequencyMode ? -164 : -157) + hal.readRegister(SX127X_REG_RSSI_VALUE, radioNumber));
563 int8_t ICACHE_RAM_ATTR SX127xDriver::GetLastPacketSNRRaw()
565 return (int8_t)hal.readRegister(SX127X_REG_PKT_SNR_VALUE, processingPacketRadio);
568 uint8_t ICACHE_RAM_ATTR SX127xDriver::GetIrqFlags(SX12XX_Radio_Number_t radioNumber)
570 return hal.readRegister(SX127X_REG_IRQ_FLAGS, radioNumber);
573 void ICACHE_RAM_ATTR SX127xDriver::ClearIrqFlags(SX12XX_Radio_Number_t radioNumber)
575 hal.writeRegister(SX127X_REG_IRQ_FLAGS, SX127X_CLEAR_IRQ_FLAG_ALL, radioNumber);
578 void ICACHE_RAM_ATTR SX127xDriver::IsrCallback_1()
580 instance->IsrCallback(SX12XX_Radio_1);
583 void ICACHE_RAM_ATTR SX127xDriver::IsrCallback_2()
585 instance->IsrCallback(SX12XX_Radio_2);
588 void ICACHE_RAM_ATTR SX127xDriver::IsrCallback(SX12XX_Radio_Number_t radioNumber)
590 instance->processingPacketRadio = radioNumber;
591 SX12XX_Radio_Number_t irqClearRadio = radioNumber;
593 uint8_t irqStatus = instance->GetIrqFlags(radioNumber);
594 if (irqStatus & SX127X_CLEAR_IRQ_FLAG_TX_DONE)
596 RFAMP.TXRXdisable();
597 instance->TXnbISR();
598 irqClearRadio = SX12XX_Radio_All;
600 else if (irqStatus & SX127X_CLEAR_IRQ_FLAG_RX_DONE)
602 if (instance->RXnbISR(radioNumber))
604 instance->lastSuccessfulPacketRadio = radioNumber;
605 irqClearRadio = SX12XX_Radio_All;
609 else if (irqStatus == SX127X_CLEAR_IRQ_FLAG_NONE)
611 return;
614 instance->ClearIrqFlags(irqClearRadio);
617 // int16_t MeasureNoiseFloor() TODO disabled for now
618 // {
619 // int NUM_READS = RSSI_FLOOR_NUM_READS * FHSSgetChannelCount();
620 // float returnval = 0;
622 // for (uint32_t freq = 0; freq < FHSSgetChannelCount(); freq++)
623 // {
624 // FHSSsetCurrIndex(freq);
625 // Radio.SetMode(SX127X_CAD);
627 // for (int i = 0; i < RSSI_FLOOR_NUM_READS; i++)
628 // {
629 // returnval = returnval + Radio.GetCurrRSSI();
630 // delay(5);
631 // }
632 // }
633 // returnval = returnval / NUM_READS;
634 // return (returnval);
635 // }
637 // uint8_t SX127xDriver::RunCAD() TODO
638 // {
639 // SetMode(SX127X_STANDBY);
641 // hal.writeRegisterBits(SX127X_REG_DIO_MAPPING_1, SX127X_DIO0_CAD_DONE | SX127X_DIO1_CAD_DETECTED, 7, 4);
643 // SetMode(SX127X_CAD);
644 // ClearIrqFlags();
646 // uint32_t startTime = millis();
648 // while (!digitalRead(SX127x_dio0))
649 // {
650 // if (millis() > (startTime + 500))
651 // {
652 // return (CHANNEL_FREE);
653 // }
654 // else
655 // {
656 // //yield();
657 // if (digitalRead(SX127x_dio1))
658 // {
659 // ClearIrqFlags();
660 // return (PREAMBLE_DETECTED);
661 // }
662 // }
663 // }
665 // ClearIrqFlags();
666 // return (CHANNEL_FREE);
667 // }