UBlox M10 Support
[openXsensor.git] / locator_receiver / lora.cpp
blob5fbc9c7603fb03935d0f5494ad2bd4455c786462
1 #include "config.h"
2 #include "lora.h"
3 #include <avr/pgmspace.h>
5 //#if defined( A_LOCATOR_IS_CONNECTED) && ( A_LOCATOR_IS_CONNECTED == YES)
7 //LORA use pin 10, 11,12 and 13 (= PB2 to PB5)
8 // At oXs side, the principle is to set Lora device in continuous receive mode
9 // In a loop, we look if a packet has been received (if so, it is one byte long with the Tx power for next transmit)
10 // When oXs get this byte, it transmits immediately RSSI, SNR, and GPS data (0 if no GPS) and GPS precision and then go back to receive mode
11 // receiving and sending are done on 2 different frequencies in order to reduce the channel occupation
14 // SX127x series common LoRa registers
15 #define LORA_REG_FIFO 0x00 //oXsTx Receiver
16 #define LORA_REG_OP_MODE 0x01 // should be 0b10000xxx
17 // bit7=1=Lora mode
18 // bit6=0 = do not access FSK registers
19 // bit3= LowfrequencyModeOn; 0=access to HF test reg; 1=access to LF test register
20 // bits2-0=Mode; 000=sleep, 001=standby, 011=Transmit, 101=Receive continous, 110=Receive single
21 #define LORA_REG_FRF_MSB 0x06 //frequency (in steps of 61.035 Hz)
22 #define LORA_REG_FRF_MID 0x07 //frequency
23 #define LORA_REG_FRF_LSB 0x08 //frequency
24 #define LORA_REG_PA_CONFIG 0x09 //power amplifier source and value eg. 0x8F for 17dbm on PA_boost
25 // bit 7 = 1 means PA_BOOST is used; min +2,max 17dBm (or 20 with 1%); 0= FRO pin = min -4,max 14 dBm
26 // bits 6-4 = MaxPowerPmax = 10.8 + 0.6MaxPower
27 // bits 0-3 = OutputPower
28 // Pout= 10.8 + 0.6MaxPowerPmax - 15 + OutputPower (if bit7=0)
29 // Pout= 2 + OutputPower (if bit7=1)
30 #define LORA_REG_PA_RAMP 0x0A //power amplifier ramp: only bits 3-0; ex: 1000= 62usec; default = 0x09 = 125usec
31 #define LORA_REG_OCP 0x0B // current protection: could be 0b00111011 (enabled at 240 ma)
32 // bit 5 = 1 = enabled
33 // bits 4-0 = OcpTrim
34 // Imax = 45+5*OcpTrim (if OcpTrim <=15 so 120mA)
35 // = -30+10*OcpTrim (sinon et <=27 so 240mA)
36 // default 0x0B = 100mA; max value = OcpTrim=27 (décimal) = 11011
37 #define LORA_REG_LNA 0x0C // gain in reception ex: 0b00100011max gain, no boost on LNA)
38 // bits 7-5 = LnaGain
39 // 000 = not used
40 // 001 = max gain // 110 = min gain
41 // bits 4-3 Low frequency LNA current adjustment; must be 00
42 // bits 1-0 High frequency LNA current adjustment
43 // 00 = Default LNA current
44 // 11 = Boost on, 150% LNA current
45 #define LORA_REG_FIFO_ADDR_PTR 0x0D // address of current byte to be read/writen in Fifo
46 #define LORA_REG_FIFO_TX_BASE_ADDR 0x0E // base of Tx fifo; default 0x80
47 #define LORA_REG_FIFO_RX_BASE_ADDR 0x0F // base of Rx fifo; default 0x00
48 #define LORA_REG_FIFO_RX_CURRENT_ADDR 0x10 // adress of start of last Rx packet received (can't be written)
49 #define LORA_REG_IRQ_FLAGS_MASK 0x11 // Irq flag mask
50 #define LORA_REG_IRQ_FLAGS 0x12 // Irq flags (write 1 to bit to clear); write 0xFF clear all flags
51 // bit 7=RxTimeout, 6=RxDone, 5=CrcError, 4= validHeader
52 // 3=TxDone, 2=CadDone, 1=FhssChange, 0= Cad detected
53 #define LORA_REG_RX_NB_BYTES 0x13 // Number of received bytes in payload of last packet received
54 #define LORA_REG_RX_HEADER_CNT_VALUE_MSB 0x14 // count nr of header received
55 #define LORA_REG_RX_HEADER_CNT_VALUE_LSB 0x15
56 #define LORA_REG_RX_PACKET_CNT_VALUE_MSB 0x16 // count nr of packet received
57 #define LORA_REG_RX_PACKET_CNT_VALUE_LSB 0x17
58 #define LORA_REG_MODEM_STAT 0x18 // Live LoRaTM modem status (see page 111 of datasheet)
59 #define LORA_REG_PKT_SNR_VALUE 0x19 // SNR of last packet received
60 // SNR = (bit 7-0 in 2 complement)/4
61 #define LORA_REG_PKT_RSSI_VALUE 0x1A // RSSI of last packet received
62 // see 5.5.5 of datasheet
63 #define LORA_REG_RSSI_VALUE 0x1B // current RSSI (not used)
64 #define LORA_REG_HOP_CHANNEL 0x1C // start of hop channel (not used)
65 #define LORA_REG_MODEM_CONFIG_1 0x1D // config of modem part 1 // e.g. BW=125,CR=4/5 , no Header => 0b01110011
66 // bits 7-4 = BW; 0110 = 62.5Khz; 0111=125Khz
67 // bits 3-1 = CR ; 001 = 4/5; 100=4/8
68 //bit 0: 0=Explicit Header; 1=no Header
69 #define LORA_REG_MODEM_CONFIG_2 0x1E // config of modem part 2 //e.g.SF=10,1 packet,CRCon,=> Ob10100100
70 // bits 7-4=SF ; from 6 up to 12
71 // bit 3=TxContinous mode;0=one packet only
72 // bit2=RxPayloadCrcON ; 1=Enable
73 // bits1-0= SymbTimeOut(9:8) = MSB
74 #define LORA_REG_SYMB_TIMEOUT_LSB 0x1F // Receiver timeout value LSB (in single mode) in number of symbols
75 #define LORA_REG_PREAMBLE_MSB 0x20 // size of preamble; e.g. 0x0006 (default 000C)
76 #define LORA_REG_PREAMBLE_LSB 0x21
77 #define LORA_REG_PAYLOAD_LENGTH 0x22 // Payload length; has to be defined when no header
78 // e.g. 0x02 (for Receiver => 150msec) and 0x06 (for oXs => 190msec)
79 #define LORA_REG_MAX_PAYLOAD_LENGTH 0x23 // max payload length (not used??? when no header); for safety, set to 0x06
80 #define LORA_REG_HOP_PERIOD 0x24 // frequency hop period (not used)
81 #define LORA_REG_FIFO_RX_BYTE_ADDR 0x25 // adress of last byte written in Fifo in receive mode
82 #define LORA_REG_MODEM_CONFIG_3 0x26 // config of modem part 3 ; e.g. 0b00001100
83 // bit3=LowDataRateOptimize; 1=Enabled mandated when symbol length exceeds 16ms
84 // bit2=AgcAutoOn; 1=LNA gain set by internal AGCloop instead of by register LnaGain
85 #define LORA_REG_FEI_MSB 0x28 // estimated frequency error
86 #define LORA_REG_FEI_MID 0x29
87 #define LORA_REG_FEI_LSB 0x2A
88 #define LORA_REG_RSSI_WIDEBAND 0x2C //wideband RSSI measurement (= average) (not used)
89 #define LORA_REG_DETECT_OPTIMIZE 0x31 // lora detection optimize ;e.g. 0x03 (for sf10)
90 // bit 2-0 = 011 for SF7 to 12; 0101 for sf6 only; default 011
91 #define LORA_REG_INVERT_IQ 0x33 // Invert lora I and Q signals
92 #define LORA_REG_DETECTION_THRESHOLD 0x37 // lora detection threshold default 0X0A is ok for SF7-12; 0x0C for sf6
93 #define LORA_REG_SYNC_WORD 0x39 // lora Sync Word (default 0x12)
94 #define LORA_REG_DIO_MAPPING_1 0x40 // DIO mapping
95 #define LORA_REG_DIO_MAPPING_2 0x41
96 #define LORA_REG_VERSION 0x42 // lora version
97 #define LORA_REG_PA_DAC 0x4D // 0x84 = normal power (up to 17 dBm); 0x87= boost (20dBm)
99 // SX127x common LoRa modem settings
100 // LORA_REG_OP_MODE MSB LSB DESCRIPTION
101 #define LORA_SLEEP 0b00000000 // 2 0 sleep
102 #define LORA_STANDBY 0b00000001 // 2 0 standby
103 #define LORA_TX 0b00000011 // 2 0 transmit
104 #define LORA_RXCONTINUOUS 0b00000101 // 2 0 receive continuous
105 #define LORA_RXSINGLE 0b00000110 // 2 0 receive single
108 // IRQ masks
109 #define IRQ_TX_DONE_MASK 0x08
110 #define IRQ_PAYLOAD_CRC_ERROR_MASK 0x20
111 #define IRQ_RX_DONE_MASK 0x40
113 // Process depends on loraState; it can be
114 #define LORA_TO_INIT 0 // device must be initialized
115 #define LORA_IN_SLEEP 1 // wait a delay and set lora in recieve continous mode
116 #define LORA_IN_RECEIVE 2 // wait that a package has been received or a max delay; if package has been received,Tx power changes, update Tx power, change mode to LORA_TO_TRANSMIT
117 #define LORA_START_TO_TRANSMIT 3 //fill lora with data to be send and ask for sending (but do not wait), change mode to LORA_WAIT_END_OF_TRANSMIT
118 #define LORA_WAIT_END_OF_TRANSMIT 4 //wait that pakage has been sent (or wait max x sec)
120 #define TX_FRF_MSB 0xC0 // F / 32E6 * 256 * 256 * 8
121 #define TX_FRF_MID 0x00
122 #define TX_FRF_LSB 0x00
124 #define RX_FRF_MSB 0xC0
125 #define RX_FRF_MID 0x00
126 #define RX_FRF_LSB 0x00
129 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
132 uint8_t oXsGpsPdop ; // gps precision sent by oxs
133 uint8_t oXsLastGpsDelay ; // delay since last gps fix at oxs side
134 uint8_t oXsPacketRssi ; // RSSI of last packet received by oXs
136 uint32_t loraMaxEndTransmitMillis ; // transmit has to be done before this delay
138 uint32_t loraLastPacketReceivedMillis ;
139 uint32_t loraLastGpsPacketReceivedMillis ;
140 int loraRxPacketRssi ;
141 float loraRxPacketSnr ;
142 int32_t lastGpsLon ;
143 int32_t lastGpsLat ;
146 void initSpi(){ // configure the SPI
147 DDRB |= (1<<2)|(1<<3)|(1<<5); // SCK, MOSI and SS as outputs on PORTB (PB2,PB3,PB5)
148 DDRB &= ~(1<<4); // MISO as input (PB4)
149 PORTB |= (1<<2) ; // Set chip select high (PB2)
151 SPCR = (1<<MSTR) | // Set as Master, send most significant bit first (because bit is left on 0)
152 (1<<SPR0) | // divided clock by 16
153 (1<<SPE); // Enable SPI, disable interrupt (bit7 on 0)
154 SPSR = 1 ; // Bit0 allows to multiply frequency by 2 (in master mode)
157 //shifts out 8 bits of data
158 // uint8_t data - the data to be shifted out
159 // returns uint8_t - the data received during sending
160 uint8_t spiSend(uint8_t value){
161 uint8_t result;
162 SPDR = value; //shift the first byte of the value
163 while(!(SPSR & (1<<SPIF))); //wait for the SPI bus to finish
164 result = SPDR; //get the received data
165 return result;
168 #define SPI_SELECT (PORTB &= ~(1<<2) ) // macro for selecting LORA device
169 #define SPI_UNSELECT (PORTB |= (1<<2) ) // macro for unselecting LORA device
171 uint8_t loraSingleTransfer(uint8_t reg, uint8_t value) { // only for internal use; Write and read one LORA register
172 uint8_t response;
173 SPI_SELECT ;
174 spiSend(reg);
175 response = spiSend(value);
176 SPI_UNSELECT ;
177 return response;
180 void loraWriteRegister(uint8_t reg, uint8_t value) { // write a LORA register, discard the read value
181 loraSingleTransfer(reg | 0x80, value);
184 uint8_t loraReadRegister(uint8_t reg) { // Read a LORA register; send a dummy value because it is just a read
185 return loraSingleTransfer(reg & 0x7f, 0x00);
188 void loraReadRegisterBurst( uint8_t reg, uint8_t* dataIn, uint8_t numBytes) {
189 SPI_SELECT ;
190 spiSend(reg & 0x7f);
191 for(size_t n = 0; n < numBytes; n++) {
192 dataIn[n] = spiSend(0x00);
194 SPI_UNSELECT ;
197 void loraWriteRegisterBurst( uint8_t reg, uint8_t* dataOut, uint8_t numBytes) {
198 SPI_SELECT ;
199 spiSend(reg | 0x80);
200 for(size_t n = 0; n < numBytes; n++) {
201 spiSend(dataOut[n]);
203 SPI_UNSELECT ;
206 #define NEXT_TRANSMIT_TIME 1000 // wait 1000 msec max for a packet being sent
207 #define RECEIVE_TIME 700 // wait 700 msec max for a packet being received
209 uint8_t loraHandle(){
210 uint8_t returnCode = 0 ; // just for debugging (= 1 is we are just transmitting)
211 uint8_t loraIrqFlags ;
212 static uint8_t loraState = 0 ;
213 static uint32_t loraStateMillis ;
214 static uint32_t loraNextTransmitMillis = 0;
216 uint32_t currentMillis = millis() ;
217 switch (loraState) {
218 case LORA_TO_INIT :
219 initSpi(); // init spi
220 loraSetup() ; // init lora with some set up that need to be done only once
221 loraState = LORA_START_TO_TRANSMIT ;
222 break ;
223 case LORA_START_TO_TRANSMIT :
224 loraFillTxPacket() ; // set mode to standby, fill fifo with data to be sent (2 bytes)
225 loraTxOn(0x15) ; // set TxOn (adjust frequency, number of bytes, Txpower = 15=max, start Tx) // set lora in transmit mode
226 loraNextTransmitMillis = currentMillis + NEXT_TRANSMIT_TIME ; // setup next transmit time
227 loraMaxEndTransmitMillis = currentMillis + 200 ; // Transmission must be done within this time
228 loraState = LORA_WAIT_END_OF_TRANSMIT ;
229 Serial.println("transmit one packet") ; // to debug
230 break;
231 case LORA_WAIT_END_OF_TRANSMIT :
232 // check if transmit is done or if timeout occurs
233 // if transmitted, put lora in receive, change loraState to LORA_IN_RECEIVE , change loraStateMillis = currentMillis+LONG_RECEIVE
234 // else, if timeOut, go in sleep for the SLEEP_TIME
235 loraIrqFlags = loraReadRegister(LORA_REG_IRQ_FLAGS);
236 if ( loraIrqFlags & IRQ_TX_DONE_MASK ) {
237 loraRxOn();
238 loraState = LORA_IN_RECEIVE ;
239 loraStateMillis = currentMillis + RECEIVE_TIME ; // normally wait a reply within 700 msec
240 returnCode = 1 ; // 1 means that packet has been sent
242 } else if ( currentMillis > loraMaxEndTransmitMillis ) { // loraStateMillis
243 Serial.println("Packet not sent within the delay") ;
244 loraInSleep() ;
245 loraState = LORA_IN_SLEEP ;
247 break;
248 case LORA_IN_SLEEP :
249 if (currentMillis > loraNextTransmitMillis ){
250 loraState = LORA_START_TO_TRANSMIT ;
252 break;
253 case LORA_IN_RECEIVE :
254 // check if a packet has been received with a correct CRC
255 loraIrqFlags = loraReadRegister(LORA_REG_IRQ_FLAGS);
256 if ( loraIrqFlags & IRQ_RX_DONE_MASK ) {
257 if ( loraIrqFlags & IRQ_PAYLOAD_CRC_ERROR_MASK) {
258 loraInSleep() ;
259 loraState = LORA_IN_SLEEP;
260 } else {
261 loraReadPacket() ; // read the data in fifo 6 bytes
262 loraInSleep() ;
263 loraState = LORA_IN_SLEEP;
264 returnCode=2;
266 } else if (currentMillis > loraStateMillis) { // back to sleep if we did not receive a packet within the expected time
267 loraInSleep() ;
268 loraState = LORA_IN_SLEEP ;
270 break;
272 } // end of switch
273 return returnCode ;
276 void loraSetup() { // parameters that are set only once
277 loraWriteRegister(LORA_REG_OP_MODE, 0x00); //RegOpMode, need to set to sleep mode before configure for LoRa mode
278 loraWriteRegister(LORA_REG_OP_MODE, 0x80); // activate LORA mode and High frequency, stay in sleep mode
279 loraWriteRegister(LORA_REG_PA_CONFIG, 0x8F) ; // activate PA_Boost and max power = 17 dBm
280 //loraWriteRegister(LORA_REG_PA_RAMP, 0x09)) ; // keep default value
281 loraWriteRegister(LORA_REG_OCP, 0b00111011) ; // current protection On with max value of 240 mA
282 loraWriteRegister(LORA_REG_LNA, 0x23) ; // max gain in reception , boost on LNA
283 loraWriteRegister(LORA_REG_MODEM_CONFIG_1,0b01110011) ;// BW=125khz,CR=4/5,No header
284 // bits 7-4 = BW; 0110 = 62.5Khz; 0111=125Khz
285 // bits 3-1 = CR ; 001 = 4/5; 100=4/8
286 //bit 0: 0=Explicit Header; 1=no Header
287 loraWriteRegister(LORA_REG_MODEM_CONFIG_2,0b10100100) ; // SF=10,One Tx packet,CrcOn, timeOutMsb=0
288 // bits 7-4=SF ; from 6 up to 12
289 // bit 3=TxContinous mode;0=one packet only
290 // bit2=RxPayloadCrcON ; 1=Enable
291 // bits1-0= SymbTimeOut(9:8) = MSB
292 loraWriteRegister(LORA_REG_SYMB_TIMEOUT_LSB, 0xFF) ; // Receiver time out in single mode
293 //loraWriteRegister(LORA_REG_PREAMBLE_MSB, 0x00) ; // keep 00 default value
294 loraWriteRegister(LORA_REG_PREAMBLE_LSB, 6) ; // 6 preamble sysbols
295 loraWriteRegister(LORA_REG_MODEM_CONFIG_3, 0b00000100); //
296 // bit3=LowDataRateOptimize; 1=Enabled mandated when symbol length exceeds 16ms
297 // bit2=AgcAutoOn; 1=LNA gain set by internal AGCloop instead of by register LnaGain
300 void loraTxOn(uint8_t txPower){
301 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_STANDBY);
302 if ( txPower <= 15) {
303 loraWriteRegister(LORA_REG_PA_CONFIG, 0x80 | txPower) ; // use PA_boost (power is from 2 up to 17dBm
304 loraWriteRegister(LORA_REG_PA_DAC , 0x84 ) ; // 0x84 = normal power (up to 17 dBm); 0x87= boost (20dBm)
305 } else { // for this project, we use only normal power (no boost
306 loraWriteRegister(LORA_REG_PA_CONFIG, 0x80 | 15) ; // use PA_boost (power is from 2 up to 17dBm
307 loraWriteRegister(LORA_REG_PA_DAC , 0x84 ) ; // 0x84 = normal power (up to 17 dBm); 0x87= boost (20dBm)
309 loraWriteRegister(LORA_REG_FRF_MSB, TX_FRF_MSB); //frequency (in steps of 61.035 Hz)
310 loraWriteRegister(LORA_REG_FRF_MID, TX_FRF_MID);
311 loraWriteRegister(LORA_REG_FRF_LSB, TX_FRF_LSB);
312 loraWriteRegister(LORA_REG_IRQ_FLAGS, 0xFF); //reset interrupt flags
313 loraWriteRegister(LORA_REG_PAYLOAD_LENGTH,2); // set payload on 6 (because it is the same time on air as 5
314 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_TX);
318 void loraRxOn(){
319 loraWriteRegister(LORA_REG_OP_MODE, 0x80);
320 loraWriteRegister(LORA_REG_FIFO_RX_BASE_ADDR, 0x00); // reset base Rx adress to 0
321 loraWriteRegister(LORA_REG_FRF_MSB, RX_FRF_MSB); //frequency (in steps of 61.035 Hz)
322 loraWriteRegister(LORA_REG_FRF_MID, RX_FRF_MID);
323 loraWriteRegister(LORA_REG_FRF_LSB, RX_FRF_LSB);
324 loraWriteRegister(LORA_REG_IRQ_FLAGS, 0xFF); //reset interrupt flags
325 loraWriteRegister(LORA_REG_PAYLOAD_LENGTH,6); // set payload on 6 (because it is the same time on air as 5
326 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_RXCONTINUOUS);
329 void loraInSleep(){
330 loraWriteRegister(LORA_REG_OP_MODE, 0x80);
333 void loraReadPacket() { // read a packet with 6 bytes ;
334 // in order to stay with 6 bytes per packet, we will send 1 byte with
335 // Bit 7/ 0 = Long, 1=Lat ; this is type of packet
336 // Bit 6/3 = GPS accuracy 0= very good; 15 = bad (we discard décimal); it is gps_HDOP/128, if >15, then becomes 15
337 // Bit 2 = gps oldier than than 1h
338 // Bit 1 = oldier than 10 min
339 // Bit 0 = oldier than 1 min
340 // Then there is one byte with Rssi and 4 bytes for long/lat (or replaced by 00 if GPS is unavailable)
341 // Note: gps_last_fix_lon and lat are filled with last value when a fix was available and if a fix has never been available they are filled with 0
343 uint8_t loraRxBuffer[6] ;
344 uint8_t oXsPacketType ; // specify if oXs packet is long or lat
345 int32_t oXsGpsLonLat ; // lon or lat sent by gps
347 loraLastPacketReceivedMillis = millis() ;
348 loraRxPacketRssi = loraReadRegister( LORA_REG_PKT_RSSI_VALUE )- 157;
349 loraRxPacketSnr = loraReadRegister( LORA_REG_PKT_SNR_VALUE ) * 0.25
351 loraWriteRegister(LORA_REG_FIFO_ADDR_PTR, 0); //set RX FIFO ptr
352 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_STANDBY) ; // set mode in standby (to read FIFO)
353 loraReadRegisterBurst( LORA_REG_FIFO , loraRxBuffer, 6) ; // read the 6 bytes in lora fifo
354 oXsPacketType = (loraRxBuffer[0] >> 7 ) ; // bit 7 gives the type of gps data
355 oXsGpsLonLat = (((uint32_t) loraRxBuffer[2] ) << 24) | (((uint32_t) loraRxBuffer[3] ) << 16) | (((uint32_t) loraRxBuffer[4] ) << 8) | ((uint32_t) loraRxBuffer[5] ) ;
356 if (oXsGpsLonLat != 0 ) {
357 loraLastGpsPacketReceivedMillis = loraLastPacketReceivedMillis ;
358 if ( oXsPacketType ) {
359 lastGpsLat = oXsGpsLonLat ;
360 } else {
361 lastGpsLon = oXsGpsLonLat ;
364 oXsGpsPdop = (loraRxBuffer[0] >> 3 ) & 0x0F ; // bit 6/3 gives the type of gps precision (normally it is in 0.01 but we put it in 1/128 for faster conversion and we loose decimal)
365 oXsLastGpsDelay = (loraRxBuffer[0] ) & 0x07 ; // code in 3 bits of the time enlapsed since previous GPS fix at oXs side
366 oXsPacketRssi = loraRxBuffer[1] ; // RSSI of last byte received by oXS
368 for (int i = 0; i < 128; i++) {
369 Serial.print("0x");
370 Serial.print(i, HEX);
371 Serial.print(": 0x");
372 Serial.println( loraReadRegister(i), HEX);
379 void loraFillTxPacket() {
380 // data to be sent are only 2 byte; the first one is requested Txpower to be used at oXs side
381 uint8_t loraTxBuffer[2] ;
382 loraTxBuffer[0] = 0x55 ; // Type of packet ; currently not used
383 loraTxBuffer[1] = 0x0F ; // 0x0F = max power (for first tests; it could be reduced based on RSSI at this side in order to increase the location possibility without GPS
384 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_STANDBY) ; // set mode in standby (to write FIFO)
385 loraWriteRegister(LORA_REG_FIFO_ADDR_PTR, 0x80 ); // set FifoAddrPtr to 80 (base adress of byte to transmit)
386 loraWriteRegisterBurst( LORA_REG_FIFO , loraTxBuffer, 2) ; // write the 2 bytes in lora fifo