2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * Based on https://github.com/ExpressLRS/ExpressLRS
23 * Thanks to AlessandroAU, original creator of the ExpressLRS project.
34 #include "build/atomic.h"
36 #include "drivers/bus_spi.h"
37 #include "drivers/io.h"
38 #include "drivers/io_impl.h"
39 #include "drivers/nvic.h"
40 #include "drivers/rx/rx_sx127x.h"
41 #include "drivers/rx/rx_spi.h"
42 #include "drivers/time.h"
44 static const uint8_t sx127xAllowedSyncwords
[105] =
45 {0, 5, 6, 7, 11, 12, 13, 15, 18,
46 21, 23, 26, 29, 30, 31, 33, 34,
47 37, 38, 39, 40, 42, 44, 50, 51,
48 54, 55, 57, 58, 59, 61, 63, 65,
49 67, 68, 71, 77, 78, 79, 80, 82,
50 84, 86, 89, 92, 94, 96, 97, 99,
51 101, 102, 105, 106, 109, 111, 113, 115,
52 117, 118, 119, 121, 122, 124, 126, 127,
53 129, 130, 138, 143, 161, 170, 172, 173,
54 175, 180, 181, 182, 187, 190, 191, 192,
55 193, 196, 199, 201, 204, 205, 208, 209,
56 212, 213, 219, 220, 221, 223, 227, 229,
57 235, 239, 240, 242, 243, 246, 247, 255};
59 static bool sx127xDetectChip(void)
62 bool flagFound
= false;
63 while ((i
< 3) && !flagFound
) {
64 uint8_t version
= sx127xReadRegister(SX127X_REG_VERSION
);
65 if (version
== 0x12) {
73 sx127xSetRegisterValue(SX127X_REG_OP_MODE
, SX127x_OPMODE_SLEEP
, 2, 0);
77 uint8_t sx127xISR(timeUs_t
*timeStamp
)
79 timeUs_t extiTimestamp
= rxSpiGetLastExtiTimeUs();
83 uint8_t irqReason
= sx127xGetIrqReason();
85 *timeStamp
= extiTimestamp
;
91 bool sx127xInit(IO_t resetPin
, IO_t busyPin
)
95 if (!rxSpiExtiConfigured()) {
100 IOInit(resetPin
, OWNER_RX_SPI_EXPRESSLRS_RESET
, 0);
101 IOConfigGPIO(resetPin
, IOCFG_OUT_PP
);
108 IOConfigGPIO(resetPin
, IOCFG_IN_FLOATING
); // leave floating
110 return sx127xDetectChip();
113 void sx127xWriteRegister(const uint8_t address
, const uint8_t data
)
115 rxSpiWriteCommand(address
| SX127x_SPI_WRITE
, data
);
118 void sx127xWriteRegisterBurst(const uint8_t address
, const uint8_t *data
, const uint8_t length
)
120 rxSpiWriteCommandMulti(address
| SX127x_SPI_WRITE
, &data
[0], length
);
123 uint8_t sx127xReadRegister(const uint8_t address
)
125 return rxSpiReadCommand(address
| SX127x_SPI_READ
, 0xFF);
128 void sx127xReadRegisterBurst(const uint8_t address
, uint8_t data
[], const uint8_t length
)
130 rxSpiReadCommandMulti(address
| SX127x_SPI_READ
, 0xFF, &data
[0], length
);
133 uint8_t sx127xGetRegisterValue(const uint8_t reg
, const uint8_t msb
, const uint8_t lsb
)
135 if ((msb
> 7) || (lsb
> 7) || (lsb
> msb
)) {
136 return (SX127x_ERR_INVALID_BIT_RANGE
);
138 uint8_t rawValue
= sx127xReadRegister(reg
);
139 return rawValue
& ((0xFF << lsb
) & (0xFF >> (7 - msb
)));
142 uint8_t sx127xSetRegisterValue(const uint8_t reg
, const uint8_t value
, const uint8_t msb
, const uint8_t lsb
)
144 if ((msb
> 7) || (lsb
> 7) || (lsb
> msb
)) {
145 return (SX127x_ERR_INVALID_BIT_RANGE
);
148 uint8_t currentValue
= sx127xReadRegister(reg
);
149 uint8_t mask
= ~((0xFF << (msb
+ 1)) | (0xFF >> (8 - lsb
)));
150 uint8_t newValue
= (currentValue
& ~mask
) | (value
& mask
);
151 sx127xWriteRegister(reg
, newValue
);
152 return (SX127x_ERR_NONE
);
155 void sx127xReadRegisterFIFO(uint8_t data
[], const uint8_t length
)
157 sx127xReadRegisterBurst(SX127X_REG_FIFO
, data
, length
);
160 void sx127xWriteRegisterFIFO(const uint8_t *data
, const uint8_t length
)
162 sx127xWriteRegisterBurst(SX127X_REG_FIFO
, data
, length
);
165 void sx127xSetBandwidthCodingRate(const sx127xBandwidth_e bw
, const sx127xCodingRate_e cr
, const sx127xSpreadingFactor_e sf
, const bool headerExplMode
, const bool crcEnabled
)
167 if (sf
== SX127x_SF_6
) { // set SF6 optimizations
168 sx127xWriteRegister(SX127X_REG_MODEM_CONFIG_1
, bw
| cr
| SX1278_HEADER_IMPL_MODE
);
169 sx127xSetRegisterValue(SX127X_REG_MODEM_CONFIG_2
, SX1278_RX_CRC_MODE_OFF
, 2, 2);
171 if (headerExplMode
) {
172 sx127xWriteRegister(SX127X_REG_MODEM_CONFIG_1
, bw
| cr
| SX1278_HEADER_EXPL_MODE
);
174 sx127xWriteRegister(SX127X_REG_MODEM_CONFIG_1
, bw
| cr
| SX1278_HEADER_IMPL_MODE
);
178 sx127xSetRegisterValue(SX127X_REG_MODEM_CONFIG_2
, SX1278_RX_CRC_MODE_ON
, 2, 2);
180 sx127xSetRegisterValue(SX127X_REG_MODEM_CONFIG_2
, SX1278_RX_CRC_MODE_OFF
, 2, 2);
184 if (bw
== SX127x_BW_500_00_KHZ
) {
185 //datasheet errata recommendation http://caxapa.ru/thumbs/972894/SX1276_77_8_ErrataNote_1.1_STD.pdf
186 sx127xWriteRegister(0x36, 0x02);
187 sx127xWriteRegister(0x3a, 0x64);
189 sx127xWriteRegister(0x36, 0x03);
193 static bool sx127xSyncWordOk(const uint8_t syncWord
)
195 for (unsigned int i
= 0; i
< sizeof(sx127xAllowedSyncwords
); i
++) {
196 if (syncWord
== sx127xAllowedSyncwords
[i
]) {
203 void sx127xSetSyncWord(uint8_t syncWord
)
205 while (sx127xSyncWordOk(syncWord
) == false) {
209 sx127xWriteRegister(SX127X_REG_SYNC_WORD
, syncWord
); //TODO: possible bug in original code
212 void sx127xSetMode(const sx127xRadioOpMode_e mode
)
214 sx127xWriteRegister(SX127x_OPMODE_LORA
| SX127X_REG_OP_MODE
, mode
);
217 void sx127xSetOutputPower(const uint8_t power
)
219 sx127xSetMode(SX127x_OPMODE_STANDBY
);
220 sx127xWriteRegister(SX127X_REG_PA_CONFIG
, SX127X_PA_SELECT_BOOST
| SX127X_MAX_OUTPUT_POWER
| power
);
223 void sx127xSetPreambleLength(const uint8_t preambleLen
)
225 sx127xWriteRegister(SX127X_REG_PREAMBLE_LSB
, preambleLen
);
228 void sx127xSetSpreadingFactor(const sx127xSpreadingFactor_e sf
)
230 sx127xSetRegisterValue(SX127X_REG_MODEM_CONFIG_2
, sf
| SX127X_TX_MODE_SINGLE
, 7, 3);
231 if (sf
== SX127x_SF_6
) {
232 sx127xSetRegisterValue(SX127X_REG_DETECT_OPTIMIZE
, SX127X_DETECT_OPTIMIZE_SF_6
, 2, 0);
233 sx127xWriteRegister(SX127X_REG_DETECTION_THRESHOLD
, SX127X_DETECTION_THRESHOLD_SF_6
);
235 sx127xSetRegisterValue(SX127X_REG_DETECT_OPTIMIZE
, SX127X_DETECT_OPTIMIZE_SF_7_12
, 2, 0);
236 sx127xWriteRegister(SX127X_REG_DETECTION_THRESHOLD
, SX127X_DETECTION_THRESHOLD_SF_7_12
);
240 void sx127xSetFrequencyHZ(const uint32_t freq
)
242 sx127xSetMode(SX127x_OPMODE_STANDBY
);
244 int32_t FRQ
= ((uint32_t)(freq
/ SX127x_FREQ_STEP
));
246 uint8_t FRQ_MSB
= (uint8_t)((FRQ
>> 16) & 0xFF);
247 uint8_t FRQ_MID
= (uint8_t)((FRQ
>> 8) & 0xFF);
248 uint8_t FRQ_LSB
= (uint8_t)(FRQ
& 0xFF);
250 uint8_t outbuff
[3] = {FRQ_MSB
, FRQ_MID
, FRQ_LSB
};
252 sx127xWriteRegisterBurst(SX127X_REG_FRF_MSB
, outbuff
, sizeof(outbuff
));
255 void sx127xSetFrequencyReg(const uint32_t freq
)
257 sx127xSetMode(SX127x_OPMODE_STANDBY
);
259 uint8_t FRQ_MSB
= (uint8_t)((freq
>> 16) & 0xFF);
260 uint8_t FRQ_MID
= (uint8_t)((freq
>> 8) & 0xFF);
261 uint8_t FRQ_LSB
= (uint8_t)(freq
& 0xFF);
263 uint8_t outbuff
[3] = {FRQ_MSB
, FRQ_MID
, FRQ_LSB
}; //check speedup
265 sx127xWriteRegisterBurst(SX127X_REG_FRF_MSB
, outbuff
, sizeof(outbuff
));
268 void sx127xTransmitData(const uint8_t *data
, const uint8_t length
)
270 sx127xSetMode(SX127x_OPMODE_STANDBY
);
272 sx127xWriteRegister(SX127X_REG_FIFO_ADDR_PTR
, SX127X_FIFO_TX_BASE_ADDR_MAX
);
273 sx127xWriteRegisterFIFO(data
, length
);
275 sx127xSetMode(SX127x_OPMODE_TX
);
278 void sx127xReceiveData(uint8_t *data
, const uint8_t length
)
280 sx127xReadRegisterFIFO(data
, length
);
283 void sx127xStartReceiving(void)
285 sx127xSetMode(SX127x_OPMODE_STANDBY
);
286 sx127xWriteRegister(SX127X_REG_FIFO_ADDR_PTR
, SX127X_FIFO_RX_BASE_ADDR_MAX
);
287 sx127xSetMode(SX127x_OPMODE_RXCONTINUOUS
);
290 void sx127xConfig(const sx127xBandwidth_e bw
, const sx127xSpreadingFactor_e sf
, const sx127xCodingRate_e cr
,
291 const uint32_t freq
, const uint8_t preambleLen
, const bool iqInverted
)
293 sx127xConfigLoraDefaults(iqInverted
);
294 sx127xSetPreambleLength(preambleLen
);
295 sx127xSetOutputPower(SX127x_MAX_POWER
);
296 sx127xSetSpreadingFactor(sf
);
297 sx127xSetBandwidthCodingRate(bw
, cr
, sf
, false, false);
298 sx127xSetFrequencyReg(freq
);
301 uint32_t sx127xGetCurrBandwidth(const sx127xBandwidth_e bw
)
304 case SX127x_BW_7_80_KHZ
:
306 case SX127x_BW_10_40_KHZ
:
308 case SX127x_BW_15_60_KHZ
:
310 case SX127x_BW_20_80_KHZ
:
312 case SX127x_BW_31_25_KHZ
:
314 case SX127x_BW_41_70_KHZ
:
316 case SX127x_BW_62_50_KHZ
:
318 case SX127x_BW_125_00_KHZ
:
320 case SX127x_BW_250_00_KHZ
:
322 case SX127x_BW_500_00_KHZ
:
328 // this is basically just used for speedier calc of the freq offset, pre compiled for 32mhz xtal
329 uint32_t sx127xGetCurrBandwidthNormalisedShifted(const sx127xBandwidth_e bw
)
332 case SX127x_BW_7_80_KHZ
:
334 case SX127x_BW_10_40_KHZ
:
336 case SX127x_BW_15_60_KHZ
:
338 case SX127x_BW_20_80_KHZ
:
340 case SX127x_BW_31_25_KHZ
:
342 case SX127x_BW_41_70_KHZ
:
344 case SX127x_BW_62_50_KHZ
:
346 case SX127x_BW_125_00_KHZ
:
348 case SX127x_BW_250_00_KHZ
:
350 case SX127x_BW_500_00_KHZ
:
356 void sx127xSetPPMoffsetReg(const int32_t offset
, const uint32_t freq
)
358 int8_t offsetPPM
= (offset
* 1e6
/ freq
) * 95 / 100;
359 sx127xWriteRegister(SX127x_PPMOFFSET
, (uint8_t) offsetPPM
);
362 static bool sx127xGetFrequencyErrorbool(void)
364 return (sx127xReadRegister(SX127X_REG_FEI_MSB
) & 0x08) >> 3; // returns true if pos freq error, neg if false
367 int32_t sx127xGetFrequencyError(const sx127xBandwidth_e bw
)
369 uint8_t reg
[3] = {0x0, 0x0, 0x0};
370 sx127xReadRegisterBurst(SX127X_REG_FEI_MSB
, reg
, sizeof(reg
));
372 uint32_t regFei
= ((reg
[0] & 0x07) << 16) + (reg
[1] << 8) + reg
[2];
374 int32_t intFreqError
= regFei
;
376 if ((reg
[0] & 0x08) >> 3) {
377 intFreqError
-= 524288; // Sign bit is on
380 // 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
381 int32_t fErrorHZ
= (intFreqError
>> 3) * (sx127xGetCurrBandwidthNormalisedShifted(bw
));
387 void sx127xAdjustFrequency(int32_t offset
, const uint32_t freq
)
389 if (sx127xGetFrequencyErrorbool()) { //logic is flipped compared to original code
390 if (offset
> SX127x_FREQ_CORRECTION_MIN
) {
393 offset
= 0; //reset because something went wrong
396 if (offset
< SX127x_FREQ_CORRECTION_MAX
) {
399 offset
= 0; //reset because something went wrong
402 sx127xSetPPMoffsetReg(offset
, freq
); //as above but corrects a different PPM offset based on freq error
405 uint8_t sx127xUnsignedGetLastPacketRSSI(void)
407 return sx127xGetRegisterValue(SX127X_REG_PKT_RSSI_VALUE
, 7, 0);
410 int8_t sx127xGetLastPacketRSSI(void)
412 return (-157 + sx127xGetRegisterValue(SX127X_REG_PKT_RSSI_VALUE
, 7, 0));
415 int8_t sx127xGetCurrRSSI(void)
417 return (-157 + sx127xGetRegisterValue(SX127X_REG_RSSI_VALUE
, 7, 0));
420 int8_t sx127xGetLastPacketSNRRaw(void)
422 return (int8_t)sx127xGetRegisterValue(SX127X_REG_PKT_SNR_VALUE
, 7, 0);
425 void sx127xGetLastPacketStats(int8_t *rssi
, int8_t *snr
)
427 *rssi
= sx127xGetLastPacketRSSI();
428 *snr
= sx127xGetLastPacketSNRRaw();
429 int8_t negOffset
= (*snr
< 0) ? (*snr
/ 4) : 0;
433 uint8_t sx127xGetIrqFlags(void)
435 return sx127xGetRegisterValue(SX127X_REG_IRQ_FLAGS
, 7, 0);
438 void sx127xClearIrqFlags(void)
440 sx127xWriteRegister(SX127X_REG_IRQ_FLAGS
, 0xFF);
443 uint8_t sx127xGetIrqReason(void)
445 uint8_t irqFlags
= sx127xGetIrqFlags();
446 sx127xClearIrqFlags();
447 if ((irqFlags
& SX127X_CLEAR_IRQ_FLAG_TX_DONE
) && (irqFlags
& SX127X_CLEAR_IRQ_FLAG_RX_DONE
)) {
449 } else if ((irqFlags
& SX127X_CLEAR_IRQ_FLAG_TX_DONE
)) {
451 } else if ((irqFlags
& SX127X_CLEAR_IRQ_FLAG_RX_DONE
)) {
457 void sx127xConfigLoraDefaults(const bool iqInverted
)
459 sx127xWriteRegister(SX127X_REG_OP_MODE
, SX127x_OPMODE_SLEEP
);
460 sx127xWriteRegister(SX127X_REG_OP_MODE
, SX127x_OPMODE_LORA
); //must be written in sleep mode
461 sx127xSetMode(SX127x_OPMODE_STANDBY
);
463 sx127xClearIrqFlags();
465 sx127xWriteRegister(SX127X_REG_PAYLOAD_LENGTH
, 8);
466 sx127xSetSyncWord(SX127X_SYNC_WORD
);
467 sx127xWriteRegister(SX127X_REG_FIFO_TX_BASE_ADDR
, SX127X_FIFO_TX_BASE_ADDR_MAX
);
468 sx127xWriteRegister(SX127X_REG_FIFO_RX_BASE_ADDR
, SX127X_FIFO_RX_BASE_ADDR_MAX
);
469 sx127xSetRegisterValue(SX127X_REG_DIO_MAPPING_1
, 0xC0, 7, 6); //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.
470 sx127xWriteRegister(SX127X_REG_LNA
, SX127X_LNA_BOOST_ON
);
471 sx127xWriteRegister(SX1278_REG_MODEM_CONFIG_3
, SX1278_AGC_AUTO_ON
| SX1278_LOW_DATA_RATE_OPT_OFF
);
472 sx127xSetRegisterValue(SX127X_REG_OCP
, SX127X_OCP_ON
| SX127X_OCP_150MA
, 5, 0); //150ma max current
473 sx127xSetPreambleLength(SX127X_PREAMBLE_LENGTH_LSB
);
474 sx127xSetRegisterValue(SX127X_REG_INVERT_IQ
, (uint8_t)iqInverted
, 6, 6);
477 #endif /* USE_RX_SX127X */