Merge pull request #11494 from haslinghuis/dshot_gpio
[betaflight.git] / src / main / drivers / rx / rx_sx127x.c
blob99172191f7eb67a6c52626a9f3bf12e6dbe001b3
1 /*
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)
8 * any later version.
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.
26 #include <stdbool.h>
27 #include <stdint.h>
28 #include <stdlib.h>
30 #include "platform.h"
32 #ifdef USE_RX_SX127X
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)
61 uint8_t i = 0;
62 bool flagFound = false;
63 while ((i < 3) && !flagFound) {
64 uint8_t version = sx127xReadRegister(SX127X_REG_VERSION);
65 if (version == 0x12) {
66 flagFound = true;
67 } else {
68 delay(50);
69 i++;
73 sx127xSetRegisterValue(SX127X_REG_OP_MODE, SX127x_OPMODE_SLEEP, 2, 0);
74 return flagFound;
77 uint8_t sx127xISR(timeUs_t *timeStamp)
79 bool extiTriggered = false;
80 timeUs_t extiTimestamp;
82 ATOMIC_BLOCK(NVIC_PRIO_RX_SPI_INT_EXTI) {
83 // prevent a data-race that can occur if a new EXTI ISR occurs during this block.
84 extiTriggered = rxSpiPollExti();
85 extiTimestamp = rxSpiGetLastExtiTimeUs();
86 if (extiTriggered) {
87 rxSpiResetExti();
91 if (extiTriggered) {
92 uint8_t irqReason = sx127xGetIrqReason();
93 if (extiTimestamp) {
94 *timeStamp = extiTimestamp;
97 return irqReason;
99 return 0;
102 bool sx127xInit(IO_t resetPin, IO_t busyPin)
104 UNUSED(busyPin);
106 if (!rxSpiExtiConfigured()) {
107 return false;
110 if (resetPin) {
111 IOInit(resetPin, OWNER_RX_SPI_EXPRESSLRS_RESET, 0);
112 IOConfigGPIO(resetPin, IOCFG_OUT_PP);
113 } else {
114 resetPin = IO_NONE;
117 IOLo(resetPin);
118 delay(50);
119 IOConfigGPIO(resetPin, IOCFG_IN_FLOATING); // leave floating
121 return sx127xDetectChip();
124 void sx127xWriteRegister(const uint8_t address, const uint8_t data)
126 rxSpiWriteCommand(address | SX127x_SPI_WRITE, data);
129 void sx127xWriteRegisterBurst(const uint8_t address, const uint8_t *data, const uint8_t length)
131 rxSpiWriteCommandMulti(address | SX127x_SPI_WRITE, &data[0], length);
134 uint8_t sx127xReadRegister(const uint8_t address)
136 return rxSpiReadCommand(address | SX127x_SPI_READ, 0xFF);
139 void sx127xReadRegisterBurst(const uint8_t address, uint8_t data[], const uint8_t length)
141 rxSpiReadCommandMulti(address | SX127x_SPI_READ, 0xFF, &data[0], length);
144 uint8_t sx127xGetRegisterValue(const uint8_t reg, const uint8_t msb, const uint8_t lsb)
146 if ((msb > 7) || (lsb > 7) || (lsb > msb)) {
147 return (SX127x_ERR_INVALID_BIT_RANGE);
149 uint8_t rawValue = sx127xReadRegister(reg);
150 return rawValue & ((0xFF << lsb) & (0xFF >> (7 - msb)));
153 uint8_t sx127xSetRegisterValue(const uint8_t reg, const uint8_t value, const uint8_t msb, const uint8_t lsb)
155 if ((msb > 7) || (lsb > 7) || (lsb > msb)) {
156 return (SX127x_ERR_INVALID_BIT_RANGE);
159 uint8_t currentValue = sx127xReadRegister(reg);
160 uint8_t mask = ~((0xFF << (msb + 1)) | (0xFF >> (8 - lsb)));
161 uint8_t newValue = (currentValue & ~mask) | (value & mask);
162 sx127xWriteRegister(reg, newValue);
163 return (SX127x_ERR_NONE);
166 void sx127xReadRegisterFIFO(uint8_t data[], const uint8_t length)
168 sx127xReadRegisterBurst(SX127X_REG_FIFO, data, length);
171 void sx127xWriteRegisterFIFO(const uint8_t *data, const uint8_t length)
173 sx127xWriteRegisterBurst(SX127X_REG_FIFO, data, length);
176 void sx127xSetBandwidthCodingRate(const sx127xBandwidth_e bw, const sx127xCodingRate_e cr, const sx127xSpreadingFactor_e sf, const bool headerExplMode, const bool crcEnabled)
178 if (sf == SX127x_SF_6) { // set SF6 optimizations
179 sx127xWriteRegister(SX127X_REG_MODEM_CONFIG_1, bw | cr | SX1278_HEADER_IMPL_MODE);
180 sx127xSetRegisterValue(SX127X_REG_MODEM_CONFIG_2, SX1278_RX_CRC_MODE_OFF, 2, 2);
181 } else {
182 if (headerExplMode) {
183 sx127xWriteRegister(SX127X_REG_MODEM_CONFIG_1, bw | cr | SX1278_HEADER_EXPL_MODE);
184 } else {
185 sx127xWriteRegister(SX127X_REG_MODEM_CONFIG_1, bw | cr | SX1278_HEADER_IMPL_MODE);
188 if (crcEnabled) {
189 sx127xSetRegisterValue(SX127X_REG_MODEM_CONFIG_2, SX1278_RX_CRC_MODE_ON, 2, 2);
190 } else {
191 sx127xSetRegisterValue(SX127X_REG_MODEM_CONFIG_2, SX1278_RX_CRC_MODE_OFF, 2, 2);
195 if (bw == SX127x_BW_500_00_KHZ) {
196 //datasheet errata recommendation http://caxapa.ru/thumbs/972894/SX1276_77_8_ErrataNote_1.1_STD.pdf
197 sx127xWriteRegister(0x36, 0x02);
198 sx127xWriteRegister(0x3a, 0x64);
199 } else {
200 sx127xWriteRegister(0x36, 0x03);
204 static bool sx127xSyncWordOk(const uint8_t syncWord)
206 for (unsigned int i = 0; i < sizeof(sx127xAllowedSyncwords); i++) {
207 if (syncWord == sx127xAllowedSyncwords[i]) {
208 return true;
211 return false;
214 void sx127xSetSyncWord(uint8_t syncWord)
216 while (sx127xSyncWordOk(syncWord) == false) {
217 syncWord++;
220 sx127xWriteRegister(SX127X_REG_SYNC_WORD, syncWord); //TODO: possible bug in original code
223 void sx127xSetMode(const sx127xRadioOpMode_e mode)
225 sx127xWriteRegister(SX127x_OPMODE_LORA | SX127X_REG_OP_MODE, mode);
228 void sx127xSetOutputPower(const uint8_t power)
230 sx127xSetMode(SX127x_OPMODE_STANDBY);
231 sx127xWriteRegister(SX127X_REG_PA_CONFIG, SX127X_PA_SELECT_BOOST | SX127X_MAX_OUTPUT_POWER | power);
234 void sx127xSetPreambleLength(const uint8_t preambleLen)
236 sx127xWriteRegister(SX127X_REG_PREAMBLE_LSB, preambleLen);
239 void sx127xSetSpreadingFactor(const sx127xSpreadingFactor_e sf)
241 sx127xSetRegisterValue(SX127X_REG_MODEM_CONFIG_2, sf | SX127X_TX_MODE_SINGLE, 7, 3);
242 if (sf == SX127x_SF_6) {
243 sx127xSetRegisterValue(SX127X_REG_DETECT_OPTIMIZE, SX127X_DETECT_OPTIMIZE_SF_6, 2, 0);
244 sx127xWriteRegister(SX127X_REG_DETECTION_THRESHOLD, SX127X_DETECTION_THRESHOLD_SF_6);
245 } else {
246 sx127xSetRegisterValue(SX127X_REG_DETECT_OPTIMIZE, SX127X_DETECT_OPTIMIZE_SF_7_12, 2, 0);
247 sx127xWriteRegister(SX127X_REG_DETECTION_THRESHOLD, SX127X_DETECTION_THRESHOLD_SF_7_12);
251 void sx127xSetFrequencyHZ(const uint32_t freq)
253 sx127xSetMode(SX127x_OPMODE_STANDBY);
255 int32_t FRQ = ((uint32_t)(freq / SX127x_FREQ_STEP));
257 uint8_t FRQ_MSB = (uint8_t)((FRQ >> 16) & 0xFF);
258 uint8_t FRQ_MID = (uint8_t)((FRQ >> 8) & 0xFF);
259 uint8_t FRQ_LSB = (uint8_t)(FRQ & 0xFF);
261 uint8_t outbuff[3] = {FRQ_MSB, FRQ_MID, FRQ_LSB};
263 sx127xWriteRegisterBurst(SX127X_REG_FRF_MSB, outbuff, sizeof(outbuff));
266 void sx127xSetFrequencyReg(const uint32_t freq)
268 sx127xSetMode(SX127x_OPMODE_STANDBY);
270 uint8_t FRQ_MSB = (uint8_t)((freq >> 16) & 0xFF);
271 uint8_t FRQ_MID = (uint8_t)((freq >> 8) & 0xFF);
272 uint8_t FRQ_LSB = (uint8_t)(freq & 0xFF);
274 uint8_t outbuff[3] = {FRQ_MSB, FRQ_MID, FRQ_LSB}; //check speedup
276 sx127xWriteRegisterBurst(SX127X_REG_FRF_MSB, outbuff, sizeof(outbuff));
279 void sx127xTransmitData(const uint8_t *data, const uint8_t length)
281 sx127xSetMode(SX127x_OPMODE_STANDBY);
283 sx127xWriteRegister(SX127X_REG_FIFO_ADDR_PTR, SX127X_FIFO_TX_BASE_ADDR_MAX);
284 sx127xWriteRegisterFIFO(data, length);
286 sx127xSetMode(SX127x_OPMODE_TX);
289 void sx127xReceiveData(uint8_t *data, const uint8_t length)
291 sx127xReadRegisterFIFO(data, length);
294 void sx127xStartReceiving(void)
296 sx127xSetMode(SX127x_OPMODE_STANDBY);
297 sx127xWriteRegister(SX127X_REG_FIFO_ADDR_PTR, SX127X_FIFO_RX_BASE_ADDR_MAX);
298 sx127xSetMode(SX127x_OPMODE_RXCONTINUOUS);
301 void sx127xConfig(const sx127xBandwidth_e bw, const sx127xSpreadingFactor_e sf, const sx127xCodingRate_e cr,
302 const uint32_t freq, const uint8_t preambleLen, const bool iqInverted)
304 sx127xConfigLoraDefaults(iqInverted);
305 sx127xSetPreambleLength(preambleLen);
306 sx127xSetOutputPower(SX127x_MAX_POWER);
307 sx127xSetSpreadingFactor(sf);
308 sx127xSetBandwidthCodingRate(bw, cr, sf, false, false);
309 sx127xSetFrequencyReg(freq);
312 uint32_t sx127xGetCurrBandwidth(const sx127xBandwidth_e bw)
314 switch (bw) {
315 case SX127x_BW_7_80_KHZ:
316 return 7.8E3;
317 case SX127x_BW_10_40_KHZ:
318 return 10.4E3;
319 case SX127x_BW_15_60_KHZ:
320 return 15.6E3;
321 case SX127x_BW_20_80_KHZ:
322 return 20.8E3;
323 case SX127x_BW_31_25_KHZ:
324 return 31.25E3;
325 case SX127x_BW_41_70_KHZ:
326 return 41.7E3;
327 case SX127x_BW_62_50_KHZ:
328 return 62.5E3;
329 case SX127x_BW_125_00_KHZ:
330 return 125E3;
331 case SX127x_BW_250_00_KHZ:
332 return 250E3;
333 case SX127x_BW_500_00_KHZ:
334 return 500E3;
336 return -1;
339 // this is basically just used for speedier calc of the freq offset, pre compiled for 32mhz xtal
340 uint32_t sx127xGetCurrBandwidthNormalisedShifted(const sx127xBandwidth_e bw)
342 switch (bw) {
343 case SX127x_BW_7_80_KHZ:
344 return 1026;
345 case SX127x_BW_10_40_KHZ:
346 return 769;
347 case SX127x_BW_15_60_KHZ:
348 return 513;
349 case SX127x_BW_20_80_KHZ:
350 return 385;
351 case SX127x_BW_31_25_KHZ:
352 return 256;
353 case SX127x_BW_41_70_KHZ:
354 return 192;
355 case SX127x_BW_62_50_KHZ:
356 return 128;
357 case SX127x_BW_125_00_KHZ:
358 return 64;
359 case SX127x_BW_250_00_KHZ:
360 return 32;
361 case SX127x_BW_500_00_KHZ:
362 return 16;
364 return -1;
367 void sx127xSetPPMoffsetReg(const int32_t offset, const uint32_t freq)
369 int8_t offsetPPM = (offset * 1e6 / freq) * 95 / 100;
370 sx127xWriteRegister(SX127x_PPMOFFSET, (uint8_t) offsetPPM);
373 static bool sx127xGetFrequencyErrorbool(void)
375 return (sx127xReadRegister(SX127X_REG_FEI_MSB) & 0x08) >> 3; // returns true if pos freq error, neg if false
378 int32_t sx127xGetFrequencyError(const sx127xBandwidth_e bw)
380 uint8_t reg[3] = {0x0, 0x0, 0x0};
381 sx127xReadRegisterBurst(SX127X_REG_FEI_MSB, reg, sizeof(reg));
383 uint32_t regFei = ((reg[0] & 0x07) << 16) + (reg[1] << 8) + reg[2];
385 int32_t intFreqError = regFei;
387 if ((reg[0] & 0x08) >> 3) {
388 intFreqError -= 524288; // Sign bit is on
391 // 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
392 int32_t fErrorHZ = (intFreqError >> 3) * (sx127xGetCurrBandwidthNormalisedShifted(bw));
393 fErrorHZ >>= 4;
395 return fErrorHZ;
398 void sx127xAdjustFrequency(int32_t offset, const uint32_t freq)
400 if (sx127xGetFrequencyErrorbool()) { //logic is flipped compared to original code
401 if (offset > SX127x_FREQ_CORRECTION_MIN) {
402 offset -= 1;
403 } else {
404 offset = 0; //reset because something went wrong
406 } else {
407 if (offset < SX127x_FREQ_CORRECTION_MAX) {
408 offset += 1;
409 } else {
410 offset = 0; //reset because something went wrong
413 sx127xSetPPMoffsetReg(offset, freq); //as above but corrects a different PPM offset based on freq error
416 uint8_t sx127xUnsignedGetLastPacketRSSI(void)
418 return sx127xGetRegisterValue(SX127X_REG_PKT_RSSI_VALUE, 7, 0);
421 int8_t sx127xGetLastPacketRSSI(void)
423 return (-157 + sx127xGetRegisterValue(SX127X_REG_PKT_RSSI_VALUE, 7, 0));
426 int8_t sx127xGetCurrRSSI(void)
428 return (-157 + sx127xGetRegisterValue(SX127X_REG_RSSI_VALUE, 7, 0));
431 int8_t sx127xGetLastPacketSNR(void)
433 int8_t rawSNR = (int8_t)sx127xGetRegisterValue(SX127X_REG_PKT_SNR_VALUE, 7, 0);
434 return (rawSNR / 4);
437 void sx127xGetLastPacketStats(int8_t *rssi, int8_t *snr)
439 *rssi = sx127xGetLastPacketRSSI();
440 *snr = sx127xGetLastPacketSNR();
441 int8_t negOffset = (*snr < 0) ? *snr : 0;
442 *rssi += negOffset;
445 uint8_t sx127xGetIrqFlags(void)
447 return sx127xGetRegisterValue(SX127X_REG_IRQ_FLAGS, 7, 0);
450 void sx127xClearIrqFlags(void)
452 sx127xWriteRegister(SX127X_REG_IRQ_FLAGS, 0xFF);
455 uint8_t sx127xGetIrqReason(void)
457 uint8_t irqFlags = sx127xGetIrqFlags();
458 sx127xClearIrqFlags();
459 if ((irqFlags & SX127X_CLEAR_IRQ_FLAG_TX_DONE) && (irqFlags & SX127X_CLEAR_IRQ_FLAG_RX_DONE)) {
460 return 3;
461 } else if ((irqFlags & SX127X_CLEAR_IRQ_FLAG_TX_DONE)) {
462 return 2;
463 } else if ((irqFlags & SX127X_CLEAR_IRQ_FLAG_RX_DONE)) {
464 return 1;
466 return 0;
469 void sx127xConfigLoraDefaults(const bool iqInverted)
471 sx127xWriteRegister(SX127X_REG_OP_MODE, SX127x_OPMODE_SLEEP);
472 sx127xWriteRegister(SX127X_REG_OP_MODE, SX127x_OPMODE_LORA); //must be written in sleep mode
473 sx127xSetMode(SX127x_OPMODE_STANDBY);
475 sx127xClearIrqFlags();
477 sx127xWriteRegister(SX127X_REG_PAYLOAD_LENGTH, 8);
478 sx127xSetSyncWord(SX127X_SYNC_WORD);
479 sx127xWriteRegister(SX127X_REG_FIFO_TX_BASE_ADDR, SX127X_FIFO_TX_BASE_ADDR_MAX);
480 sx127xWriteRegister(SX127X_REG_FIFO_RX_BASE_ADDR, SX127X_FIFO_RX_BASE_ADDR_MAX);
481 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.
482 sx127xWriteRegister(SX127X_REG_LNA, SX127X_LNA_BOOST_ON);
483 sx127xWriteRegister(SX1278_REG_MODEM_CONFIG_3, SX1278_AGC_AUTO_ON | SX1278_LOW_DATA_RATE_OPT_OFF);
484 sx127xSetRegisterValue(SX127X_REG_OCP, SX127X_OCP_ON | SX127X_OCP_150MA, 5, 0); //150ma max current
485 sx127xSetPreambleLength(SX127X_PREAMBLE_LENGTH_LSB);
486 sx127xSetRegisterValue(SX127X_REG_INVERT_IQ, (uint8_t)iqInverted, 6, 6);
489 #endif /* USE_RX_SX127X */