Update oXs_out_frsky.cpp
[openXsensor.git] / openXsensor / oXs_lora.cpp
blob898f671330d220ebf1b1387bb2c8748f10f84a38
1 #include "oXs_lora.h"
2 #include <avr/pgmspace.h>
4 //#if defined( A_LOCATOR_IS_CONNECTED) && ( A_LOCATOR_IS_CONNECTED == YES)
6 //LORA use pin 10, 11,12 and 13 (= PB2 to PB5)
7 // At oXs side, the principle is to set Lora device in continuous receive mode
8 // 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)
9 // 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
10 // receiving and sending are done on 2 different frequencies in order to reduce the channel occupation
13 // SX127x series common LoRa registers
14 #define LORA_REG_FIFO 0x00 //oXsTx Receiver
15 #define LORA_REG_OP_MODE 0x01 // should be 0b10000xxx
16 // bit7=1=Lora mode
17 // bit6=0 = do not access FSK registers
18 // bit3= LowfrequencyModeOn; 0=access to HF test reg; 1=access to LF test register
19 // bits2-0=Mode; 000=sleep, 001=standby, 011=Transmit, 101=Receive continous, 110=Receive single
20 #define LORA_REG_FRF_MSB 0x06 //frequency (in steps of 61.035 Hz)
21 #define LORA_REG_FRF_MID 0x07 //frequency
22 #define LORA_REG_FRF_LSB 0x08 //frequency
23 #define LORA_REG_PA_CONFIG 0x09 //power amplifier source and value eg. 0x8F for 17dbm on PA_boost
24 // bit 7 = 1 means PA_BOOST is used; min +2,max 17dBm (or 20 with 1%); 0= FRO pin = min -4,max 14 dBm
25 // bits 6-4 = MaxPowerPmax = 10.8 + 0.6MaxPower
26 // bits 0-3 = OutputPower
27 // Pout= 10.8 + 0.6MaxPowerPmax - 15 + OutputPower (if bit7=0)
28 // Pout= 2 + OutputPower (if bit7=1)
29 #define LORA_REG_PA_RAMP 0x0A //power amplifier ramp: only bits 3-0; ex: 1000= 62usec; default = 0x09 = 125usec
30 #define LORA_REG_OCP 0x0B // current protection: could be 0b00111011 (enabled at 240 ma)
31 // bit 5 = 1 = enabled
32 // bits 4-0 = OcpTrim
33 // Imax = 45+5*OcpTrim (if OcpTrim <=15 so 120mA)
34 // = -30+10*OcpTrim (sinon et <=27 so 240mA)
35 // default 0x0B = 100mA; max value = OcpTrim=27 (décimal) = 11011
36 #define LORA_REG_LNA 0x0C // gain in reception ex: 0b00100011max gain, no boost on LNA)
37 // bits 7-5 = LnaGain
38 // 000 = not used
39 // 001 = max gain // 110 = min gain
40 // bits 4-3 Low frequency LNA current adjustment; must be 00
41 // bits 1-0 High frequency LNA current adjustment
42 // 00 = Default LNA current
43 // 11 = Boost on, 150% LNA current
44 #define LORA_REG_FIFO_ADDR_PTR 0x0D // address of current byte to be read/writen in Fifo
45 #define LORA_REG_FIFO_TX_BASE_ADDR 0x0E // base of Tx fifo; default 0x80
46 #define LORA_REG_FIFO_RX_BASE_ADDR 0x0F // base of Rx fifo; default 0x00
47 #define LORA_REG_FIFO_RX_CURRENT_ADDR 0x10 // adress of start of last Rx packet received (can't be written)
48 #define LORA_REG_IRQ_FLAGS_MASK 0x11 // Irq flag mask
49 #define LORA_REG_IRQ_FLAGS 0x12 // Irq flags (write 1 to bit to clear); write 0xFF clear all flags
50 // bit 7=RxTimeout, 6=RxDone, 5=CrcError, 4= validHeader
51 // 3=TxDone, 2=CadDone, 1=FhssChange, 0= Cad detected
52 #define LORA_REG_RX_NB_BYTES 0x13 // Number of received bytes in payload of last packet received
53 #define LORA_REG_RX_HEADER_CNT_VALUE_MSB 0x14 // count nr of header received
54 #define LORA_REG_RX_HEADER_CNT_VALUE_LSB 0x15
55 #define LORA_REG_RX_PACKET_CNT_VALUE_MSB 0x16 // count nr of packet received
56 #define LORA_REG_RX_PACKET_CNT_VALUE_LSB 0x17
57 #define LORA_REG_MODEM_STAT 0x18 // Live LoRaTM modem status (see page 111 of datasheet)
58 #define LORA_REG_PKT_SNR_VALUE 0x19 // SNR of last packet received
59 // SNR = (bit 7-0 in 2 complement)/4
60 #define LORA_REG_PKT_RSSI_VALUE 0x1A // RSSI of last packet received
61 // see 5.5.5 of datasheet
62 #define LORA_REG_RSSI_VALUE 0x1B // current RSSI (not used)
63 #define LORA_REG_HOP_CHANNEL 0x1C // start of hop channel (not used)
64 #define LORA_REG_MODEM_CONFIG_1 0x1D // config of modem part 1 // e.g. BW=125,CR=4/5 , no Header => 0b01110011
65 // bits 7-4 = BW; 0110 = 62.5Khz; 0111=125Khz
66 // bits 3-1 = CR ; 001 = 4/5; 100=4/8
67 //bit 0: 0=Explicit Header; 1=no Header
68 #define LORA_REG_MODEM_CONFIG_2 0x1E // config of modem part 2 //e.g.SF=10,1 packet,CRCon,=> Ob10100100
69 // bits 7-4=SF ; from 6 up to 12
70 // bit 3=TxContinous mode;0=one packet only
71 // bit2=RxPayloadCrcON ; 1=Enable
72 // bits1-0= SymbTimeOut(9:8) = MSB
73 #define LORA_REG_SYMB_TIMEOUT_LSB 0x1F // Receiver timeout value LSB (in single mode) in number of symbols
74 #define LORA_REG_PREAMBLE_MSB 0x20 // size of preamble; e.g. 0x0006 (default 000C)
75 #define LORA_REG_PREAMBLE_LSB 0x21
76 #define LORA_REG_PAYLOAD_LENGTH 0x22 // Payload length; has to be defined when no header
77 // e.g. 0x02 (for Receiver => 150msec) and 0x06 (for oXs => 190msec)
78 #define LORA_REG_MAX_PAYLOAD_LENGTH 0x23 // max payload length (not used??? when no header); for safety, set to 0x06
79 #define LORA_REG_HOP_PERIOD 0x24 // frequency hop period (not used)
80 #define LORA_REG_FIFO_RX_BYTE_ADDR 0x25 // adress of last byte written in Fifo in receive mode
81 #define LORA_REG_MODEM_CONFIG_3 0x26 // config of modem part 3 ; e.g. 0b00001100
82 // bit3=LowDataRateOptimize; 1=Enabled mandated when symbol length exceeds 16ms
83 // bit2=AgcAutoOn; 1=LNA gain set by internal AGCloop instead of by register LnaGain
84 #define LORA_REG_FEI_MSB 0x28 // estimated frequency error
85 #define LORA_REG_FEI_MID 0x29
86 #define LORA_REG_FEI_LSB 0x2A
87 #define LORA_REG_RSSI_WIDEBAND 0x2C //wideband RSSI measurement (= average) (not used)
88 #define LORA_REG_DETECT_OPTIMIZE 0x31 // lora detection optimize ;e.g. 0x03 (for sf10)
89 // bit 2-0 = 011 for SF7 to 12; 0101 for sf6 only; default 011
90 #define LORA_REG_INVERT_IQ 0x33 // Invert lora I and Q signals
91 #define LORA_REG_DETECTION_THRESHOLD 0x37 // lora detection threshold default 0X0A is ok for SF7-12; 0x0C for sf6
92 #define LORA_REG_SYNC_WORD 0x39 // lora Sync Word (default 0x12)
93 #define LORA_REG_DIO_MAPPING_1 0x40 // DIO mapping
94 #define LORA_REG_DIO_MAPPING_2 0x41
95 #define LORA_REG_VERSION 0x42 // lora version
96 #define LORA_REG_PA_DAC 0x4D // 0x84 = normal power (up to 17 dBm); 0x87= boost (20dBm)
98 // SX127x common LoRa modem settings
99 // LORA_REG_OP_MODE MSB LSB DESCRIPTION
100 #define LORA_SLEEP 0b00000000 // 2 0 sleep
101 #define LORA_STANDBY 0b00000001 // 2 0 standby
102 #define LORA_TX 0b00000011 // 2 0 transmit
103 #define LORA_RXCONTINUOUS 0b00000101 // 2 0 receive continuous
104 #define LORA_RXSINGLE 0b00000110 // 2 0 receive single
107 // IRQ masks
108 #define IRQ_TX_DONE_MASK 0x08
109 #define IRQ_PAYLOAD_CRC_ERROR_MASK 0x20
110 #define IRQ_RX_DONE_MASK 0x40
112 // Process depends on loraState; it can be
113 #define LORA_TO_INIT 0 // device must be initialized
114 #define LORA_IN_SLEEP 1 // wait a delay and set lora in recieve continous mode
115 #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
116 #define LORA_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
117 #define LORA_WAIT_END_OF_TRANSMIT 4 //wait that pakage has been sent (or wait max x sec)
119 #define TX_FRF_MSB 0xC0 // F / 32E6 * 256 * 256 * 8
120 #define TX_FRF_MID 0x00
121 #define TX_FRF_LSB 0x00
123 #define RX_FRF_MSB 0xC0
124 #define RX_FRF_MID 0x00
125 #define RX_FRF_LSB 0x00
128 //++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
130 uint8_t loraRxPacketRssi ;
131 uint8_t loraRxPacketSnr ;
132 uint8_t loraRxPacketType ;
133 uint8_t loraRxPacketTxPower ;
134 uint8_t loraState = 0 ;
137 extern uint32_t GPS_last_fix_millis ; // time when last fix has been received (used by lora locator)
138 extern int32_t GPS_last_fix_lon ; // last lon when a fix has been received
139 extern int32_t GPS_last_fix_lat ; // last lat when a fix has been received
140 extern uint16_t GPS_hdop ;
142 void initSpi(){ // configure the SPI
143 DDRB |= (1<<2)|(1<<3)|(1<<5); // SCK, MOSI and SS as outputs on PORTB (PB2,PB3,PB5)
144 DDRB &= ~(1<<4); // MISO as input (PB4)
145 PORTB |= (1<<2) ; // Set chip select high (PB2)
147 SPCR = (1<<MSTR) | // Set as Master, send most significant bit first (because bit is left on 0)
148 (1<<SPR0) | // divided clock by 16
149 (1<<SPE); // Enable SPI, disable interrupt (bit7 on 0)
150 SPSR = 1 ; // Bit0 allows to multiply frequency by 2 (in master mode)
153 //shifts out 8 bits of data
154 // uint8_t data - the data to be shifted out
155 // returns uint8_t - the data received during sending
156 uint8_t spiSend(uint8_t value){
157 uint8_t result;
158 SPDR = value; //shift the first byte of the value
159 while(!(SPSR & (1<<SPIF))); //wait for the SPI bus to finish
160 result = SPDR; //get the received data
161 return result;
164 #define SPI_SELECT (PORTB &= ~(1<<2) ) // macro for selecting LORA device
165 #define SPI_UNSELECT (PORTB |= (1<<2) ) // macro for unselecting LORA device
167 uint8_t loraSingleTransfer(uint8_t reg, uint8_t value) { // only for internal use; Write and read one LORA register
168 uint8_t response;
169 SPI_SELECT ;
170 spiSend(reg);
171 response = spiSend(value);
172 SPI_UNSELECT ;
173 return response;
176 void loraWriteRegister(uint8_t reg, uint8_t value) { // write a LORA register, discard the read value
177 loraSingleTransfer(reg | 0x80, value);
180 uint8_t loraReadRegister(uint8_t reg) { // Read a LORA register; send a dummy value because it is just a read
181 return loraSingleTransfer(reg & 0x7f, 0x00);
184 void loraReadRegisterBurst( uint8_t reg, uint8_t* dataIn, uint8_t numBytes) {
185 SPI_SELECT ;
186 spiSend(reg & 0x7f);
187 for(size_t n = 0; n < numBytes; n++) {
188 dataIn[n] = spiSend(0x00);
190 SPI_UNSELECT ;
193 void loraWriteRegisterBurst( uint8_t reg, uint8_t* dataOut, uint8_t numBytes) {
194 SPI_SELECT ;
195 spiSend(reg | 0x80);
196 for(size_t n = 0; n < numBytes; n++) {
197 spiSend(dataOut[n]);
199 SPI_UNSELECT ;
204 #define SLEEP_TIME 55000 // sleep during 55 sec
205 #define SHORT_RECEIVE_TIME 5000 // wait 5 sec for a packet
206 #define LONG_RECEIVE_TIME 60000 // stay in receive for 1 min after receiving a packet
208 void loraHandle(){
209 uint8_t loraIrqFlags ;
210 static uint32_t loraStateMillis ;
211 //static uint32_t receiveMillis ;
212 uint32_t currentMillis = millis() ;
213 //Serial.println(loraState);
214 //Serial.println(loraStateMillis ) ;
215 switch (loraState) {
216 case LORA_TO_INIT :
217 initSpi(); // init spi
218 loraSetup() ; // init lora with some set up that need to be done only once
219 loraState = LORA_IN_SLEEP ;
220 loraStateMillis = currentMillis + SLEEP_TIME ;
221 Serial.println("End of init") ;
222 break ;
223 case LORA_IN_SLEEP :
224 if (currentMillis > loraStateMillis ){
225 Serial.println("End of sleep; enter receive mode for 5 sec");
226 loraRxOn();
227 loraState = LORA_IN_RECEIVE ;
228 loraStateMillis = currentMillis + SHORT_RECEIVE_TIME ;
230 break;
231 case LORA_IN_RECEIVE :
232 // check if a packet has been received with a correct CRC
233 loraIrqFlags = loraReadRegister(LORA_REG_IRQ_FLAGS);
234 if ( loraIrqFlags & IRQ_RX_DONE_MASK ) {
235 if ( loraIrqFlags & IRQ_PAYLOAD_CRC_ERROR_MASK) {
236 Serial.println("wrong crc received") ;
237 loraRxOn() ; // restart reading in continous mode if CRC is wrong (reset address and interrupt)
238 } else {
239 loraReadPacket() ; // read the data in fifo (type and TxPower) and Rssi+SNR
240 loraInSleep() ;
241 loraState = LORA_TO_TRANSMIT;
242 Serial.println("packet received") ;
244 } else if (currentMillis > loraStateMillis) {
245 Serial.println("receive timeout; go to sleep") ;
246 loraInSleep() ;
247 loraState = LORA_IN_SLEEP;
248 loraStateMillis = currentMillis + SLEEP_TIME ;
250 break;
251 case LORA_TO_TRANSMIT :
252 loraFillTxPacket() ; // set mode to standby, fill fifo with data to be sent (6 bytes)
253 loraTxOn(loraRxPacketTxPower) ; // set TxOn (adjust frequency, number of bytes, Txpower, start Tx) // set lora in transmit mode
254 loraStateMillis = currentMillis + 400 ; // start a timeout ; normally sending is done in less than 200msec
255 loraState = LORA_WAIT_END_OF_TRANSMIT ;
256 Serial.println("packet redy for sending") ;
257 break;
258 case LORA_WAIT_END_OF_TRANSMIT :
259 // check if transmit is done or if timeout occurs
260 // if transmitted, put lora in receive, change loraState to LORA_IN_RECEIVE , change loraStateMillis = currentMillis+LONG_RECEIVE
261 // else, if timeOut, go in sleep for the SLEEP_TIME
262 loraIrqFlags = loraReadRegister(LORA_REG_IRQ_FLAGS);
263 if ( loraIrqFlags & IRQ_TX_DONE_MASK ) {
264 Serial.println("packet has been sent; go to receive for 60sec") ;
265 loraRxOn();
266 loraState = LORA_IN_RECEIVE ;
267 loraStateMillis = currentMillis + LONG_RECEIVE_TIME ;
268 } else if ( currentMillis > loraStateMillis ) {
269 Serial.println("transmit timeout; go to sleep for 66") ;
270 loraInSleep() ;
271 loraState = LORA_IN_SLEEP;
272 loraStateMillis = currentMillis + SLEEP_TIME ;
275 break;
277 } // end of switch
280 void loraSetup() { // parameters that are set only once
281 loraWriteRegister(LORA_REG_OP_MODE, 0x00); //RegOpMode, need to set to sleep mode before configure for LoRa mode
282 loraWriteRegister(LORA_REG_OP_MODE, 0x80); // activate LORA mode and High frequency, stay in sleep mode
283 loraWriteRegister(LORA_REG_PA_CONFIG, 0x8F) ; // activate PA_Boost and max power = 17 dBm
284 //loraWriteRegister(LORA_REG_PA_RAMP, 0x09)) ; // keep default value
285 loraWriteRegister(LORA_REG_OCP, 0b00111011) ; // current protection On with max value of 240 mA
286 loraWriteRegister(LORA_REG_LNA, 0x23) ; // max gain in reception , boost on LNA
287 loraWriteRegister(LORA_REG_MODEM_CONFIG_1,0b01110011) ;// BW=125khz,CR=4/5,No header
288 // bits 7-4 = BW; 0110 = 62.5Khz; 0111=125Khz
289 // bits 3-1 = CR ; 001 = 4/5; 100=4/8
290 //bit 0: 0=Explicit Header; 1=no Header
291 loraWriteRegister(LORA_REG_MODEM_CONFIG_2,0b10100100) ; // SF=10,One Tx packet,CrcOn, timeOutMsb=0
292 // bits 7-4=SF ; from 6 up to 12
293 // bit 3=TxContinous mode;0=one packet only
294 // bit2=RxPayloadCrcON ; 1=Enable
295 // bits1-0= SymbTimeOut(9:8) = MSB
296 loraWriteRegister(LORA_REG_SYMB_TIMEOUT_LSB, 0xFF) ; // Receiver time out in single mode
297 //loraWriteRegister(LORA_REG_PREAMBLE_MSB, 0x00) ; // keep 00 default value
298 loraWriteRegister(LORA_REG_PREAMBLE_LSB, 6) ; // 6 preamble sysbols
299 loraWriteRegister(LORA_REG_MODEM_CONFIG_3, 0b00000100); //
300 // bit3=LowDataRateOptimize; 1=Enabled mandated when symbol length exceeds 16ms
301 // bit2=AgcAutoOn; 1=LNA gain set by internal AGCloop instead of by register LnaGain
304 void loraTxOn(uint8_t txPower){ // if TX power <= 15, do not use the boost
305 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_STANDBY);
306 if ( txPower <= 15) {
307 loraWriteRegister(LORA_REG_PA_CONFIG, 0x80 | txPower) ; // use PA_boost (power is from 2 up to 17dBm
308 loraWriteRegister(LORA_REG_PA_DAC , 0x84 ) ; // 0x84 = normal power (up to 17 dBm); 0x87= boost (20dBm)
309 } else { // for this project, we use only normal power (no boost
310 loraWriteRegister(LORA_REG_PA_CONFIG, 0x80 | 15) ; // use PA_boost (power is from 2 up to 17dBm
311 loraWriteRegister(LORA_REG_PA_DAC , 0x84 ) ; // 0x84 = normal power (up to 17 dBm); 0x87= boost (20dBm)
313 loraWriteRegister(LORA_REG_FRF_MSB, TX_FRF_MSB); //frequency (in steps of 61.035 Hz)
314 loraWriteRegister(LORA_REG_FRF_MID, TX_FRF_MID);
315 loraWriteRegister(LORA_REG_FRF_LSB, TX_FRF_LSB);
316 loraWriteRegister(LORA_REG_IRQ_FLAGS, 0xFF); //reset interrupt flags
317 loraWriteRegister(LORA_REG_PAYLOAD_LENGTH,6); // set payload on 6 (because it is the same time on air as 5
318 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_TX);
322 void loraRxOn(){
323 loraWriteRegister(LORA_REG_OP_MODE, 0x80);
324 loraWriteRegister(LORA_REG_FIFO_RX_BASE_ADDR, 0x00); // reset base Rx adress to 0
325 loraWriteRegister(LORA_REG_FRF_MSB, RX_FRF_MSB); //frequency (in steps of 61.035 Hz)
326 loraWriteRegister(LORA_REG_FRF_MID, RX_FRF_MID);
327 loraWriteRegister(LORA_REG_FRF_LSB, RX_FRF_LSB);
328 loraWriteRegister(LORA_REG_IRQ_FLAGS, 0xFF); //reset interrupt flags
329 loraWriteRegister(LORA_REG_PAYLOAD_LENGTH,2); // set payload on 6 (because it is the same time on air as 5
330 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_RXCONTINUOUS);
333 void loraInSleep(){
334 loraWriteRegister(LORA_REG_OP_MODE, 0x80);
337 void loraReadPacket() // read a packet with 2 bytes ; PacketType and PacketTxPower
339 loraRxPacketRssi = loraReadRegister( LORA_REG_PKT_RSSI_VALUE );
340 loraRxPacketSnr = loraReadRegister( LORA_REG_PKT_RSSI_VALUE );
341 loraWriteRegister(LORA_REG_FIFO_ADDR_PTR, 0); //set RX FIFO ptr
342 SPI_SELECT ; // start of read burst on fifo
343 spiSend(LORA_REG_FIFO); //address for fifo
344 loraRxPacketType = spiSend(0);
345 loraRxPacketTxPower = spiSend(0);
346 SPI_UNSELECT ;
347 Serial.print("Rssi=");Serial.println(loraRxPacketRssi ) ;
348 Serial.print("Snr=");Serial.println( loraRxPacketSnr) ;
349 Serial.print("Type=");Serial.println(loraRxPacketType ) ;
350 Serial.print("Power=");Serial.println(loraRxPacketTxPower ) ;
354 void loraFillTxPacket() {
355 // data to be sent are type of packet, Long, Lat, Gps accuracy, rssi, snr, nbr of min since last GPS
356 // in order to stay with 6 bytes per packet, we will send 1 byte with
357 // Bit 7/ 0 = Long, 1=Lat ; this is type of packet
358 // Bit 6/3 = GPS accuracy 0= very good; 15 = bad (we discard décimal); it is gps_HDOP/128, if >15, then becomes 15
359 // Bit 2/0/= gps oldier than than x sec....1h; 0 = no GPS (yet)
360 // Then there is one byte with Rssi and 4 bytes for long/lat (or replaced by 00 if GPS is unavailable)
361 // 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
362 uint8_t loraTxBuffer[6] ;
363 static uint8_t packetType = 0 ;
364 uint16_t temp16 = 0 ;
365 uint8_t temp8 = 0 ;
366 int32_t gpsPos = 0 ;
367 packetType = (~packetType ) & 0x80 ; // reverse first bit
368 #if defined( A_GPS_IS_CONNECTED ) && ( A_GPS_IS_CONNECTED == YES)
369 temp16 = (GPS_hdop >> 7) ; // Divide by 128 instead of 100 to go faster and keep only 4 bytes
370 if ( temp16 > 0x0F) temp16 = 0x0F ;
371 packetType |= (temp16 << 3 ) ; // shift in pos 3 to 6
372 if ( GPS_last_fix_millis > 0 ) { // if we receive at least one fix then we calculate the nelapsed time
373 temp16 = ( millis() - GPS_last_fix_millis) >> 16 ; // to save bytes, we divide millisec by 1024
374 if ( temp16 > 3515 ) {
375 temp8 = 6 ; // more than 1 h (3515 = 3600000/1024
376 } else if ( temp16 > 585 ) {
377 temp8 = 5 ; // more than 10 min (585 = 600000/1024
378 } else if ( temp16 > 59 ) {
379 temp8 = 4 ; // more than 1 min (59 = 60000/1024
380 } else if ( temp16 > 10 ) {
381 temp8 = 3 ; // more than 10 sec (10 = 10000/1024
382 } else if ( temp16 > 1 ) {
383 temp8 = 2 ; // more than 1 sec (1 = 1000/1024
384 } else {
385 temp8 = 1 ; // less than 1 sec
388 #endif
389 loraTxBuffer[0] = packetType | temp8 ;
390 loraTxBuffer[1] = loraRxPacketRssi ; // RSSI value of last packet
391 #if defined( A_GPS_IS_CONNECTED ) && ( A_GPS_IS_CONNECTED == YES)
392 if (packetType & 0x80) {
393 gpsPos = GPS_last_fix_lat ;
394 } else {
395 gpsPos = GPS_last_fix_lon ;
397 #endif
398 loraTxBuffer[2] = gpsPos >> 24 ;
399 loraTxBuffer[3] = gpsPos >> 16 ;
400 loraTxBuffer[4] = gpsPos >> 8 ;
401 loraTxBuffer[5] = gpsPos ;
403 loraWriteRegister(LORA_REG_OP_MODE, 0x80 | LORA_STANDBY) ; // set mode in standby ( to write FIFO)
404 loraWriteRegister(LORA_REG_FIFO_ADDR_PTR, 0x80 ); // set FifoAddrPtr to 80 (base adress of byte to transmit)
405 loraWriteRegisterBurst( LORA_REG_FIFO , loraTxBuffer, 6) ; // write the 6 bytes in lora fifo
408 //#endif