./src/utils/ trim trailing whitestpaces (#14082)
[betaflight.git] / src / main / drivers / rx / rx_sx127x.h
blob0a0921657c4701064ebef104eb1e0f36e09794c1
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 #pragma once
28 //SX127x_ModulationModes
29 typedef enum {
30 SX127x_OPMODE_FSK_OOK = 0x00,
31 SX127x_OPMODE_LORA = 0x80,
32 SX127X_ACCESS_SHARED_REG_OFF = 0x00,
33 SX127X_ACCESS_SHARED_REG_ON = 0x40,
34 } sx127xModulationMode_e;
36 //SX127x_RadioOPmodes
37 typedef enum {
38 SX127x_OPMODE_SLEEP = 0x00,
39 SX127x_OPMODE_STANDBY = 0x01,
40 SX127x_OPMODE_FSTX = 0x02,
41 SX127x_OPMODE_TX = 0x03,
42 SX127x_OPMODE_FSRX = 0x04,
43 SX127x_OPMODE_RXCONTINUOUS = 0x05,
44 SX127x_OPMODE_RXSINGLE = 0x06,
45 SX127x_OPMODE_CAD = 0x07,
46 } sx127xRadioOpMode_e;
48 //SX127x_Bandwidth
49 typedef enum {
50 SX127x_BW_7_80_KHZ = 0x00,
51 SX127x_BW_10_40_KHZ = 0x10,
52 SX127x_BW_15_60_KHZ = 0x20,
53 SX127x_BW_20_80_KHZ = 0x30,
54 SX127x_BW_31_25_KHZ = 0x40,
55 SX127x_BW_41_70_KHZ = 0x50,
56 SX127x_BW_62_50_KHZ = 0x60,
57 SX127x_BW_125_00_KHZ = 0x70,
58 SX127x_BW_250_00_KHZ = 0x80,
59 SX127x_BW_500_00_KHZ = 0x90,
60 } sx127xBandwidth_e;
62 //SX127x_SpreadingFactor
63 typedef enum {
64 SX127x_SF_6 = 0x60,
65 SX127x_SF_7 = 0x70,
66 SX127x_SF_8 = 0x80,
67 SX127x_SF_9 = 0x90,
68 SX127x_SF_10 = 0xA0,
69 SX127x_SF_11 = 0xB0,
70 SX127x_SF_12 = 0xC0,
71 } sx127xSpreadingFactor_e;
73 //SX127x_CodingRate
74 typedef enum {
75 SX127x_CR_4_5 = 0x02,
76 SX127x_CR_4_6 = 0x04,
77 SX127x_CR_4_7 = 0x06,
78 SX127x_CR_4_8 = 0x08,
79 } sx127xCodingRate_e;
81 // SX127x series common registers
82 #define SX127X_REG_FIFO 0x00
83 #define SX127X_REG_OP_MODE 0x01
84 #define SX127X_REG_FRF_MSB 0x06
85 #define SX127X_REG_FRF_MID 0x07
86 #define SX127X_REG_FRF_LSB 0x08
87 #define SX127X_REG_PA_CONFIG 0x09
88 #define SX127X_REG_PA_RAMP 0x0A
89 #define SX127X_REG_OCP 0x0B
90 #define SX127X_REG_LNA 0x0C
91 #define SX127X_REG_FIFO_ADDR_PTR 0x0D
92 #define SX127X_REG_FIFO_TX_BASE_ADDR 0x0E
93 #define SX127X_REG_FIFO_RX_BASE_ADDR 0x0F
94 #define SX127X_REG_FIFO_RX_CURRENT_ADDR 0x10
95 #define SX127X_REG_IRQ_FLAGS_MASK 0x11
96 #define SX127X_REG_IRQ_FLAGS 0x12
97 #define SX127X_REG_RX_NB_BYTES 0x13
98 #define SX127X_REG_RX_HEADER_CNT_VALUE_MSB 0x14
99 #define SX127X_REG_RX_HEADER_CNT_VALUE_LSB 0x15
100 #define SX127X_REG_RX_PACKET_CNT_VALUE_MSB 0x16
101 #define SX127X_REG_RX_PACKET_CNT_VALUE_LSB 0x17
102 #define SX127X_REG_MODEM_STAT 0x18
103 #define SX127X_REG_PKT_SNR_VALUE 0x19
104 #define SX127X_REG_PKT_RSSI_VALUE 0x1A
105 #define SX127X_REG_RSSI_VALUE 0x1B
106 #define SX127X_REG_HOP_CHANNEL 0x1C
107 #define SX127X_REG_MODEM_CONFIG_1 0x1D
108 #define SX127X_REG_MODEM_CONFIG_2 0x1E
109 #define SX127X_REG_SYMB_TIMEOUT_LSB 0x1F
110 #define SX127X_REG_PREAMBLE_MSB 0x20
111 #define SX127X_REG_PREAMBLE_LSB 0x21
112 #define SX127X_REG_PAYLOAD_LENGTH 0x22
113 #define SX127X_REG_MAX_PAYLOAD_LENGTH 0x23
114 #define SX127X_REG_HOP_PERIOD 0x24
115 #define SX127X_REG_FIFO_RX_BYTE_ADDR 0x25
116 #define SX127X_REG_FEI_MSB 0x28
117 #define SX127X_REG_FEI_MID 0x29
118 #define SX127X_REG_FEI_LSB 0x2A
119 #define SX127X_REG_RSSI_WIDEBAND 0x2C
120 #define SX127X_REG_DETECT_OPTIMIZE 0x31
121 #define SX127X_REG_INVERT_IQ 0x33
122 #define SX127X_REG_DETECTION_THRESHOLD 0x37
123 #define SX127X_REG_SYNC_WORD 0x39
124 #define SX127X_REG_DIO_MAPPING_1 0x40
125 #define SX127X_REG_DIO_MAPPING_2 0x41
126 #define SX127X_REG_VERSION 0x42
128 // SX127X_REG_PA_CONFIG
129 #define SX127X_PA_SELECT_RFO 0x00 // 7 7 RFO pin output, power limited to +14 dBm
130 #define SX127X_PA_SELECT_BOOST 0x80 // 7 7 PA_BOOST pin output, power limited to +20 dBm
131 #define SX127X_OUTPUT_POWER 0x0F // 3 0 output power: P_out = 17 - (15 - OUTPUT_POWER) [dBm] for PA_SELECT_BOOST
132 #define SX127X_MAX_OUTPUT_POWER 0x70 // Enable max output power
134 // SX127X_REG_OCP
135 #define SX127X_OCP_OFF 0x00 // 5 5 PA overload current protection disabled
136 #define SX127X_OCP_ON 0x20 // 5 5 PA overload current protection enabled
137 #define SX127X_OCP_TRIM 0x0B // 4 0 OCP current: I_max(OCP_TRIM = 0b1011) = 100 mA
138 #define SX127X_OCP_150MA 0x12 // 4 0 OCP current: I_max(OCP_TRIM = 10010) = 150 mA
140 // SX127X_REG_LNA
141 #define SX127X_LNA_GAIN_0 0x00 // 7 5 LNA gain setting: not used
142 #define SX127X_LNA_GAIN_1 0x20 // 7 5 max gain
143 #define SX127X_LNA_GAIN_2 0x40 // 7 5 .
144 #define SX127X_LNA_GAIN_3 0x60 // 7 5 .
145 #define SX127X_LNA_GAIN_4 0x80 // 7 5 .
146 #define SX127X_LNA_GAIN_5 0xA0 // 7 5 .
147 #define SX127X_LNA_GAIN_6 0xC0 // 7 5 min gain
148 #define SX127X_LNA_GAIN_7 0xE0 // 7 5 not used
149 #define SX127X_LNA_BOOST_OFF 0x00 // 1 0 default LNA current
150 #define SX127X_LNA_BOOST_ON 0x03 // 1 0 150% LNA current
152 #define SX127X_TX_MODE_SINGLE 0x00 // 3 3 single TX
153 #define SX127X_TX_MODE_CONT 0x08 // 3 3 continuous TX
154 #define SX127X_RX_TIMEOUT_MSB 0x00 // 1 0
156 // SX127X_REG_SYMB_TIMEOUT_LSB
157 #define SX127X_RX_TIMEOUT_LSB 0x64 // 7 0 10 bit RX operation timeout
159 // SX127X_REG_PREAMBLE_MSB + REG_PREAMBLE_LSB
160 #define SX127X_PREAMBLE_LENGTH_MSB 0x00 // 7 0 2 byte preamble length setting: l_P = PREAMBLE_LENGTH + 4.25
161 #define SX127X_PREAMBLE_LENGTH_LSB 0x08 // 7 0 where l_p = preamble length
162 //#define SX127X_PREAMBLE_LENGTH_LSB 0x04 // 7 0 where l_p = preamble length //CHANGED
164 // SX127X_REG_DETECT_OPTIMIZE
165 #define SX127X_DETECT_OPTIMIZE_SF_6 0x05 // 2 0 SF6 detection optimization
166 #define SX127X_DETECT_OPTIMIZE_SF_7_12 0x03 // 2 0 SF7 to SF12 detection optimization
168 // SX127X_REG_DETECTION_THRESHOLD
169 #define SX127X_DETECTION_THRESHOLD_SF_6 0x0C // 7 0 SF6 detection threshold
170 #define SX127X_DETECTION_THRESHOLD_SF_7_12 0x0A // 7 0 SF7 to SF12 detection threshold
172 // SX127X_REG_PA_DAC
173 #define SX127X_PA_BOOST_OFF 0x04 // 2 0 PA_BOOST disabled
174 #define SX127X_PA_BOOST_ON 0x07 // 2 0 +20 dBm on PA_BOOST when OUTPUT_POWER = 0b1111
176 // SX127X_REG_HOP_PERIOD
177 #define SX127X_HOP_PERIOD_OFF 0x00 // 7 0 number of periods between frequency hops; 0 = disabled
178 #define SX127X_HOP_PERIOD_MAX 0xFF // 7 0
180 // SX127X_REG_DIO_MAPPING_1
181 #define SX127X_DIO0_RX_DONE 0x00 // 7 6
182 #define SX127X_DIO0_TX_DONE 0x40 // 7 6
183 #define SX127X_DIO0_CAD_DONE 0x80 // 7 6
184 #define SX127X_DIO1_RX_TIMEOUT 0x00 // 5 4
185 #define SX127X_DIO1_FHSS_CHANGE_CHANNEL 0x10 // 5 4
186 #define SX127X_DIO1_CAD_DETECTED 0x20 // 5 4
188 // SX127X_REG_IRQ_FLAGS
189 #define SX127X_CLEAR_IRQ_FLAG_RX_TIMEOUT 0x80 // 7 7 timeout
190 #define SX127X_CLEAR_IRQ_FLAG_RX_DONE 0x40 // 6 6 packet reception complete
191 #define SX127X_CLEAR_IRQ_FLAG_PAYLOAD_CRC_ERROR 0x20 // 5 5 payload CRC error
192 #define SX127X_CLEAR_IRQ_FLAG_VALID_HEADER 0x10 // 4 4 valid header received
193 #define SX127X_CLEAR_IRQ_FLAG_TX_DONE 0x08 // 3 3 payload transmission complete
194 #define SX127X_CLEAR_IRQ_FLAG_CAD_DONE 0x04 // 2 2 CAD complete
195 #define SX127X_CLEAR_IRQ_FLAG_FHSS_CHANGE_CHANNEL 0x02 // 1 1 FHSS change channel
196 #define SX127X_CLEAR_IRQ_FLAG_CAD_DETECTED 0x01 // 0 0 valid LoRa signal detected during CAD operation
198 // SX127X_REG_IRQ_FLAGS_MASK
199 #define SX127X_MASK_IRQ_FLAG_RX_TIMEOUT 0x7F // 7 7 timeout
200 #define SX127X_MASK_IRQ_FLAG_RX_DONE 0xBF // 6 6 packet reception complete
201 #define SX127X_MASK_IRQ_FLAG_PAYLOAD_CRC_ERROR 0xDF // 5 5 payload CRC error
202 #define SX127X_MASK_IRQ_FLAG_VALID_HEADER 0xEF // 4 4 valid header received
203 #define SX127X_MASK_IRQ_FLAG_TX_DONE 0xF7 // 3 3 payload transmission complete
204 #define SX127X_MASK_IRQ_FLAG_CAD_DONE 0xFB // 2 2 CAD complete
205 #define SX127X_MASK_IRQ_FLAG_FHSS_CHANGE_CHANNEL 0xFD // 1 1 FHSS change channel
206 #define SX127X_MASK_IRQ_FLAG_CAD_DETECTED 0xFE // 0 0 valid LoRa signal detected during CAD operation
208 // SX127X_REG_FIFO_TX_BASE_ADDR
209 #define SX127X_FIFO_TX_BASE_ADDR_MAX 0x00 // 7 0 allocate the entire FIFO buffer for TX only
211 // SX127X_REG_FIFO_RX_BASE_ADDR
212 #define SX127X_FIFO_RX_BASE_ADDR_MAX 0x00 // 7 0 allocate the entire FIFO buffer for RX only
214 // SX127X_REG_SYNC_WORD
215 //#define SX127X_SYNC_WORD 0xC8 // 200 0 default ExpressLRS sync word - 200Hz
216 #define SX127X_SYNC_WORD 0x12 // 18 0 default LoRa sync word
217 #define SX127X_SYNC_WORD_LORAWAN 0x34 // 52 0 sync word reserved for LoRaWAN networks
219 ///Added by Sandro
220 #define SX127x_TXCONTINUOUSMODE_MASK 0xF7
221 #define SX127x_TXCONTINUOUSMODE_ON 0x08
222 #define SX127x_TXCONTINUOUSMODE_OFF 0x00
223 #define SX127x_PPMOFFSET 0x27
225 ///// SX1278 Regs /////
226 //SX1278 specific register map
227 #define SX1278_REG_MODEM_CONFIG_3 0x26
228 #define SX1278_REG_TCXO 0x4B
229 #define SX1278_REG_PA_DAC 0x4D
230 #define SX1278_REG_FORMER_TEMP 0x5D
231 #define SX1278_REG_AGC_REF 0x61
232 #define SX1278_REG_AGC_THRESH_1 0x62
233 #define SX1278_REG_AGC_THRESH_2 0x63
234 #define SX1278_REG_AGC_THRESH_3 0x64
235 #define SX1278_REG_PLL 0x70
237 //SX1278 LoRa modem settings
238 //SX1278_REG_OP_MODE MSB LSB DESCRIPTION
239 #define SX1278_HIGH_FREQ 0x00 // 3 3 access HF test registers
240 #define SX1278_LOW_FREQ 0x08 // 3 3 access LF test registers
242 //SX1278_REG_FRF_MSB + REG_FRF_MID + REG_FRF_LSB
243 #define SX1278_FRF_MSB 0x6C // 7 0 carrier frequency setting: f_RF = (F(XOSC) * FRF)/2^19
244 #define SX1278_FRF_MID 0x80 // 7 0 where F(XOSC) = 32 MHz
245 #define SX1278_FRF_LSB 0x00 // 7 0 FRF = 3 byte value of FRF registers
247 //SX1278_REG_PA_CONFIG
248 #define SX1278_MAX_POWER 0x70 // 6 4 max power: P_max = 10.8 + 0.6*MAX_POWER [dBm]; P_max(MAX_POWER = 0b111) = 15 dBm
249 //#define SX1278_MAX_POWER 0x10 // 6 4 changed
251 //SX1278_REG_LNA
252 #define SX1278_LNA_BOOST_LF_OFF 0x00 // 4 3 default LNA current
254 #define SX1278_HEADER_EXPL_MODE 0x00 // 0 0 explicit header mode
255 #define SX1278_HEADER_IMPL_MODE 0x01 // 0 0 implicit header mode
257 //SX1278_REG_MODEM_CONFIG_2
258 #define SX1278_RX_CRC_MODE_OFF 0x00 // 2 2 CRC disabled
259 #define SX1278_RX_CRC_MODE_ON 0x04 // 2 2 CRC enabled
261 //SX1278_REG_MODEM_CONFIG_3
262 #define SX1278_LOW_DATA_RATE_OPT_OFF 0x00 // 3 3 low data rate optimization disabled
263 #define SX1278_LOW_DATA_RATE_OPT_ON 0x08 // 3 3 low data rate optimization enabled
264 #define SX1278_AGC_AUTO_OFF 0x00 // 2 2 LNA gain set by REG_LNA
265 #define SX1278_AGC_AUTO_ON 0x04 // 2 2 LNA gain set by internal AGC loop
267 #define SX1276_HEADER_EXPL_MODE 0x00 // 0 0 explicit header mode
268 #define SX1276_HEADER_IMPL_MODE 0x01 // 0 0 implicit header mode
270 #define SX127x_ERR_NONE 0x00
271 #define SX127x_ERR_CHIP_NOT_FOUND 0x01
272 #define SX127x_ERR_EEPROM_NOT_INITIALIZED 0x02
274 #define SX127x_ERR_PACKET_TOO_LONG 0x10
275 #define SX127x_ERR_TX_TIMEOUT 0x11
277 #define SX127x_ERR_RX_TIMEOUT 0x20
278 #define SX127x_ERR_CRC_MISMATCH 0x21
280 #define SX127x_ERR_INVALID_BANDWIDTH 0x30
281 #define SX127x_ERR_INVALID_SPREADING_FACTOR 0x31
282 #define SX127x_ERR_INVALID_CODING_RATE 0x32
283 #define SX127x_ERR_INVALID_FREQUENCY 0x33
285 #define SX127x_ERR_INVALID_BIT_RANGE 0x40
287 #define SX127x_CHANNEL_FREE 0x50
288 #define SX127x_PREAMBLE_DETECTED 0x51
290 #define SX127x_SPI_READ 0x00
291 #define SX127x_SPI_WRITE 0x80
293 #define SX127x_MAX_POWER 0x0F //17dBm
295 #define SX127x_FREQ_STEP 61.03515625
297 #define SX127x_FREQ_CORRECTION_MAX ((int32_t)(100000 / SX127x_FREQ_STEP))
298 #define SX127x_FREQ_CORRECTION_MIN ((int32_t)(-100000 / SX127x_FREQ_STEP))
300 bool sx127xInit(IO_t resetPin, IO_t busyPin);
301 uint8_t sx127xISR(uint32_t *timeStamp);
302 void sx127xWriteRegister(const uint8_t address, const uint8_t data);
303 void sx127xWriteRegisterBurst(const uint8_t address, const uint8_t *data, const uint8_t length);
304 uint8_t sx127xReadRegister(const uint8_t address);
305 void sx127xReadRegisterBurst(const uint8_t address, uint8_t *data, const uint8_t length);
306 uint8_t sx127xGetRegisterValue(const uint8_t reg, const uint8_t msb, const uint8_t lsb);
307 uint8_t sx127xSetRegisterValue(const uint8_t reg, const uint8_t value, const uint8_t msb, const uint8_t lsb);
308 void sx127xReadRegisterFIFO(uint8_t *data, const uint8_t length);
309 void sx127xWriteRegisterFIFO(const uint8_t *data, const uint8_t length);
310 void sx127xSetBandwidthCodingRate(const sx127xBandwidth_e bw, const sx127xCodingRate_e cr, const sx127xSpreadingFactor_e sf, const bool headerExplMode, const bool crcEnabled);
311 void sx127xSetSyncWord(uint8_t syncWord);
312 void sx127xSetMode(const sx127xRadioOpMode_e mode);
313 void sx127xSetOutputPower(const uint8_t power);
314 void sx127xSetPreambleLength(const uint8_t preambleLen);
315 void sx127xSetSpreadingFactor(const sx127xSpreadingFactor_e sf);
316 void sx127xSetFrequencyHZ(const uint32_t freq);
317 void sx127xSetFrequencyReg(const uint32_t freq);
319 void sx127xTransmitData(const uint8_t *data, const uint8_t length);
320 void sx127xReceiveData(uint8_t *data, const uint8_t length);
321 void sx127xStartReceiving(void);
322 void sx127xConfig(const uint8_t bw, const uint8_t sfbt, const uint8_t cr,
323 const uint32_t freq, const uint8_t preambleLength, const bool iqInverted,
324 const uint32_t flrcSyncWord, const uint16_t flrcCrcSeed, const bool isFlrc);
325 uint32_t sx127xGetCurrBandwidth(const sx127xBandwidth_e bw);
326 uint32_t sx127xGetCurrBandwidthNormalisedShifted(const sx127xBandwidth_e bw);
327 void sx127xSetPPMoffsetReg(const int32_t offset, const uint32_t freq);
328 int32_t sx127xGetFrequencyError(const sx127xBandwidth_e bw);
329 void sx127xAdjustFrequency(int32_t *offset, const uint32_t freq);
330 uint8_t sx127xUnsignedGetLastPacketRSSI(void);
331 int8_t sx127xGetLastPacketRSSI(void);
332 int8_t sx127xGetCurrRSSI(void);
333 int8_t sx127xGetLastPacketSNRRaw(void);
334 uint8_t sx127xGetIrqFlags(void);
335 void sx127xClearIrqFlags(void);
336 uint8_t sx127xGetIrqReason(void);
337 void sx127xGetLastPacketStats(int8_t *rssi, int8_t *snr);
339 void sx127xConfigLoraDefaults(const bool iqInverted);