makes GPIO_PIN_RST optional for the sx1276
[ExpressLRS.git] / src / lib / SX127xDriver / SX127xRegs.h
blobf5a239022254a9adeac9d837ff6929447d57d8e0
1 #pragma once
3 typedef enum
5 SX127x_OPMODE_FSK_OOK = 0b00000000,
6 SX127x_OPMODE_LORA = 0b10000000,
7 SX127X_ACCESS_SHARED_REG_OFF = 0b00000000,
8 SX127X_ACCESS_SHARED_REG_ON = 0b01000000
9 } SX127x_ModulationModes;
11 typedef enum
13 SX127x_OPMODE_SLEEP = 0b00000000,
14 SX127x_OPMODE_STANDBY = 0b00000001,
15 SX127x_OPMODE_FSTX = 0b00000010,
16 SX127x_OPMODE_TX = 0b00000011,
17 SX127x_OPMODE_FSRX = 0b00000100,
18 SX127x_OPMODE_RXCONTINUOUS = 0b00000101,
19 SX127x_OPMODE_RXSINGLE = 0b00000110,
20 SX127x_OPMODE_CAD = 0b00000111,
21 } SX127x_RadioOPmodes;
23 typedef enum
25 SX127x_BW_7_80_KHZ = 0b00000000,
26 SX127x_BW_10_40_KHZ = 0b00010000,
27 SX127x_BW_15_60_KHZ = 0b00100000,
28 SX127x_BW_20_80_KHZ = 0b00110000,
29 SX127x_BW_31_25_KHZ = 0b01000000,
30 SX127x_BW_41_70_KHZ = 0b01010000,
31 SX127x_BW_62_50_KHZ = 0b01100000,
32 SX127x_BW_125_00_KHZ = 0b01110000,
33 SX127x_BW_250_00_KHZ = 0b10000000,
34 SX127x_BW_500_00_KHZ = 0b10010000
35 } SX127x_Bandwidth;
37 typedef enum
39 SX127x_SF_6 = 0b01100000,
40 SX127x_SF_7 = 0b01110000,
41 SX127x_SF_8 = 0b10000000,
42 SX127x_SF_9 = 0b10010000,
43 SX127x_SF_10 = 0b10100000,
44 SX127x_SF_11 = 0b10110000,
45 SX127x_SF_12 = 0b11000000
46 } SX127x_SpreadingFactor;
48 typedef enum
50 SX127x_CR_4_5 = 0b00000010,
51 SX127x_CR_4_6 = 0b00000100,
52 SX127x_CR_4_7 = 0b00000110,
53 SX127x_CR_4_8 = 0b00001000,
54 } SX127x_CodingRate;
56 // SX127x series common registers
57 #define SX127X_REG_FIFO 0x00
58 #define SX127X_REG_OP_MODE 0x01
59 #define SX127X_REG_FRF_MSB 0x06
60 #define SX127X_REG_FRF_MID 0x07
61 #define SX127X_REG_FRF_LSB 0x08
62 #define SX127X_REG_PA_CONFIG 0x09
63 #define SX127X_REG_PA_RAMP 0x0A
64 #define SX127X_REG_OCP 0x0B
65 #define SX127X_REG_LNA 0x0C
66 #define SX127X_REG_FIFO_ADDR_PTR 0x0D
67 #define SX127X_REG_FIFO_TX_BASE_ADDR 0x0E
68 #define SX127X_REG_FIFO_RX_BASE_ADDR 0x0F
69 #define SX127X_REG_FIFO_RX_CURRENT_ADDR 0x10
70 #define SX127X_REG_IRQ_FLAGS_MASK 0x11
71 #define SX127X_REG_IRQ_FLAGS 0x12
72 #define SX127X_REG_RX_NB_BYTES 0x13
73 #define SX127X_REG_RX_HEADER_CNT_VALUE_MSB 0x14
74 #define SX127X_REG_RX_HEADER_CNT_VALUE_LSB 0x15
75 #define SX127X_REG_RX_PACKET_CNT_VALUE_MSB 0x16
76 #define SX127X_REG_RX_PACKET_CNT_VALUE_LSB 0x17
77 #define SX127X_REG_MODEM_STAT 0x18
78 #define SX127X_REG_PKT_SNR_VALUE 0x19
79 #define SX127X_REG_PKT_RSSI_VALUE 0x1A
80 #define SX127X_REG_RSSI_VALUE 0x1B
81 #define SX127X_REG_HOP_CHANNEL 0x1C
82 #define SX127X_REG_MODEM_CONFIG_1 0x1D
83 #define SX127X_REG_MODEM_CONFIG_2 0x1E
84 #define SX127X_REG_SYMB_TIMEOUT_LSB 0x1F
85 #define SX127X_REG_PREAMBLE_MSB 0x20
86 #define SX127X_REG_PREAMBLE_LSB 0x21
87 #define SX127X_REG_PAYLOAD_LENGTH 0x22
88 #define SX127X_REG_MAX_PAYLOAD_LENGTH 0x23
89 #define SX127X_REG_HOP_PERIOD 0x24
90 #define SX127X_REG_FIFO_RX_BYTE_ADDR 0x25
91 #define SX127X_REG_FEI_MSB 0x28
92 #define SX127X_REG_FEI_MID 0x29
93 #define SX127X_REG_FEI_LSB 0x2A
94 #define SX127X_REG_RSSI_WIDEBAND 0x2C
95 #define SX127X_REG_DETECT_OPTIMIZE 0x31
96 #define SX127X_REG_INVERT_IQ 0x33
97 #define SX127X_REG_DETECTION_THRESHOLD 0x37
98 #define SX127X_REG_SYNC_WORD 0x39
99 #define SX127X_REG_DIO_MAPPING_1 0x40
100 #define SX127X_REG_DIO_MAPPING_2 0x41
101 #define SX127X_REG_VERSION 0x42
103 // SX127X_REG_PA_CONFIG
104 #define SX127X_PA_SELECT_RFO 0b00000000 // 7 7 RFO pin output, power limited to +14 dBm
105 #define SX127X_PA_SELECT_BOOST 0b10000000 // 7 7 PA_BOOST pin output, power limited to +20 dBm
106 #define SX127X_OUTPUT_POWER 0b00001111 // 3 0 output power: P_out = 17 - (15 - OUTPUT_POWER) [dBm] for PA_SELECT_BOOST
107 #if defined(USE_SX1276_RFO_HF)
108 #define SX127X_MAX_OUTPUT_POWER 0b00000000 // Enable max output power
109 #else
110 #define SX127X_MAX_OUTPUT_POWER 0b01110000 // Enable max output power
111 #endif
112 // SX127X_REG_OCP
113 #define SX127X_OCP_OFF 0b00000000 // 5 5 PA overload current protection disabled
114 #define SX127X_OCP_ON 0b00100000 // 5 5 PA overload current protection enabled
115 #define SX127X_OCP_TRIM 0b00001011 // 4 0 OCP current: I_max(OCP_TRIM = 0b1011) = 100 mA
116 #define SX127X_OCP_150MA 0b00010010 // 4 0 OCP current: I_max(OCP_TRIM = 10010) = 150 mA
118 // SX127X_REG_LNA
119 #define SX127X_LNA_GAIN_0 0b00000000 // 7 5 LNA gain setting: not used
120 #define SX127X_LNA_GAIN_1 0b00100000 // 7 5 max gain
121 #define SX127X_LNA_GAIN_2 0b01000000 // 7 5 .
122 #define SX127X_LNA_GAIN_3 0b01100000 // 7 5 .
123 #define SX127X_LNA_GAIN_4 0b10000000 // 7 5 .
124 #define SX127X_LNA_GAIN_5 0b10100000 // 7 5 .
125 #define SX127X_LNA_GAIN_6 0b11000000 // 7 5 min gain
126 #define SX127X_LNA_GAIN_7 0b11100000 // 7 5 not used
127 #define SX127X_LNA_BOOST_OFF 0b00000000 // 1 0 default LNA current
128 #define SX127X_LNA_BOOST_ON 0b00000011 // 1 0 150% LNA current
130 #define SX127X_TX_MODE_SINGLE 0b00000000 // 3 3 single TX
131 #define SX127X_TX_MODE_CONT 0b00001000 // 3 3 continuous TX
132 #define SX127X_RX_TIMEOUT_MSB 0b00000000 // 1 0
134 // SX127X_REG_SYMB_TIMEOUT_LSB
135 #define SX127X_RX_TIMEOUT_LSB 0b01100100 // 7 0 10 bit RX operation timeout
137 // SX127X_REG_PREAMBLE_MSB + REG_PREAMBLE_LSB
138 #define SX127X_PREAMBLE_LENGTH_MSB 0b00000000 // 7 0 2 byte preamble length setting: l_P = PREAMBLE_LENGTH + 4.25
139 #define SX127X_PREAMBLE_LENGTH_LSB 0b00001000 // 7 0 where l_p = preamble length
140 //#define SX127X_PREAMBLE_LENGTH_LSB 0b00000100 // 7 0 where l_p = preamble length //CHANGED
142 // SX127X_REG_DETECT_OPTIMIZE
143 #define SX127X_DETECT_OPTIMIZE_SF_6 0b00000101 // 2 0 SF6 detection optimization
144 #define SX127X_DETECT_OPTIMIZE_SF_7_12 0b00000011 // 2 0 SF7 to SF12 detection optimization
146 // SX127X_REG_DETECTION_THRESHOLD
147 #define SX127X_DETECTION_THRESHOLD_SF_6 0b00001100 // 7 0 SF6 detection threshold
148 #define SX127X_DETECTION_THRESHOLD_SF_7_12 0b00001010 // 7 0 SF7 to SF12 detection threshold
150 // SX127X_REG_PA_DAC
151 #define SX127X_PA_BOOST_OFF 0b00000100 // 2 0 PA_BOOST disabled
152 #define SX127X_PA_BOOST_ON 0b00000111 // 2 0 +20 dBm on PA_BOOST when OUTPUT_POWER = 0b1111
154 // SX127X_REG_HOP_PERIOD
155 #define SX127X_HOP_PERIOD_OFF 0b00000000 // 7 0 number of periods between frequency hops; 0 = disabled
156 #define SX127X_HOP_PERIOD_MAX 0b11111111 // 7 0
158 // SX127X_REG_DIO_MAPPING_1
159 #define SX127X_DIO0_RX_DONE 0b00000000 // 7 6
160 #define SX127X_DIO0_TX_DONE 0b01000000 // 7 6
161 #define SX127X_DIO0_CAD_DONE 0b10000000 // 7 6
162 #define SX127X_DIO1_RX_TIMEOUT 0b00000000 // 5 4
163 #define SX127X_DIO1_FHSS_CHANGE_CHANNEL 0b00010000 // 5 4
164 #define SX127X_DIO1_CAD_DETECTED 0b00100000 // 5 4
166 // SX127X_REG_IRQ_FLAGS
167 #define SX127X_CLEAR_IRQ_FLAG_RX_TIMEOUT 0b10000000 // 7 7 timeout
168 #define SX127X_CLEAR_IRQ_FLAG_RX_DONE 0b01000000 // 6 6 packet reception complete
169 #define SX127X_CLEAR_IRQ_FLAG_PAYLOAD_CRC_ERROR 0b00100000 // 5 5 payload CRC error
170 #define SX127X_CLEAR_IRQ_FLAG_VALID_HEADER 0b00010000 // 4 4 valid header received
171 #define SX127X_CLEAR_IRQ_FLAG_TX_DONE 0b00001000 // 3 3 payload transmission complete
172 #define SX127X_CLEAR_IRQ_FLAG_CAD_DONE 0b00000100 // 2 2 CAD complete
173 #define SX127X_CLEAR_IRQ_FLAG_FHSS_CHANGE_CHANNEL 0b00000010 // 1 1 FHSS change channel
174 #define SX127X_CLEAR_IRQ_FLAG_CAD_DETECTED 0b00000001 // 0 0 valid LoRa signal detected during CAD operation
176 // SX127X_REG_IRQ_FLAGS_MASK
177 #define SX127X_MASK_IRQ_FLAG_RX_TIMEOUT 0b01111111 // 7 7 timeout
178 #define SX127X_MASK_IRQ_FLAG_RX_DONE 0b10111111 // 6 6 packet reception complete
179 #define SX127X_MASK_IRQ_FLAG_PAYLOAD_CRC_ERROR 0b11011111 // 5 5 payload CRC error
180 #define SX127X_MASK_IRQ_FLAG_VALID_HEADER 0b11101111 // 4 4 valid header received
181 #define SX127X_MASK_IRQ_FLAG_TX_DONE 0b11110111 // 3 3 payload transmission complete
182 #define SX127X_MASK_IRQ_FLAG_CAD_DONE 0b11111011 // 2 2 CAD complete
183 #define SX127X_MASK_IRQ_FLAG_FHSS_CHANGE_CHANNEL 0b11111101 // 1 1 FHSS change channel
184 #define SX127X_MASK_IRQ_FLAG_CAD_DETECTED 0b11111110 // 0 0 valid LoRa signal detected during CAD operation
186 // SX127X_REG_FIFO_TX_BASE_ADDR
187 #define SX127X_FIFO_TX_BASE_ADDR_MAX 0b00000000 // 7 0 allocate the entire FIFO buffer for TX only
189 // SX127X_REG_FIFO_RX_BASE_ADDR
190 #define SX127X_FIFO_RX_BASE_ADDR_MAX 0b00000000 // 7 0 allocate the entire FIFO buffer for RX only
192 // SX127X_REG_SYNC_WORD
193 //#define SX127X_SYNC_WORD 0xC8 // 200 0 default ExpressLRS sync word - 200Hz
194 #define SX127X_SYNC_WORD 0x12 // 18 0 default LoRa sync word
195 #define SX127X_SYNC_WORD_LORAWAN 0x34 // 52 0 sync word reserved for LoRaWAN networks
197 #define IRQpin 26
199 ///Added by Sandro
200 #define SX127x_TXCONTINUOUSMODE_MASK 0xF7
201 #define SX127x_TXCONTINUOUSMODE_ON 0x08
202 #define SX127x_TXCONTINUOUSMODE_OFF 0x00
203 #define SX127x_PPMOFFSET 0x27
205 ///// SX1278 Regs /////
206 //SX1278 specific register map
207 #define SX1278_REG_MODEM_CONFIG_3 0x26
208 #define SX1278_REG_TCXO 0x4B
209 #define SX1278_REG_PA_DAC 0x4D
210 #define SX1278_REG_FORMER_TEMP 0x5D
211 #define SX1278_REG_AGC_REF 0x61
212 #define SX1278_REG_AGC_THRESH_1 0x62
213 #define SX1278_REG_AGC_THRESH_2 0x63
214 #define SX1278_REG_AGC_THRESH_3 0x64
215 #define SX1278_REG_PLL 0x70
217 //SX1278 LoRa modem settings
218 //SX1278_REG_OP_MODE MSB LSB DESCRIPTION
219 #define SX1278_HIGH_FREQ 0b00000000 // 3 3 access HF test registers
220 #define SX1278_LOW_FREQ 0b00001000 // 3 3 access LF test registers
222 //SX1278_REG_FRF_MSB + REG_FRF_MID + REG_FRF_LSB
223 #define SX1278_FRF_MSB 0x6C // 7 0 carrier frequency setting: f_RF = (F(XOSC) * FRF)/2^19
224 #define SX1278_FRF_MID 0x80 // 7 0 where F(XOSC) = 32 MHz
225 #define SX1278_FRF_LSB 0x00 // 7 0 FRF = 3 byte value of FRF registers
227 //SX1278_REG_PA_CONFIG
228 #define SX1278_MAX_POWER 0b01110000 // 6 4 max power: P_max = 10.8 + 0.6*MAX_POWER [dBm]; P_max(MAX_POWER = 0b111) = 15 dBm
229 //#define SX1278_MAX_POWER 0b00010000 // 6 4 changed
231 //SX1278_REG_LNA
232 #define SX1278_LNA_BOOST_LF_OFF 0b00000000 // 4 3 default LNA current
234 #define SX1278_HEADER_EXPL_MODE 0b00000000 // 0 0 explicit header mode
235 #define SX1278_HEADER_IMPL_MODE 0b00000001 // 0 0 implicit header mode
237 //SX1278_REG_MODEM_CONFIG_2
238 #define SX1278_RX_CRC_MODE_OFF 0b00000000 // 2 2 CRC disabled
239 #define SX1278_RX_CRC_MODE_ON 0b00000100 // 2 2 CRC enabled
241 //SX1278_REG_MODEM_CONFIG_3
242 #define SX1278_LOW_DATA_RATE_OPT_OFF 0b00000000 // 3 3 low data rate optimization disabled
243 #define SX1278_LOW_DATA_RATE_OPT_ON 0b00001000 // 3 3 low data rate optimization enabled
244 #define SX1278_AGC_AUTO_OFF 0b00000000 // 2 2 LNA gain set by REG_LNA
245 #define SX1278_AGC_AUTO_ON 0b00000100 // 2 2 LNA gain set by internal AGC loop
247 #define SX1276_HEADER_EXPL_MODE 0b00000000 // 0 0 explicit header mode
248 #define SX1276_HEADER_IMPL_MODE 0b00000001 // 0 0 implicit header mode
250 #define ERR_NONE 0x00
251 #define ERR_CHIP_NOT_FOUND 0x01
252 #define ERR_EEPROM_NOT_INITIALIZED 0x02
254 #define ERR_PACKET_TOO_LONG 0x10
255 #define ERR_TX_TIMEOUT 0x11
257 #define ERR_RX_TIMEOUT 0x20
258 #define ERR_CRC_MISMATCH 0x21
260 #define ERR_INVALID_BANDWIDTH 0x30
261 #define ERR_INVALID_SPREADING_FACTOR 0x31
262 #define ERR_INVALID_CODING_RATE 0x32
263 #define ERR_INVALID_FREQUENCY 0x33
265 #define ERR_INVALID_BIT_RANGE 0x40
267 #define CHANNEL_FREE 0x50
268 #define PREAMBLE_DETECTED 0x51
270 #define SPI_READ 0b00000000
271 #define SPI_WRITE 0b10000000