Resolve conflict

pull/46/head
Pawel Jalocha 2021-12-21 04:07:26 +00:00
commit 2d8315e757
11 zmienionych plików z 584 dodań i 140 usunięć

Wyświetl plik

@ -1 +1 @@
tar cvzf esp32-ogn-tracker-bin.tgz flash_USB?.sh esptool.py build/partitions.bin build/bootloader/bootloader.bin build/esp32-ogn-tracker.bin utils/read_log utils/serial_dump main/config.h
tar cvzf esp32-ogn-tracker-bin.tgz flash_USB?.sh flash_COM?.bat esptool.py build/partitions.bin build/bootloader/bootloader.bin build/esp32-ogn-tracker.bin utils/read_log utils/serial_dump main/config.h

Wyświetl plik

@ -427,21 +427,30 @@ static void esp_ble_gatts_cb(esp_gatts_cb_event_t Event, esp_gatt_if_t gatts_if,
break;
case ESP_GATTS_START_EVT: // #12
break;
case ESP_GATTS_STOP_EVT: //
break;
case ESP_GATTS_UNREG_EVT: // #6
break;
case ESP_GATTS_MTU_EVT: // #4
spp_mtu_size = Param->mtu.mtu;
break;
case ESP_GATTS_CONNECT_EVT: // #14
case ESP_GATTS_CONNECT_EVT: // #14 = GATT client connect
spp_conn_id = Param->connect.conn_id;
spp_gatts_if = gatts_if;
is_connected = true;
memcpy(&spp_remote_bda, &Param->connect.remote_bda, sizeof(esp_bd_addr_t));
break;
case ESP_GATTS_DISCONNECT_EVT: // #15
case ESP_GATTS_DISCONNECT_EVT: // #15 = GATT client disconnect
is_connected = false;
esp_ble_gap_start_advertising(&spp_adv_params);
break;
case ESP_GATTS_MTU_EVT: // #4 = set MTU complete
spp_mtu_size = Param->mtu.mtu;
break;
case ESP_GATTS_READ_EVT: // #1 = request read operation
break;
case ESP_GATTS_WRITE_EVT: // #2 = request write operation
break;
case ESP_GATTS_EXEC_WRITE_EVT: // #3 = request execute write opearation
// if(Param->exec_write.exec_write_flag) { }
break;
default:
break;
}
@ -449,6 +458,8 @@ static void esp_ble_gatts_cb(esp_gatts_cb_event_t Event, esp_gatt_if_t gatts_if,
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_String(CONS_UART_Write, "BLE_GATTS: Event ");
Format_UnsDec(CONS_UART_Write, (uint32_t)Event);
Format_String(CONS_UART_Write, ".");
Format_UnsDec(CONS_UART_Write, (uint32_t)gatts_if);
Format_String(CONS_UART_Write, "\n");
xSemaphoreGive(CONS_Mutex);
}
@ -468,6 +479,8 @@ static void esp_ble_gap_cb(esp_gap_ble_cb_event_t Event, esp_ble_gap_cb_param_t
break;
case ESP_GAP_BLE_AUTH_CMPL_EVT: // #8 = AUTHentication CoMPLete
break;
case ESP_GAP_BLE_KEY_EVT: // #9 =
break;
case ESP_GAP_BLE_ADV_START_COMPLETE_EVT: // #6 = starting advertise complete
break;
default:
@ -504,8 +517,8 @@ int BT_SPP_Init(void)
Err = esp_bt_controller_enable((esp_bt_mode_t)BTconf.mode); if(Err!=ESP_OK) return Err; // mode must be same as in BTconf
Err = esp_bluedroid_init(); if(Err!=ESP_OK) return Err; // init the BT stack
Err = esp_bluedroid_enable(); if(Err!=ESP_OK) return Err; // enable the BT stack
Err = esp_ble_gap_register_callback(esp_ble_gap_cb); if(Err!=ESP_OK) return Err;
Err = esp_ble_gatts_register_callback(esp_ble_gatts_cb); if(Err!=ESP_OK) return Err;
Err = esp_ble_gap_register_callback(esp_ble_gap_cb); if(Err!=ESP_OK) return Err; // GAP callback
Err = esp_ble_gatts_register_callback(esp_ble_gatts_cb); if(Err!=ESP_OK) return Err; // GATTS callback
Err = esp_ble_gatts_app_register(ESP_SPP_APP_ID); if(Err!=ESP_OK) return Err;
esp_ble_io_cap_t IOcap = ESP_IO_CAP_NONE; // no input and no output capabilities

Wyświetl plik

@ -13,6 +13,10 @@
#include "driver/adc.h"
#include "esp_adc_cal.h"
#if ESP_IDF_VERSION_MINOR>=3
#include "soc/adc_channel.h" // v4.3
#endif
#include "esp_system.h"
#include "esp_freertos_hooks.h"
@ -278,7 +282,7 @@ GPIO HELTEC TTGO JACEK M5_JACEK T-Beam T-Beamv10 Foll
#ifdef WITH_TBEAM_V10
#ifdef WITH_SX1262
#define PIN_RFM_BUSY GPIO_NUM_32 // for the T-Beam with SX1262
#define PIN_RFM_BUSY GPIO_NUM_32 // for the T-Beam with SX1262 (watch for conflict with the LCD)
#endif
#endif
@ -302,7 +306,7 @@ GPIO HELTEC TTGO JACEK M5_JACEK T-Beam T-Beamv10 Foll
#define RFM_SPI_HOST VSPI_HOST // or H or VSPI_HOST ?
#define RFM_SPI_DMA 1 // DMA channel
#define RFM_SPI_SPEED 4000000 // [Hz] 4MHz SPI clock rate for RF chip
#define RFM_SPI_SPEED 4000000 // [Hz] 2MHz SPI clock rate for RF chip
#ifdef WITH_ST7789
#ifdef WITH_TBEAM // old T-Beam
@ -1726,7 +1730,7 @@ void IO_Configuration(void)
input_delay_ns : 0,
spics_io_num : PIN_RFM_SS,
flags : 0,
queue_size : 3,
queue_size : 1,
pre_cb : 0,
post_cb : 0
};

Wyświetl plik

@ -23,8 +23,8 @@ class LoRaWANnode
uint32_t JoinNonce; // from Join-Accept: unique must not be reused
uint32_t HomeNetID; // from Join-Accept: Home Network ID
uint32_t DevAddr; // from Join-Accept: Device Address
uint8_t DLsetting; // from Join-Accept: DownLink configuration: OptNeg | RX1DRoffset | RX2 data rate
uint8_t RxDelay; // from Join-Accept:
uint8_t DLsetting; // from Join-Accept: DownLink configuration: OptNeg:1 | RX1 data rate offset:3 | RX2 data rate:4
uint8_t RxDelay; // from Join-Accept: RFU:4 | Del:4 Del=1..15s for the RX1, RX2 delay is Del+1
uint8_t State; // 0:disconencted, 1:join-request sent, 2:join-accept received, 3:uplink-packet sent
uint8_t Chan; // [0..7] Current channel being used
uint32_t UpCount; // [seq] Uplink frame counter: reset when joining the network
@ -59,6 +59,9 @@ class LoRaWANnode
if(AppKey) memcpy(this->AppKey, AppKey, 16);
Reset(); }
void Disconnect(void)
{ State=0; }
uint8_t incrChan(uint8_t Step=1) { Chan+=Step; if(Chan>=Chans) Chan-=Chans; return Chan; }
int Save(FILE *File) { return fwrite(this, sizeof(LoRaWANnode), 1, File); }
@ -172,24 +175,26 @@ class LoRaWANnode
{ int Len=getDataPacket(Packet, Data, DataLen, Port, Confirm); *Pkt = Packet; return Len; }
int procRxData(const RFM_LoRa_RxPacket &RxPacket)
{ int Ret=procRxData(RxPacket.Byte, RxPacket.Len); if(Ret<0) return Ret;
RxSNR += (RxPacket.SNR-RxSNR+1)/2;
{ int Ret = procRxData(RxPacket.Byte, RxPacket.Len); if(Ret<0) return Ret;
RxSNR += (RxPacket.SNR-RxSNR+1)/2; // if good packet then update the signal statistics
RxRSSI += (RxPacket.RSSI-RxRSSI+1)/2;
return Ret; }
int procRxData(const uint8_t *PktData, int PktLen)
{ if(PktLen<12) return -1;
uint8_t Type = PktData[0]>>5; if(Type!=3 && Type!=5) return -1;
uint32_t Addr=readInt<uint32_t>(PktData+1, 4);
if(Addr!=DevAddr) return 0;
uint8_t Ctrl = PktData[5]; // Frame control: ADR | RFU | ACK | FPending | FOptLen[4]
uint32_t Count=readInt<uint32_t>(PktData+6, 2);
int16_t CountDiff = Count-DnCount; //
if(CountDiff<=0) return -1; // attempt to reuse the counter: drop this packet
uint8_t Type = PktData[0]>>5; if(Type!=3 && Type!=5) return -1; // Frame Type: 3=unconfirmed data downlink, 5=confirmed data downlink
uint32_t Addr=readInt<uint32_t>(PktData+1, 4); // device address
if(Addr!=DevAddr) return 0; // check if packet is for us (it could be for somebody else)
uint8_t Ctrl = PktData[5]; // Frame Control: ADR | RFU | ACK | FPending | FOptLen[4]
uint32_t Count = readInt<uint32_t>(PktData+6, 2); // download counter
int16_t CountDiff = Count-DnCount; // how many we have missed ?
if(CountDiff<=0) return -1; // attempt to reuse the counter: drop this packet
uint32_t MIC=0;
LoRaMacComputeMic(PktData, PktLen-4, NetSesKey, Addr, 0x01, Count, &MIC);
if(memcmp(PktData+PktLen-4, &MIC, 4)) return -1; // give up if MIC does not match
uint8_t DataOfs = 8 + (Ctrl&0x0F); // where the port byte should be
uint8_t OptLen = Ctrl&0x0F; // Options: how many bytes
uint8_t DataOfs = 8 + OptLen; // where the port byte should be
if(OptLen) procRxOpt(PktData+8, OptLen); // process the options (these are not encrypted)
uint8_t DataLen = PktLen-DataOfs-4; // number of bytes of the user data field
if(DataLen) // if non-zero
{ Packet[0] = PktData[DataOfs]; // copy port number
@ -205,8 +210,20 @@ class LoRaWANnode
if(Type==5) TxACK=1; // if ACK requested
RxPend = Ctrl&0x10; // is there more data pending to be received on next round ?
State=2;
// if(DataLen==0)
// { Packet[0]=0x00; DataLen++; // copy MAC commands to user buffer for debug
// for(uint8_t Idx=0; Idx<OptLen; Idx++)
// { Packet[DataLen++] = PktData[8+Idx]; }
// }
return DataLen; }
void procRxOpt(const uint8_t *Opt, uint8_t Len) // process the options
{ }
// { Format_String(CONS_UART_Write, "LoRaWAN Opt: ");
// for(uint8_t Idx=0; Idx<Len; Idx++)
// Format_Hex(CONS_UART_Write, Opt[Idx]);
// Format_String(CONS_UART_Write, "\n"); }
#ifdef WITH_ESP32
esp_err_t WriteToNVS(const char *Name="LoRaWAN", const char *NameSpace="TRACKER")
{ nvs_handle Handle;

Wyświetl plik

@ -79,6 +79,7 @@ void app_main(void)
{ WANdev.Reset(getUniqueID(), Parameters.AppKey); // then reset LoRaWAN to this key
WANdev.WriteToNVS(); } // and save LoRaWAN config. to NVS
Parameters.clrAppKey(); }
WANdev.Disconnect(); // restart with network join-request/accept at each restart
#endif
CONS_UART_SetBaudrate(Parameters.CONbaud);

Wyświetl plik

@ -60,6 +60,12 @@ static uint8_t RX_Channel=0; // (hopping) channel currently being
static void SetTxChannel(uint8_t TxChan=RX_Channel) // default channel to transmit is same as the receive channel
{
#ifdef WITH_SX1262
TRX.OGN_Configure(TxChan&0x7F, OGN_SYNC);
TRX.WaitWhileBusy_ms(2);
TRX.WriteTxPower(Parameters.TxPower);
TRX.WaitWhileBusy_ms(2);
#else // WITH_SX1262
#ifdef WITH_RFM69
TRX.WriteTxPower(Parameters.TxPower, Parameters.RFchipTypeHW); // set TX for transmission
#endif
@ -67,12 +73,20 @@ static void SetTxChannel(uint8_t TxChan=RX_Channel) // default channel t
TRX.WriteTxPower(Parameters.TxPower); // set TX for transmission
#endif
TRX.setChannel(TxChan&0x7F);
TRX.FSK_WriteSYNC(8, 7, OGN_SYNC); } // Full SYNC for TX
TRX.FSK_WriteSYNC(8, 7, OGN_SYNC); // Full SYNC for TX
#endif // WITH_SX1262
}
static void SetRxChannel(uint8_t RxChan=RX_Channel)
{ TRX.WriteTxPowerMin(); // setup for RX
{
#ifdef WITH_SX1262
// TRX.setChannel(RxChan&0x7F);
#else
TRX.WriteTxPowerMin(); // setup for RX
TRX.setChannel(RxChan&0x7F);
TRX.FSK_WriteSYNC(7, 7, OGN_SYNC); } // Shorter SYNC for RX
TRX.FSK_WriteSYNC(7, 7, OGN_SYNC); // Shorter SYNC for RX
#endif
}
static uint8_t ReceivePacket(void) // see if a packet has arrived
{ if(!TRX.DIO0_isOn()) return 0; // DIO0 line HIGH signals a new packet has arrived
@ -87,11 +101,12 @@ static uint8_t ReceivePacket(void) // see if a pack
RxPkt->msTime = TimeSync_msTime(); if(RxPkt->msTime<200) RxPkt->msTime+=1000;
RxPkt->Channel = RX_Channel; // store reception channel
RxPkt->RSSI = RxRSSI; // store signal strength
TRX.ReadPacketOGN(RxPkt->Data, RxPkt->Err); // get the packet data from the FIFO
// PktData.Print(); // for debug
TRX.OGN_ReadPacket(RxPkt->Data, RxPkt->Err); // get the packet data from the FIFO
RxPkt->Print(CONS_UART_Write); // for debug
RF_RxFIFO.Write(); // complete the write to the receiver FIFO
// TRX.setModeRX(); // back to receive (but we already have AutoRxRestart)
TRX.setModeRX(); // back to receive (but we already have AutoRxRestart)
TRX.ClearIrqFlags();
return 1; } // return: 1 packet we have received
static uint32_t ReceiveUntil(TickType_t End)
@ -131,8 +146,34 @@ static uint8_t Transmit(uint8_t TxChan, const uint8_t *PacketByte, uint8_t Thres
vTaskDelay(1);
SetTxChannel(TxChan);
#ifdef WITH_SX1262
TRX.OGN_WritePacket(PacketByte);
uint16_t PreFlags=TRX.ReadIrqFlags();
TRX.ClearIrqFlags();
TRX.WritePacketOGN(PacketByte); // write packet into FIFO
TRX.WaitWhileBusy_ms(10);
TickType_t TxDur = xTaskGetTickCount();
TRX.setModeTX(0);
TRX.WaitWhileBusy_ms(2);
for( uint16_t Wait=7; Wait; Wait--)
{ vTaskDelay(1);
uint16_t Flags=TRX.ReadIrqFlags();
if(Flags&IRQ_TXDONE) break; }
TxDur = xTaskGetTickCount()-TxDur;
TRX.setModeStandby();
#ifdef DEBUG_PRINT
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_String(CONS_UART_Write, "0x");
Format_Hex(CONS_UART_Write, PreFlags);
Format_String(CONS_UART_Write, " => Transmit() => 0x");
Format_Hex(CONS_UART_Write, TRX.getStatus());
Format_String(CONS_UART_Write, " ");
Format_UnsDec(CONS_UART_Write, TxDur);
Format_String(CONS_UART_Write, "ms\n");
xSemaphoreGive(CONS_Mutex);
#endif
#else
TRX.ClearIrqFlags();
TRX.OGN_WritePacket(PacketByte); // write packet into FIFO
TRX.setModeTX(); // transmit
vTaskDelay(5); // wait 5ms (about the OGN packet time)
uint8_t Break=0;
@ -142,9 +183,11 @@ static uint8_t Transmit(uint8_t TxChan, const uint8_t *PacketByte, uint8_t Thres
if(Break>=2) break; }
TRX.setModeStandby(); // switch to standy
// vTaskPrioritySet(0, tskIDLE_PRIORITY+2);
#endif
SetRxChannel();
TRX.setModeRX(); // back to receive mode
TRX.ClearIrqFlags();
return 1; }
// make a time-slot: listen for packets and transmit given PacketByte$
static void TimeSlot(uint8_t TxChan, uint32_t SlotLen, const uint8_t *PacketByte, uint8_t Rx_RSSI, uint8_t MaxWait=8, uint32_t TxTime=0)
@ -154,7 +197,7 @@ static void TimeSlot(uint8_t TxChan, uint32_t SlotLen, const uint8_t *PacketByte
if( (TxTime==0) || (TxTime>=MaxTxTime) ) TxTime = RX_Random%MaxTxTime; // if TxTime out of limits, setup a random TxTime
TickType_t Tx = Start + TxTime; // Tx = the moment to start transmission
ReceiveUntil(Tx); // listen until this time comes
if( (TX_Credit>0) && Parameters.TxPower!=(-32) && (PacketByte) ) // when packet to transmit is given and there is still TX credit left:
if( (TX_Credit>0) && Parameters.TxPower!=(-32) && (PacketByte) ) // when packet to transmit is given and there is still TX credit left:
if(Transmit(TxChan, PacketByte, Rx_RSSI, MaxWait)) TX_Credit-=5; // attempt to transmit the packet
ReceiveUntil(End); // listen till the end of the time-slot
}
@ -162,20 +205,84 @@ static void TimeSlot(uint8_t TxChan, uint32_t SlotLen, const uint8_t *PacketByte
static void SetFreqPlanOGN(void) // set the RF TRX according to the selected frequency hopping plan
{ TRX.setBaseFrequency(RF_FreqPlan.BaseFreq); // set the base frequency (recalculate to RFM69 internal synth. units)
TRX.setChannelSpacing(RF_FreqPlan.ChanSepar); // set the channel separation
TRX.setFrequencyCorrection(Parameters.RFchipFreqCorr); } // set the fine correction (to counter the Xtal error)
TRX.setFrequencyCorrection(Parameters.RFchipFreqCorr); // set the fine correction (to counter the Xtal error)
#ifdef DEBUG_PRINT
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_String(CONS_UART_Write, "SetFreqPlanOGN() ");
Format_UnsDec(CONS_UART_Write, TRX.BaseFrequency);
Format_String(CONS_UART_Write, " + [");
Format_UnsDec(CONS_UART_Write, TRX.ChannelSpacing);
Format_String(CONS_UART_Write, "] [32MHz/2^27]\n");
xSemaphoreGive(CONS_Mutex);
#endif
}
static void SetFreqPlanWAN(void) // set the LoRaWAN EU frequency plan: 8 LoRa channels
{ TRX.setBaseFrequency(867100000);
TRX.setChannelSpacing( 200000);
TRX.setFrequencyCorrection(Parameters.RFchipFreqCorr); }
/*
#ifdef WITH_SX1262
static int WaitWhileBusy(uint32_t MaxTime)
{ if(!TRX.readBusy()) return 0;
uint32_t Count=0;
for( ; Count<MaxTime; )
{ Count++; if(!TRX.readBusy()) break; }
#ifdef DEBUG_PRINT
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_String(CONS_UART_Write, "WaitWhileBusy(");
Format_UnsDec(CONS_UART_Write, MaxTime);
Format_String(CONS_UART_Write, ") => ");
Format_UnsDec(CONS_UART_Write, Count);
Format_String(CONS_UART_Write, "\n");
xSemaphoreGive(CONS_Mutex);
#endif
return Count; }
#endif
*/
// some LoRaWAN variables
static uint8_t StartRFchip(void)
{ TRX.setModeStandby();
vTaskDelay(1);
TRX.RESET(1); // RESET active
vTaskDelay(1); // wait 10ms
TRX.RESET(1); // RESET active: LOW for RFM95 and SX1262
vTaskDelay(1); // 100us for SX1262, p.50
TRX.RESET(0); // RESET released
vTaskDelay(5); // wait 10ms
#ifdef WITH_SX1262
TRX.WaitWhileBusy_ms(20);
// if(TRX.readBusy()) Format_String(CONS_UART_Write, "StartRFchip() sx1262 BUSY after RESET(0)\n");
// else Format_String(CONS_UART_Write, "StartRFchip() sx1262 NOT busy after reset\n");
TRX.setRegulator(1);
TRX.WaitWhileBusy_ms(5);
TRX.setRFswitchDIO2(1); // enable DIO0 as RF switch
TRX.WaitWhileBusy_ms(5);
// if(TRX.readBusy()) Format_String(CONS_UART_Write, "StartRFchip() sx1262 BUSY after setRFswitchDIO2()\n");
// WaitWhileBusy(100);
TRX.setTCXOctrlDIO3(1, 300); // TCXO control
TRX.WaitWhileBusy_ms(5);
// if(TRX.readBusy()) Format_String(CONS_UART_Write, "StartRFchip() sx1262 BUSY after setTCXOctrlDIO3()\n");
// WaitWhileBusy(100);
TRX.setModeStandby(0);
TRX.WaitWhileBusy_ms(5);
// if(TRX.readBusy()) Format_String(CONS_UART_Write, "StartRFchip() sx1262 BUSY after setModeStandby()\n");
// WaitWhileBusy(100);
// if(TRX.readBusy()) { Format_String(CONS_UART_Write, "StartRFchip() sx1262 still busy !\n"); }
TRX.setFSK();
TRX.WaitWhileBusy_ms(5);
#ifdef DEBUG_PRINT
{ uint8_t *SYNC = TRX.Regs_Read(REG_SYNCWORD0, 8);
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_String(CONS_UART_Write, "StartRFchip() => 0x");
Format_Hex(CONS_UART_Write, TRX.getStatus());
Format_String(CONS_UART_Write, " => 0x");
for(int Idx=0; Idx<8; Idx++)
{ Format_Hex(CONS_UART_Write, SYNC[Idx]); }
Format_String(CONS_UART_Write, "\n");
xSemaphoreGive(CONS_Mutex); }
#endif
#else // WITH_SX1262 // not WITH_SX1262
vTaskDelay(5); // wait 10ms
#endif
SetFreqPlanOGN(); // set TRX base frequency and channel separation after the frequency hopping plan
#ifdef DEBUG_PRINT
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
@ -186,11 +293,30 @@ static uint8_t StartRFchip(void)
// TRX.WriteDefaultReg();
// #endif
TRX.OGN_Configure(0, OGN_SYNC); // setup RF chip parameters and set to channel #0
#ifdef WITH_SX1262
TRX.WaitWhileBusy_ms(5);
#ifdef DEBUG_PRINT
{ uint8_t *SYNC = TRX.Regs_Read(REG_SYNCWORD0, 8);
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_String(CONS_UART_Write, "OGN_Configure() => 0x");
Format_Hex(CONS_UART_Write, TRX.getStatus());
Format_String(CONS_UART_Write, " => 0x");
for(int Idx=0; Idx<8; Idx++)
{ Format_Hex(CONS_UART_Write, SYNC[Idx]); }
Format_String(CONS_UART_Write, "\n");
xSemaphoreGive(CONS_Mutex); }
#endif
TRX.Calibrate();
TRX.WaitWhileBusy_ms(20);
if(TRX.readBusy()) Format_String(CONS_UART_Write, "StartRFchip() sx1262 BUSY after OGN_Configure() and Calibrate()\n");
#endif
TRX.setModeStandby(); // set RF chip mode to STANDBY
uint8_t Version = TRX.ReadVersion();
#ifdef DEBUG_PRINT
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
#ifdef WITH_RFM95
TRX.PrintReg(CONS_UART_Write);
#endif
Format_String(CONS_UART_Write, "StartRFchip() v");
Format_Hex(CONS_UART_Write, Version);
CONS_UART_Write(' ');
@ -204,7 +330,6 @@ static uint8_t StartRFchip(void)
#endif
return Version; } // read the RF chip version and return it
// some LoRaWAN variables
#ifdef WITH_LORAWAN
static uint8_t WAN_BackOff = 60; // back-off timer
static TickType_t WAN_RespTick = 0; // when to expect the WAN response
@ -230,7 +355,7 @@ extern "C"
TRX.Deselect = RFM_Deselect; // [call]
TRX.TransferByte = RFM_TransferByte; // [call]
#endif
TRX.DIO0_isOn = RFM_IRQ_isOn; // [call] read IRQ
TRX.DIO0_isOn = RFM_IRQ_isOn; // [call] read IRQ (it is DIO1 for sx1262)
#ifdef WITH_SX1262
TRX.Busy_isOn = RFM_Busy_isOn; // [call] read Busy
#endif
@ -263,6 +388,7 @@ extern "C"
RX_Channel = RF_FreqPlan.getChannel(TimeSync_Time(), 0, 1); // set initial RX channel
SetRxChannel();
TRX.setModeRX();
TRX.ClearIrqFlags();
RX_RSSI.Set(2*112);
@ -284,19 +410,20 @@ extern "C"
if(WANdev.State==1 || WANdev.State==3) // if State indicates we are waiting for the response
{ if(WAN_RespLeft<=5) WANdev.State--; // if time below 5 ticks we have not enough time
else if(WAN_RespLeft<200) { WANrx=1; } // if more than 200ms then we can't wait this long now
// xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
// Format_UnsDec(CONS_UART_Write, xTaskGetTickCount(), 4, 3);
// Format_String(CONS_UART_Write, "s LoRaWAN Rx: ");
// Format_SignDec(CONS_UART_Write, WAN_RespLeft);
// Format_String(CONS_UART_Write, "ms\n");
// xSemaphoreGive(CONS_Mutex);
if(WANrx==0 && WAN_RespLeft<=5)
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_UnsDec(CONS_UART_Write, xTaskGetTickCount(), 4, 3);
Format_String(CONS_UART_Write, "s LoRaWAN missed Rx: ");
Format_SignDec(CONS_UART_Write, WAN_RespLeft);
Format_String(CONS_UART_Write, "ms\n");
xSemaphoreGive(CONS_Mutex); }
}
if(WANrx) // if reception expected from WAN
{ int RxLen=0;
TRX.setModeStandby(); // TRX to standby
TRX.setModeStandby(); // TRX to standby
TRX.setLoRa(); // switch to LoRa mode (through sleep)
TRX.setModeLoRaStandby(); // TRX in standby
TRX.setModeLoRaStandby(); // TRX in LoRa (not FSK) standby
SetFreqPlanWAN(); // WAN frequency plan
TRX.WAN_Configure(); // LoRa for WAN config.
TRX.setChannel(WANdev.Chan); // set the channel
@ -306,7 +433,7 @@ extern "C"
for( ; Wait>0; Wait--)
{ vTaskDelay(1);
if(TRX.readIRQ()) break; } // IRQ signals packet reception
if(Wait)
if(Wait) // if no timeout thus a packet has been received.
{ TRX.LoRa_ReceivePacket(WAN_RxPacket);
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_UnsDec(CONS_UART_Write, xTaskGetTickCount(), 4, 3);
@ -316,41 +443,51 @@ extern "C"
Format_UnsDec(CONS_UART_Write, (unsigned)Wait);
Format_String(CONS_UART_Write, "ms\n");
xSemaphoreGive(CONS_Mutex);
if(WANdev.State==1) WANdev.procJoinAccept(WAN_RxPacket); // if join-request state then expect a join-accept packet
if(WANdev.State==1) WANdev.procJoinAccept(WAN_RxPacket); // if join-request state then expect a join-accept packet
else if(WANdev.State==3) RxLen=WANdev.procRxData(WAN_RxPacket); // if data send then respect ACK and/or downlink data packet
}
else WANdev.State--;
TRX.setFSK(); // back to FSK
SetFreqPlanOGN(); // OGN frequency plan
TRX.OGN_Configure(0, OGN_SYNC); // OGN config
else WANdev.State--; // if no packet received then retreat the State
TRX.setFSK(); // back to FSK
SetFreqPlanOGN(); // OGN frequency plan
TRX.OGN_Configure(0, OGN_SYNC); // OGN config
SetRxChannel();
TRX.setModeRX(); // switch to receive mode
WANdev.WriteToNVS(); // store new WAN state in flash
if(RxLen>0) // if Downlink data received
TRX.setModeRX(); // switch to receive mode
TRX.ClearIrqFlags();
WANdev.WriteToNVS(); // store new WAN state in flash
if(RxLen>0) // if Downlink data received
{ xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_String(CONS_UART_Write, "LoRaWAN Msg: ");
// Format_UnsDec(CONS_UART_Write, (uint16_t)RxLen);
// Format_String(CONS_UART_Write, "B");
for(int Idx=0; Idx<RxLen; Idx++)
{ Format_Hex(CONS_UART_Write, WANdev.Packet[Idx]); }
{ Format_Hex(CONS_UART_Write, WANdev.Packet[Idx]); } //
Format_String(CONS_UART_Write, "\n");
xSemaphoreGive(CONS_Mutex); }
}
else
#else
else // if no WAN reception expected or possible
#else // WITH_LORAWAN
// if(TimeSync_msTime()<260);
{ uint32_t RxRssiSum=0; uint16_t RxRssiCount=0; // measure the average RSSI for lower frequency
{ uint32_t RxRssiSum=0; uint16_t RxRssiCount=0; // measure the average RSSI for lower frequency
do
{ ReceivePacket(); // keep checking for received packets
{ ReceivePacket(); // keep checking for received packets
#ifdef WITH_RFM69
TRX.TriggerRSSI();
#endif
vTaskDelay(1);
uint8_t RxRSSI=TRX.ReadRSSI(); // measure the channel noise level
uint8_t RxRSSI=TRX.ReadRSSI(); // measure the channel noise level
RX_Random = (RX_Random<<1) | (RxRSSI&1);
RxRssiSum+=RxRSSI; RxRssiCount++;
} while(TimeSync_msTime()<270); // until 300ms from the PPS
RX_RSSI.Process(RxRssiSum/RxRssiCount); // [-0.5dBm] average noise on channel
} while(TimeSync_msTime()<270); // until 300ms from the PPS
RX_RSSI.Process(RxRssiSum/RxRssiCount); // [-0.5dBm] average noise on channel
#ifdef DEBUG_PRINT
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_String(CONS_UART_Write, "RSSI: ");
Format_UnsDec(CONS_UART_Write, RxRssiSum);
Format_String(CONS_UART_Write, "/");
Format_UnsDec(CONS_UART_Write, RxRssiCount);
Format_String(CONS_UART_Write, "\n");
xSemaphoreGive(CONS_Mutex);
#endif
}
#endif
@ -388,8 +525,8 @@ extern "C"
uint8_t TxChan = RF_FreqPlan.getChannel(RF_SlotTime, 0, 1); // tranmsit channel
RX_Channel = TxChan;
SetRxChannel();
// here we can read the chip temperature
TRX.setModeRX(); // switch to receive mode
TRX.setModeRX(); // switch to receive mode
TRX.ClearIrqFlags(); // here we can read the chip temperature
vTaskDelay(1);
uint32_t RxRssiSum=0; uint16_t RxRssiCount=0; // measure the average RSSI for the upper frequency
@ -469,10 +606,11 @@ extern "C"
TRX.setFSK();
TRX.OGN_Configure(0, OGN_SYNC);
}
#endif
#endif // WITH_FANET
SetRxChannel();
TRX.setModeRX(); // switch to receive mode
TRX.ClearIrqFlags();
XorShift32(RX_Random);
TxTime = (RX_Random&0x3F)+1; TxTime*=6; // [ms] (1..64)*6 = 6..384ms
@ -482,7 +620,7 @@ extern "C"
if(WAN_BackOff) WAN_BackOff--;
else if(Parameters.TxPower!=(-32)) // decide to transmit in this slot
{ if(WANdev.State==0 || WANdev.State==2) //
{ WANtx=1; SlotEnd=1200; }
{ WANtx=1; SlotEnd=1220; }
}
TimeSlot(TxChan, SlotEnd-TimeSync_msTime(), TxPktData1, TRX.averRSSI, 0, TxTime);
#else
@ -506,14 +644,22 @@ extern "C"
TRX.WriteTxPower(Parameters.TxPower+6);
vTaskDelay(RX_Random&0x3F);
TRX.ClearIrqFlags();
TRX.WritePacketPAW(Packet.Byte, 24);
TRX.PAW_WritePacket(Packet.Byte, 24);
TRX.setModeTX();
vTaskDelay(8); // wait 8ms (about the PAW packet time)
#ifdef WITH_SX1262
TRX.WaitWhileBusy_ms(2);
for( uint16_t Wait=7; Wait; Wait--)
{ vTaskDelay(1);
uint16_t Flags=TRX.ReadIrqFlags();
if(Flags&IRQ_TXDONE) break; }
#else
uint8_t Break=0;
for(uint16_t Wait=400; Wait; Wait--) // wait for transmission to end
{ uint16_t Flags=TRX.ReadIrqFlags();
if(Flags&RF_IRQ_PacketSent) Break++;
if(Break>=2) break; }
#endif
TRX.setModeStandby();
TRX.OGN_Configure(0, OGN_SYNC);
PAWtxBackOff = 2+(RX_Random%5); XorShift32(RX_Random);
@ -552,7 +698,7 @@ extern "C"
{ TxPktLen=WANdev.getDataPacket(&TxPacket, PktData+4, 16, 1, ((RX_Random>>16)&0xF)==0x8 ); }
else
{ TxPktLen=WANdev.getDataPacket(&TxPacket, PktData, 20, 1, ((RX_Random>>16)&0xF)==0x8 ); }
TRX.LoRa_SendPacket(TxPacket, TxPktLen); RespDelay=1000;
TRX.LoRa_SendPacket(TxPacket, TxPktLen); RespDelay = WANdev.RxDelay&0x0F; if(RespDelay<1) RespDelay=1; RespDelay*=1000;
WAN_BackOff=50+(RX_Random%21); XorShift32(RX_Random); }
}
if(RespDelay)
@ -561,7 +707,7 @@ extern "C"
{ vTaskDelay(1); if(!TRX.isModeLoRaTX()) break; }
// uint8_t Mode=TRX.ReadMode();
// if(Mode!=RF_OPMODE_LORA_TX) break; }
WAN_RespTick=xTaskGetTickCount()+RespDelay; // when to expect the response: 5sec after the end of Join-Request packet
WAN_RespTick=xTaskGetTickCount()+RespDelay; // when to expect the response after the end of transmitted packet
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
Format_UnsDec(CONS_UART_Write, xTaskGetTickCount(), 4, 3);
Format_String(CONS_UART_Write, "s LoRaWAN Tx: ");
@ -574,6 +720,7 @@ extern "C"
TRX.OGN_Configure(0, OGN_SYNC); // OGN config
SetRxChannel();
TRX.setModeRX(); // switch to receive mode
TRX.ClearIrqFlags();
}
#endif

Wyświetl plik

@ -16,7 +16,8 @@ class RFM_LoRa_Config
union
{ uint32_t Word;
struct
{ uint8_t Spare :3;
{ uint8_t Spare :2;
uint8_t InvIQ :1; // 0..1, invert IQ (common for Rx/Tx for the SX1262 chip)
uint8_t LowRate :1; // 0..1, optimize for low-rate (strips two lowest bits of every symbol)
uint8_t TxInv :1; // 0..1, invert on TX
uint8_t RxInv :1; // 0..1, invert on RX <- probably inverted logic
@ -47,8 +48,8 @@ class RFM_LoRa_Config
} ;
const RFM_LoRa_Config RFM_FNTcfg { 0xF1587190 } ; // LoRa seting for FANET
const RFM_LoRa_Config RFM_WANcfg { 0x34877190 } ; // LoRa WAN setting for TX
const RFM_LoRa_Config RFM_FNTcfg { 0xF1587194 } ; // LoRa seting for FANET
const RFM_LoRa_Config RFM_WANcfg { 0x34877194 } ; // LoRa WAN setting for TX
class RFM_LoRa_RxPacket
{ public:
@ -66,8 +67,8 @@ class RFM_LoRa_RxPacket
static const int MaxBytes = 40;
uint8_t Byte[MaxBytes+2];
uint32_t sTime; // [ s] reception time
uint16_t msTime; // [ms]
uint32_t sTime; // [ s] reception time: seconds
uint16_t msTime; // [ms] reception time: miliseconds
int16_t FreqOfs; // [ 10Hz]
int8_t SNR; // [0.25dB]
int8_t RSSI; // [dBm]
@ -85,13 +86,13 @@ class RFM_LoRa_RxPacket
} ;
class RFM_FSK_RxPktData // OGN packet received by the RF chip
class RFM_FSK_RxPktData // OGN packet received by the RF chip
{ public:
static const uint8_t Bytes=26; // [bytes] number of bytes in the packet
uint32_t Time; // [sec] Time slot
uint16_t msTime; // [ms] reception time since the PPS[Time]
uint8_t Channel; // [] channel where the packet has been recieved
uint8_t RSSI; // [-0.5dBm]
uint8_t Channel; // [ ] channel where the packet has been recieved
uint8_t RSSI; // [-0.5dBm] receiver signal strength
uint8_t Data[Bytes]; // Manchester decoded data bits/bytes
uint8_t Err [Bytes]; // Manchester decoding errors
@ -154,6 +155,50 @@ class RFM_FSK_RxPktData // OGN packet received by the RF chip
// -----------------------------------------------------------------------------------------------------------------------
/*
SX1262 setup calls
.Cmd_Writet(0x80, 0x00);
.Cmd_Writet(0x96, 0x01); // set regulator mode: 0=only LDO, 1=DC-DC+LDO
.Cmd_Writet(0x9D, 0x01); // DIO2 as RF switch
.Cmd_Writet(0x97, 0x0100012C); // DIO3 as TCXO control: voltage, timeout
.Cmd_Writet(0x80, 0x00); // set Standby 00=RC 01=Xtal
.Cmd_Writet(0x8A, 0x00); // 0=FSK 1=LoRa
.Cmd_Writet(0x86, 0x36433333); // set frequency [32.0MHz/2^25]
.Cmd_Writet(0x8B, 0x00 28 00 09 0A 00 CC CD); // set modulation parameters: bitrate, BT, bandwidth, deviation
.Cmd_Writet(0x8C, 0x00 04 00 40 00 00 34 01 00); // set packet parameters: preamble len. preamble det. len. sync. len. payload len.
.Regs_Write(0x06C0, 0xAA6655A59699965A); // SYNC
.Cmd_Writet(0x80, 0x00); // set standby
.Cmd_Writet(0x82, 0x000000); // set RX mode
.Cmd_Writet(0x80, 0x00); // set standby
.Cmd_Writet(0x86, 0x36466667); // set frequency 868.4MHz
.Cmd_Writet(0x8B, 0x002800090A00CCCD); // set modulation parameters
.Cmd_Writet(0x8C, 0x000400400000340100); // set packet parameters
.Cmd_Writet(0x95, 0x04 07 00 01); // PA config
.Cmd_Writet(0x8E, 0x0E04); // TX parm: power and ramp time
.Cmd_Writet(0x8F, 0x8000); // set TX/RX buffer address: TX=0x80, RX=0x00
.Cmd_Writet(0x83, 0x000000); // set TX mode: timeout [15.625us]
.Cmd_Writet(0x80, 0x00); // set standby
... transmission ...
.Cmd_Writet(0x82, 0x000000); // set RX mode: timeout [15.625us] 000000 = single mode, FFFFFF = continous mode
.Cmd_Writet(0x80, 0x00); // set standby
.Cmd_Writet(0x82, 0x000000); // set RX mode
.Cmd_Writet(0x80, 0x00); // set standby
.Cmd_Writet(0x86, 0x36433333); // set frequency
.Cmd_Writet(0x8B, 0x002800090A00CCCD);
.Cmd_Writet(0x8C, 0x000400400000340100);
.Cmd_Writet(0x95, 0x04070001);
.Cmd_Writet(0x8E, 0x0E04);
.Cmd_Writet(0x8F, 0x8000);
.Cmd_Writet(0x83, 0x000000);
.Cmd_Writet(0x80, 0x00);
... transmission ...
.Cmd_Writet(0x82, 0x000000);
*/
// -----------------------------------------------------------------------------------------------------------------------
// OGN frequencies for Europe: 868.2 and 868.4 MHz
// static const uint32_t OGN_BaseFreq = 868200000; // [Hz] base frequency
// static const uint32_t OGN_ChanSpace = 0200000; // [Hz] channel spacing
@ -198,12 +243,12 @@ class RFM_FSK_RxPktData // OGN packet received by the RF chip
#ifdef WITH_SX1262
#include "sx1262.h"
#define RF_IRQ_PacketSent 0x0001 // packet transmission was completed
#define RF_IRQ_PayloadReady 0x0002 //
#define RF_IRQ_PreambleDetect 0x0004 //
#define RF_IRQ_SyncAddrMatch 0x0008 //
#define RF_IRQ_CrcErr 0x0040 //
#define RF_IRQ_Timeout 0x0200 //
// #define RF_IRQ_PacketSent 0x0001 // packet transmission was completed
// #define RF_IRQ_PayloadReady 0x0002 //
// #define RF_IRQ_PreambleDetect 0x0004 //
// #define RF_IRQ_SyncAddrMatch 0x0008 //
// #define RF_IRQ_CrcErr 0x0040 //
// #define RF_IRQ_Timeout 0x0200 //
#endif
@ -251,36 +296,99 @@ class RFM_TRX
return Block_Buffer+1; }
#ifdef WITH_SX1262
uint16_t WaitWhileBusy(uint16_t Loops=100) // 50 seems to be still too short on RPI
{ for( ; Loops; Loops--)
{ if(!readBusy()) break; }
return Loops; }
uint16_t WaitWhileBusy_ms(uint16_t ms=10)
{ WaitWhileBusy(50);
for( ; ms; ms--)
{ if(!readBusy()) break;
Delay_ms(1); }
return ms; }
uint8_t *Cmd_Write(uint8_t Cmd, const uint8_t *Data, uint8_t Len) // command code, Data[Len]
{ return Block_Write(Data, Len, Cmd); }
{ WaitWhileBusy_ms(); // if(WaitWhileBusy()==0) return 0;
#ifdef DEBUG_PRINT
if(readBusy())
{ Format_String(CONS_UART_Write, "Cmd_Write(0x");
Format_Hex(CONS_UART_Write, Cmd);
Format_String(CONS_UART_Write, ") => RF busy !\n"); }
CONS_UART_Write(readBusy()?'!':'.'); // Busy-line state
Format_String(CONS_UART_Write, "Cmd_Write(0x");
Format_Hex(CONS_UART_Write, Cmd);
Format_String(CONS_UART_Write, ", 0x");
for(uint8_t Idx=0; Idx<Len; Idx++)
Format_Hex(CONS_UART_Write, Data[Idx]);
Format_String(CONS_UART_Write, ");\n");
#endif
return Block_Write(Data, Len, Cmd); }
// { uint8_t *Ret = Block_Write(Data, Len, Cmd); printf("Cmd_Write: %02X %02X\n", Ret[0], Ret[1]); return Ret; }
uint8_t *Cmd_Read(uint8_t Cmd, uint8_t Len)
{ Block_Buffer[0] = Cmd; memset(Block_Buffer+1, 0, Len+1);
{ WaitWhileBusy_ms(); // if(WaitWhileBusy()==0) return 0;
Block_Buffer[0] = Cmd; memset(Block_Buffer+1, 0, Len+1);
(*TransferBlock) (Block_Buffer, Len+2);
#ifdef DEBUG_PRINT
CONS_UART_Write(readBusy()?'!':'.'); // Busy-line state
Format_String(CONS_UART_Write, "Cmd_Read(0x");
Format_Hex(CONS_UART_Write, Cmd);
Format_String(CONS_UART_Write, ") => 0x");
for(uint8_t Idx=0; Idx<Len+2; Idx++)
Format_Hex(CONS_UART_Write, Block_Buffer[Idx]);
Format_String(CONS_UART_Write, ";\n");
#endif
return Block_Buffer+2; }
uint8_t *Regs_Write(uint16_t Addr, const uint8_t *Data, uint8_t Len) // register-write code, 2-byte Address, Data[Len]
{ Block_Buffer[0] = CMD_WRITEREGISTER; Block_Buffer[1] = Addr>>8; Block_Buffer[2] = Addr; memcpy(Block_Buffer+3, Data, Len);
{ WaitWhileBusy_ms(); // if(WaitWhileBusy()==0) return 0;
#ifdef DEBUG_PRINT
CONS_UART_Write(readBusy()?'!':'.'); // Busy-line state
Format_String(CONS_UART_Write, "Regs_Write(0x");
Format_Hex(CONS_UART_Write, Addr);
Format_String(CONS_UART_Write, ", 0x");
for(uint8_t Idx=0; Idx<Len; Idx++)
Format_Hex(CONS_UART_Write, Data[Idx]);
Format_String(CONS_UART_Write, ");\n");
#endif
Block_Buffer[0] = CMD_WRITEREGISTER; Block_Buffer[1] = Addr>>8; Block_Buffer[2] = Addr; memcpy(Block_Buffer+3, Data, Len);
(*TransferBlock) (Block_Buffer, Len+3);
return Block_Buffer+3; }
uint8_t *Regs_Read(uint16_t Addr, const uint8_t *Data, uint8_t Len) // register-read code, 2-byte Address, zero, Data[Len]
{ Block_Buffer[0] = CMD_READREGISTER; Block_Buffer[1] = Addr>>8; Block_Buffer[2] = Addr; memset(Block_Buffer+3, 0, Len+1);
uint8_t *Regs_Read(uint16_t Addr, uint8_t Len) // register-read code, 2-byte Address, zero, Data[Len]
{ WaitWhileBusy_ms(); // if(WaitWhileBusy()==0) return 0;
Block_Buffer[0] = CMD_READREGISTER; Block_Buffer[1] = Addr>>8; Block_Buffer[2] = Addr; memset(Block_Buffer+3, 0, Len+1);
(*TransferBlock) (Block_Buffer, Len+4);
return Block_Buffer+4; }
uint8_t *Buff_Write(uint8_t Ofs, const uint8_t *Data, uint8_t Len) // buffer-write code, 1-byte offset, Data[Len]
{ Block_Buffer[0] = CMD_WRITEBUFFER; Block_Buffer[1] = Ofs; memcpy(Block_Buffer+2, Data, Len);
{ WaitWhileBusy_ms(); // if(WaitWhileBusy()==0) return 0;
#ifdef DEBUG_PRINT
if(readBusy())
{ Format_String(CONS_UART_Write, "Buff_Write(0x");
Format_Hex(CONS_UART_Write, Ofs);
Format_String(CONS_UART_Write, ") => RF busy !\n"); }
CONS_UART_Write(readBusy()?'!':'.'); // Busy-line state
Format_String(CONS_UART_Write, "Buff_Write(0x");
Format_Hex(CONS_UART_Write, Ofs);
Format_String(CONS_UART_Write, ", 0x");
for(uint8_t Idx=0; Idx<Len; Idx++)
Format_Hex(CONS_UART_Write, Data[Idx]);
Format_String(CONS_UART_Write, ");\n");
#endif
Block_Buffer[0] = CMD_WRITEBUFFER; Block_Buffer[1] = Ofs; memcpy(Block_Buffer+2, Data, Len);
(*TransferBlock) (Block_Buffer, Len+2);
return Block_Buffer+2; }
uint8_t *Buff_Read(uint8_t Ofs, uint8_t Len) // buffer-read code, 1-byte offset, zero, Data[Len]
{ Block_Buffer[0] = CMD_READBUFFER; Block_Buffer[1] = Ofs; memset(Block_Buffer+2, 0, Len+1);
{ WaitWhileBusy_ms(); // if(WaitWhileBusy()==0) return 0;
Block_Buffer[0] = CMD_READBUFFER; Block_Buffer[1] = Ofs; memset(Block_Buffer+2, 0, Len+1);
(*TransferBlock) (Block_Buffer, Len+3);
return Block_Buffer+3; }
#endif
#else // SPI transfers as single bytes, explicit control of the SPI-select
#else // USE_BLOCK_SPI // SPI transfers as single bytes, explicit control of the SPI-select
void (*Select)(void); // activate SPI select
void (*Deselect)(void); // desactivate SPI select
uint8_t (*TransferByte)(uint8_t); // exchange one byte through SPI
@ -289,14 +397,14 @@ class RFM_TRX
void (*Delay_ms)(int ms);
bool (*DIO0_isOn)(void); // read DIO0 = packet is ready
#ifdef WITH_SX1262
bool (*Busy_isOn)(void); //
bool (*Busy_isOn)(void); // sx1262 has an additional BUSY line
#endif
// bool (*DIO4_isOn)(void);
void (*RESET)(uint8_t On); // activate or desactivate the RF chip reset
bool readIRQ(void) { return (*DIO0_isOn)(); }
#ifdef WITH_SX1262
bool readBusy(void) { return (*Busy_isOn)(); }
bool readBusy(void) { return (*Busy_isOn)(); } // read the BUSY line of the sx1262
#endif
// the following are in units of the synthesizer with 8 extra bits of precision
uint32_t BaseFrequency; // [32MHz/2^19/2^8] base frequency = channel #0
@ -404,7 +512,7 @@ class RFM_TRX
#endif
#ifdef WITH_SX1262
void WriteFreq(uint32_t Freq) // [32MHz/2^27] Set center frequency
void WriteFreq(uint32_t Freq) // [32MHz/2^27] set transmission frequency
{ uint8_t Buff[4];
Freq = (Freq+2)>>2; // [32MHz/2^25]
Buff[0] = Freq>>24;
@ -416,24 +524,27 @@ class RFM_TRX
void WriteFIFO(const uint8_t *Data, uint8_t Len)
{ const uint8_t BaseOfs[2] = { 0x80, 0x00 }; // TX, RX offsets in the 256-byte buffer
Cmd_Write(CMD_SETBUFFERBASEADDRESS, BaseOfs, 2);
Buff_Write(BaseOfs[0], Data, Len); }
Buff_Write(0x80, Data, Len); }
uint8_t *ReadFIFO(uint8_t Len)
{ uint8_t *BuffStat = Cmd_Read(CMD_GETRXBUFFERSTATUS, 2); // length, offset
return Buff_Read(BuffStat[1], BuffStat[0]); }
#endif
void WritePacketOGN(const uint8_t *Data, uint8_t Len=26) // write the packet data (26 bytes)
void FNT_WritePacket(const uint8_t *Data, uint8_t Len)
{ WriteFIFO(Data, Len); }
void OGN_WritePacket(const uint8_t *Data, uint8_t Len=26) // write the packet data (26 bytes)
{ uint8_t Packet[2*Len];
uint8_t PktIdx=0;
for(uint8_t Idx=0; Idx<Len; Idx++)
{ uint8_t Byte=Data[Idx];
Packet[PktIdx++]=ManchesterEncode[Byte>>4]; // software manchester encode every byte
Packet[PktIdx++]=ManchesterEncode[Byte>>4]; // software manchester encode every byte
Packet[PktIdx++]=ManchesterEncode[Byte&0x0F];
}
WriteFIFO(Packet, 2*Len); }
void WritePacketPAW(const uint8_t *Data, uint8_t Len=24)
void PAW_WritePacket(const uint8_t *Data, uint8_t Len=24)
{ uint8_t Packet[Len+1];
for(uint8_t Idx=0; Idx<Len; Idx++)
{ Packet[Idx] = Data[Idx]; }
@ -441,7 +552,7 @@ class RFM_TRX
Packet[Len] = PAW_Packet::CRC8(Packet, Len);
WriteFIFO(Packet, Len+1); }
void ReadPacketOGN(uint8_t *Data, uint8_t *Err, uint8_t Len=26) // read packet data from FIFO
void OGN_ReadPacket(uint8_t *Data, uint8_t *Err, uint8_t Len=26) // read packet data from FIFO
{ uint8_t *Packet = ReadFIFO(2*Len); // read 2x26 bytes from the RF chip RxFIFO
uint8_t PktIdx=0;
for(uint8_t Idx=0; Idx<Len; Idx++) // loop over packet bytes
@ -514,7 +625,7 @@ class RFM_TRX
TransferByte(Data[Idx]);
Deselect(); }
void WritePacketOGN(const uint8_t *Data, uint8_t Len=26) const // write the packet data (26 bytes)
void OGN_WritePacket(const uint8_t *Data, uint8_t Len=26) const // write the packet data (26 bytes)
{ const uint8_t Addr=REG_FIFO; // write to FIFO
Select();
TransferByte(Addr | 0x80);
@ -525,7 +636,7 @@ class RFM_TRX
}
Deselect(); }
void WritePacketPAW(const uint8_t *Data, uint8_t Len=24)
void PAW_WritePacket(const uint8_t *Data, uint8_t Len=24)
{ uint8_t Packet[Len+1];
for(uint8_t Idx=0; Idx<Len; Idx++)
{ Packet[Idx] = Data[Idx]; }
@ -562,7 +673,7 @@ class RFM_TRX
if(WriteSize>8) WriteSize=8; // up to 8 bytes of SYNC can be programmed
WriteBytes(SyncData+(8-WriteSize), WriteSize, REG_SYNCVALUE1); // write the SYNC, skip some initial bytes
WriteByte( 0x80 | ((WriteSize-1)<<3) | SyncTol, REG_SYNCCONFIG); // write SYNC length [bytes] and tolerance to errors [bits]
WriteWord( 9-WriteSize, REG_PREAMBLEMSB); } // write preamble length [bytes] (page 71)
WriteWord( /* 9-WriteSize, */ 1, REG_PREAMBLEMSB); } // write preamble length [bytes] (page 71)
// ^ 8 or 9 ?
#endif
@ -571,22 +682,142 @@ class RFM_TRX
{ if(SyncTol>7) SyncTol=7;
if(WriteSize>8) WriteSize=8;
WriteBytes(SyncData+(8-WriteSize), WriteSize, REG_SYNCVALUE1); // write the SYNC, skip some initial bytes
WriteByte( 0x90 | (WriteSize-1), REG_SYNCCONFIG); // write SYNC length [bytes] (or 0xB0 for reversed preamble) => p.92
WriteWord( 9-WriteSize, REG_PREAMBLEMSB); } // write preamble length [bytes] (page 71)
WriteByte( 0x90 | (WriteSize-1), REG_SYNCCONFIG); // write SYNC length [bytes] AAPS_sss
WriteWord( /* 9-WriteSize, */ 1, REG_PREAMBLEMSB); } // write preamble length [bytes] (page 71)
// ^ 8 or 9 ?
#endif
#ifdef WITH_SX1262
void WriteTxPower(int8_t TxPower) { }
void WriteTxPowerMin(void) { WriteTxPower(0); }
void FSK_WriteSYNC(uint8_t WriteSize, uint8_t SyncTol, const uint8_t *SyncData) { }
void OGN_Configure(int16_t Channel, const uint8_t *Sync) { }
void ClearIrqFlags(uint16_t Mask=0xFFFF) { uint8_t Data[2]; Data[0]=Mask>>8; Data[1]=Mask; Cmd_Write(CMD_CLEARIRQSTATUS, Data, 2); }
uint16_t ReadIrqFlags(void) { uint8_t *Stat=Cmd_Read(CMD_GETIRQSTATUS, 2); return 0x0000; }
void setModeSleep(void) { uint8_t Config[3] = { 0,0,0 }; Cmd_Write(CMD_SETSLEEP, Config, 3); }
void setModeStandby(void) { uint8_t Config[1] = { 1 }; Cmd_Write(CMD_SETSTANDBY, Config, 1); }
void setModeTX(uint32_t Timeout=0) { uint8_t T[3]; T[0]=Timeout>>16; T[1]=Timeout>>8; T[2]=Timeout; Cmd_Write(CMD_SETTX, T, 3); }
void setModeRX(uint32_t Timeout=0) { uint8_t T[3]; T[0]=Timeout>>16; T[1]=Timeout>>8; T[2]=Timeout; Cmd_Write(CMD_SETRX, T, 3); }
void setTCXOctrlDIO3(uint8_t Volt=1, uint32_t Delay=320) // [0..7 => 1.6-3.3V] [1/64ms] p.82
{ uint8_t Data[4] = { Volt, (uint8_t)(Delay>>16), (uint8_t)(Delay>>8), (uint8_t)Delay }; Cmd_Write(CMD_SETDIO3ASTCXOCTRL, Data, 4); }
void setRFswitchDIO2(uint8_t Mode=0) { Cmd_Write(CMD_SETDIO2ASRFSWITCHCTRL, &Mode, 1); } // enable DIO2 as RF switch
void setRegulator(uint8_t Mode=0) { Cmd_Write(CMD_SETREGULATORMODE, &Mode, 1); } // 0=LDO, 1=DCDC+LDO
void setModulation(uint8_t Mode=0) { Cmd_Write(CMD_SETPACKETTYPE, &Mode, 1); } // 0=FSK, 1=LoRa
void setLoRa(void) { setModulation(0x01); } // switch to LoRa
void setFSK(void) { setModulation(0x00); } // switch to FSK
uint8_t getModulation(void) { return Cmd_Read(CMD_GETPACKETTYPE, 1)[0]; }
uint8_t getStatus(void) { return Cmd_Read(CMD_GETSTATUS, 0)[-1]; } // RMMM SSSR MMM: 2=STBY_RC, 3=STBY_XOSC, 4:FS, 5:RX, 6:TX p.95
void WriteTxPower(int8_t TxPower)
{ if(TxPower>22) TxPower=22; // for high power PA
else if(TxPower<(-9)) TxPower=(-9);
uint8_t PAparm[4] = { 0x04, 0x07, 0x00, 0x01 } ; // for high power PA: paDutyCycle, hpMax, deviceSel, paLut
Cmd_Write(CMD_SETPACONFIG, PAparm, 4); // Power Amplifier Configuration
uint8_t TxParm[2] = { (uint8_t)TxPower, 0x04 } ; // RampTime = 200us
Cmd_Write(CMD_SETTXPARAMS, TxParm, 2); } // 0x8E, Power, RampTime
void WriteTxPowerMin(void) { WriteTxPower(-8); }
void Calibrate(void) // Calibrate receiver image rejection
{ uint8_t CalParm[2] = { 0xD7, 0xDB }; // for 868MHz // { 0xE1, 0xE9 } for 915MHz
Cmd_Write(CMD_SETTXPARAMS, CalParm, 2); }
void FSK_WriteSYNC(uint8_t WriteSize, uint8_t SyncTol, const uint8_t *SyncData)
{ if(SyncTol>7) SyncTol=7;
if(WriteSize>8) WriteSize=8;
uint8_t Param[12];
Param[0] = 0; //
Param[1] = 4; // [bits] preamble length
Param[2] = 0x04; // preamble detect: 0x00:OFF, 0x04:8bits, 0x05:16bits, 0x06=24bits, 0x07=32bits
Param[3] = WriteSize*8; // [bits] SYNC word length, write word at 0x06C0
Param[4] = 0x00; // address filtering: OFF
Param[5] = 0x00; // fixed packet size
Param[6] = 2*26; // 26 bytes, software Manchester
Param[7] = 0x01; // no CRC
Param[8] = 0x00; // no whitening
Cmd_Write(CMD_SETPACKETPARAMS, Param, 9); // 0x8C, PacketParam
Regs_Write(REG_SYNCWORD0, SyncData+(8-WriteSize), WriteSize); } // Write the SYNC word
static void Pack3bytes(uint8_t *Byte, uint32_t Value) { Byte[0]=Value>>16; Byte[1]=Value>>8; Byte[2]=Value; }
void FNT_Configure(uint8_t CR=1) // configure for FANET/LoRa
{ WriteTxPower(0);
RFM_LoRa_Config CFG = RFM_FNTcfg; CFG.CR=CR;
LoRa_Configure(CFG, FANET_Packet::MaxBytes); }
void LoRa_Configure(RFM_LoRa_Config CFG, uint8_t MaxSize=64)
{ setChannel(0);
uint8_t Param[8];
Param[0] = CFG.SF; // Spreading Factor
Param[1] = CFG.BW-3; // work only for 62.5/125/256/512kHz
Param[2] = CFG.CR; // Coding Rate
Param[3] = CFG.LowRate; // Low-Rate optimize
Cmd_Write(CMD_SETMODULATIONPARAMS, Param, 4); // 0x8B, ModParam
Param[0] = 0x00;
Param[1] = CFG.Preamble; // preamble size
Param[2] = CFG.IHDR; // implicit header
Param[3] = MaxSize; // [bytes]
Param[4] = CFG.CRC; // check or not CRC
Param[5] = CFG.InvIQ; // common flag for Tx/Rx
Cmd_Write(CMD_SETPACKETPARAMS, Param, 6); // 0x8C, PacketParam
setDioMode( /* IRQ_TXDONE | */ IRQ_RXDONE);
Param[0] = (CFG.SYNC&0xF0) | 0x04;
Param[1] = (CFG.SYNC<<4) | 0x04;
Regs_Write(REG_LORASYNCWORD, Param, 2); }
void OGN_Configure(int16_t Channel, const uint8_t *SyncData)
{ setChannel(Channel);
uint8_t Param[12];
Pack3bytes(Param, 10240); // data bitrate = 32*Xtal/100e3 for OGN 100kbps
Param[3] = 0x09; // 0x00:no filter, 0x08:BT=0.3, 0x09:BT=0.5, 0x0A:BT=0.7, 0x0B:BT=1.0
Param[4] = 0x0A; // DSB RX bandwidth: 0x0A=232.3kHz, 0x19=312.2kHz, 0x1B=78.2kHz, 0x13=117.3kHz
Pack3bytes(Param+5, 52429); // FSK deviation: 50e3*2^25/Xtal for OGN +/-50kHz
Cmd_Write(CMD_SETMODULATIONPARAMS, Param, 8); // 0x8B, ModParam
Param[0] = 0; //
Param[1] = 4; // [bits] preamble length
Param[2] = 0x00; // preamble detect: 0x00:OFF, 0x04:8bits, 0x05:16bits, 0x06=24bits, 0x07=32bits
Param[3] = 8*8; // [bits] SYNC word length, write word at 0x06C0
Param[4] = 0x00; // address filtering: OFF
Param[5] = 0x00; // fixed packet size
Param[6] = 2*26; // 26 bytes, software Manchester
Param[7] = 0x01; // no CRC
Param[8] = 0x00; // no whitening
Cmd_Write(CMD_SETPACKETPARAMS, Param, 9); // 0x8C, PacketParam
setDioMode(/* IRQ_TXDONE | */ IRQ_RXDONE);
Regs_Write(REG_SYNCWORD0, SyncData, 8); } // Write the SYNC word
void PAW_Configure(const uint8_t *Sync)
{ setFrequency(869525000);
uint8_t Param[12];
Pack3bytes(Param, 26667); // data bitrate = 32*Xtal/38.4e3 for PAW 38.4kbps
Param[3] = 0x09; // 0x00:no filter, 0x08:BT=0.3, 0x09:BT=0.5, 0x0A:BT=0.7, 0x0B:BT=1.0
Param[4] = 0x18; // DSB RX bandwidth: 0x0A=232.3kHz, 0x19=312.2kHz, 0x1B=78.2kHz, 0x13=117.3kHz
Pack3bytes(Param+5, 10066); // FSK deviation: 9.6e3*2^25/Xtal for PAW +/-9.6kHz
Cmd_Write(CMD_SETMODULATIONPARAMS, Param, 8); // 0x8B, ModParam
Param[0] = 0; //
Param[1] = 10*8; // [bits] preamble length
Param[2] = 0x06; // preamble detect: 0x00:OFF, 0x04:8bits, 0x05:16bits, 0x06=24bits, 0x07=32bits
Param[3] = 8*8; // [bits] SYNC word length, write word at 0x06C0
Param[4] = 0x00; // address filtering: OFF
Param[5] = 0x00; // fixed packet size
Param[6] = 25; // 25 bytes
Param[7] = 0x01; // no CRC
Param[8] = 0x00; // no whitening
Cmd_Write(CMD_SETPACKETPARAMS, Param, 9); // 0x8C, PacketParam
setDioMode( /* IRQ_TXDONE | */ IRQ_RXDONE);
Regs_Write(REG_SYNCWORD0, Sync, 8); } // Write the SYNC word
void ClearIrqFlags(uint16_t Mask=IRQ_ALL) { uint8_t Data[2]; Data[0]=Mask>>8; Data[1]=Mask; Cmd_Write(CMD_CLEARIRQSTATUS, Data, 2); }
uint16_t ReadIrqFlags(void) { uint8_t *Stat=Cmd_Read(CMD_GETIRQSTATUS, 2); return (((uint16_t)(Stat[0]))<<8) | Stat[1]; }
void setModeSleep(void) { uint8_t Config[3] = { 0, 0, 0 }; Cmd_Write(CMD_SETSLEEP, Config, 3); }
void setModeStandby(uint8_t Mode=0) { uint8_t Config[1] = { Mode }; Cmd_Write(CMD_SETSTANDBY, Config, 1); }
void setModeTX(uint32_t Timeout=0) { uint8_t T[3]; Pack3bytes(T, Timeout); Cmd_Write(CMD_SETTX, T, 3); }
void setModeRX(uint32_t Timeout=0) { uint8_t T[3]; Pack3bytes(T, Timeout); Cmd_Write(CMD_SETRX, T, 3); }
void setModeSynth(void) { Cmd_Write(CMD_SETFS, 0, 0); }
void setDioMode(uint16_t Mask = IRQ_RXDONE)
{ uint8_t Param[8];
Param[0] = Mask>>8; // IRQ mask
Param[1] = Mask;
Param[2] = Mask>>8; // DIO1 mask
Param[3] = Mask;
Param[4] = 0; // DIO2 mask
Param[5] = 0;
Param[6] = 0; // DIO3 mask
Param[7] = 0;
Cmd_Write(CMD_SETDIOIRQPARAMS, Param, 8); }
#endif
#if defined(WITH_RFM95) || defined(WITH_SX1272) || defined(WITH_RFM69)
@ -601,7 +832,9 @@ class RFM_TRX
void setModeSleep(void) { WriteMode(RF_OPMODE_SLEEP); } // FSK sleep
void setModeStandby(void) { WriteMode(RF_OPMODE_STANDBY); } // FSK standby
void setModeTX(void) { WriteMode(RF_OPMODE_TRANSMITTER); } // FSK transmit
bool isModeTX(void) { return ReadMode()==RF_OPMODE_TRANSMITTER; } // in transmitter mode ?
void setModeRX(void) { WriteMode(RF_OPMODE_RECEIVER); } // FSK receive
bool isModeRX(void) { return ReadMode()==RF_OPMODE_RECEIVER; } // in receiver mode ? ?
#if defined(WITH_RFM95) || defined(WITH_SX1272)
void setModeLoRaStandby(void) { WriteMode(RF_OPMODE_LORA_STANDBY); } // LoRa standby
void setModeLoRaRXcont(void) { WriteMode(RF_OPMODE_LORA_RX_CONT); } // Lora continues recieve
@ -650,7 +883,7 @@ class RFM_TRX
WriteWord(0x0140, REG_BITRATEMSB); // bit rate = 100kbps
WriteWord(0x0333, REG_FDEVMSB); // FSK deviation = +/-50kHz
setChannel(Channel); // operating channel
FSK_WriteSYNC(8, 7, Sync); // SYNC pattern (setup for reception)
FSK_WriteSYNC(8, 7, Sync); // SYNC pattern (setup for transmission)
WriteByte( 0x00, REG_PACKETCONFIG1); // [0x10] Fixed size packet, no DC-free encoding, no CRC, no address filtering
WriteByte(0x80+51, REG_FIFOTHRESH); // [ ] TxStartCondition=FifoNotEmpty, FIFO threshold = 51 bytes
WriteByte( 2*26, REG_PAYLOADLENGTH); // [0x40] Packet size = 26 bytes Manchester encoded into 52 bytes
@ -671,13 +904,6 @@ class RFM_TRX
WriteByte( +10, REG_TESTAFC); } // [0x00] [488Hz] if AfcLowBetaOn
#endif
#ifdef WITH_SX1262
void setModulation(uint8_t Mode=0) { Cmd_Write(CMD_SETPACKETTYPE, &Mode, 1); }
void setLoRa(void) { setModulation(0x01); } // switch to FSK
void setFSK(void) { setModulation(0x00); } // switch to LoRa
#endif
// #ifdef WITH_RFM95
#if defined(WITH_RFM95) || defined(WITH_SX1272)
@ -714,7 +940,7 @@ class RFM_TRX
{ WriteMode(RF_OPMODE_SLEEP);
WriteMode(RF_OPMODE_SLEEP); }
int LoRa_Configure(RFM_LoRa_Config CFG, uint8_t MaxSize=64)
void LoRa_Configure(RFM_LoRa_Config CFG, uint8_t MaxSize=64)
{ WriteByte(0x00, REG_LORA_HOPPING_PERIOD); // disable fast-hopping
WriteByte(CFG.SYNC, REG_LORA_SYNC); // SYNC
WriteWord(CFG.Preamble, REG_LORA_PREAMBLE_MSB); // [symbols] minimal preamble
@ -737,17 +963,17 @@ class RFM_TRX
setChannel(0); // operating channel
WriteWord(0x0000, REG_DIOMAPPING1); // 001122334455___D signals: 00=DIO0 11=DIO1 22=DIO2 33=DIO3 44=DIO4 55=DIO5 D=MapPreambleDetect
// DIO0: 00=RxDone, 01=TxDone, 10=CadDone
return 0; }
}
int FNT_Configure(uint8_t CR=1) // configure for FANET/LoRa
void FNT_Configure(uint8_t CR=1) // configure for FANET/LoRa
{ WriteTxPower(0);
RFM_LoRa_Config CFG = RFM_FNTcfg; CFG.CR=CR;
return LoRa_Configure(CFG, FANET_Packet::MaxBytes); }
LoRa_Configure(CFG, FANET_Packet::MaxBytes); }
int WAN_Configure(uint8_t CR=1) // configure for LoRaWAN
void WAN_Configure(uint8_t CR=1) // configure for LoRaWAN
{ WriteTxPower(0);
RFM_LoRa_Config CFG = RFM_WANcfg; CFG.CR=CR;
return LoRa_Configure(CFG, 40); }
LoRa_Configure(CFG, 40); }
void LoRa_setIRQ(uint8_t Mode=0) // 0:on RX, 1:on TX, 2: on CAD
{ WriteByte(Mode<<6, REG_DIOMAPPING1); }
@ -842,7 +1068,7 @@ class RFM_TRX
// WriteByte( 0x02, REG_RXBW); // Man=0=16 Exp=2 +/-125kHz Rx (single-side) bandwidth => p.27,67,83,90
WriteByte( 0x23, REG_RXBW); // Man=1=20 Exp=3 +/-50kHz Rx (single-side) bandwidth => p.27,67,83,90
WriteByte( 0x23, REG_AFCBW); // +/-125kHz AFC bandwidth
WriteByte( 0x49, REG_PARAMP); // BT=0.5 shaping, 40us ramp up/down
WriteByte( 0x29, REG_PARAMP); // 2:BT=1.0 (seems better ?), 4:BT=0.5 shaping, 40us ramp up/down
WriteByte( 0x0E, REG_RXCONFIG); // => p.90 (or 0x8E ?)
WriteByte( 0x07, REG_RSSICONFIG); // 256 samples for RSSI, no offset, => p.90,82
WriteByte( 0x20, REG_LNA); // max. LNA gain, => p.89

Wyświetl plik

@ -8,7 +8,7 @@
#define CMD_SETCAD 0xC5 // [0]
#define CMD_SETTXCONTINUOUSWAVE 0xD1 // [1] test mode: continues wave
#define CMD_SETTXINFINITEPREAMBLE 0xD2 // [1] test mode: continues preamble
#define CMD_SETREGULATORMODE 0x96 // [1]
#define CMD_SETREGULATORMODE 0x96 // [1] 0 = LDO, 1=DC-DC + LDO
#define CMD_CALIBRATE 0x89 // [1]
#define CMD_CALIBRATEIMAGE 0x98 // [2]
#define CMD_SETPACONFIG 0x95 // [4] PA control: duty
@ -26,12 +26,12 @@
#define CMD_SETDIO3ASTCXOCTRL 0x97 // [4] Use DIO3 as TCXO control: voltage, delay
#define CMD_SETRFFREQUENCY 0x86 // [4] frequency [Fxtal/2^25]
#define CMD_SETPACKETTYPE 0x8A // [1] 0x00=GFSK, 0x01=LoRa (must be the first vonfiguration command)
#define CMD_SETPACKETTYPE 0x8A // [1] 0x00=GFSK, 0x01=LoRa (must be the first configuration command)
#define CMD_GETPACKETTYPE 0x11
#define CMD_SETTXPARAMS 0x8E // [2] TxPower: -17..+14 or -9..+22 [dBm] depending on PA config RampTime: 0..7: 10,20,40,80,200,800,1700,3400us
#define CMD_SETMODULATIONPARAMS 0x8B
#define CMD_SETMODULATIONPARAMS 0x8B // [8] depends on the protocol: FSK or LoRa
#define CMD_SETPACKETPARAMS 0x8C // [9]
#define CMD_SETCADPARAMS 0x88 // [8] depends on the protocol
#define CMD_SETCADPARAMS 0x88
#define CMD_SETBUFFERBASEADDRESS 0x8F // [2] Tx-base address, Rx-base address
#define CMD_SETLORASYMBNUMTIMEOUT 0xA0 // [1] timeout [symbols]
@ -44,6 +44,7 @@
#define CMD_GETSTATS 0x10 // [stat+6] RX-statistics: packets, errors
#define CMD_RESETSTATS 0x00 // [stat+6] RX-statistics reset
// registers
#define REG_WHITENINGMSB 0x06B8
#define REG_WHITENINGLSB 0x06B9
#define REG_CRCINITVALMSB 0x06BC
@ -60,6 +61,7 @@
#define REG_SYNCWORD7 0x06C7
#define REG_NODEADDRESS 0x06CD
#define REG_BROADCASTADDR 0x06CE
#define REG_LORASYNCWORD 0x0740
#define REG_LORASYNCWORDMSB 0x0740
#define REG_LORASYNCWORDLSB 0x0741
#define REG_RANDOMNUMBERGEN0 0x0819
@ -70,3 +72,17 @@
#define REG_OCPCONFIG 0x08E7
#define REG_XTATRIM 0x0911
#define REG_XTBTRIM 0x0912
// IRQ types
#define IRQ_TXDONE (1 << 0)
#define IRQ_RXDONE (1 << 1)
#define IRQ_PREAMBLEDETECTED (1 << 2)
#define IRQ_SYNCWORDVALID (1 << 3)
#define IRQ_HEADERVALID (1 << 4)
#define IRQ_HEADERERR (1 << 5)
#define IRQ_CRCERR (1 << 6)
#define IRQ_CADDONE (1 << 7)
#define IRQ_CADDETECTED (1 << 8)
#define IRQ_TIMEOUT (1 << 9)
#define IRQ_ALL 0x3FF

Wyświetl plik

@ -80,7 +80,11 @@ esp_err_t WIFI_StartAP(const char *SSID, const char *Pass, int MaxConnections)
// IP4_ADDR(&IPinfo.netmask, 255,255,255,0);
// tcpip_adapter_set_ip_info(TCPIP_ADAPTER_IF_AP, &IPinfo);
Err = esp_wifi_set_mode(WIFI_MODE_AP); if(Err!=ESP_OK) return Err; // which one should come first: set_mode or set_config ?
Err = esp_wifi_set_config(ESP_IF_WIFI_AP, &WIFI_Config); if(Err!=ESP_OK) return Err;
#if ESP_IDF_VERSION_MINOR<3
Err = esp_wifi_set_config(ESP_IF_WIFI_AP, &WIFI_Config); if(Err!=ESP_OK) return Err; // v4.1
#else
Err = esp_wifi_set_config(WIFI_IF_AP, &WIFI_Config); if(Err!=ESP_OK) return Err; // v4.3
#endif
Err = esp_wifi_start();
return Err; }
@ -117,7 +121,11 @@ esp_err_t WIFI_Connect(wifi_ap_record_t *AP, const char *Pass, int8_t MinSig) //
WIFI_Config.sta.scan_method = WIFI_ALL_CHANNEL_SCAN;
WIFI_Config.sta.sort_method = WIFI_CONNECT_AP_BY_SIGNAL;
WIFI_Config.sta.threshold.rssi = MinSig;
Err = esp_wifi_set_config(ESP_IF_WIFI_STA, &WIFI_Config); if(Err!=ESP_OK) return Err;
#if ESP_IDF_VERSION_MINOR<3
Err = esp_wifi_set_config(ESP_IF_WIFI_STA, &WIFI_Config); if(Err!=ESP_OK) return Err; // v4.1
#else
Err = esp_wifi_set_config(WIFI_IF_STA, &WIFI_Config); if(Err!=ESP_OK) return Err; // v4.3
#endif
Err = esp_wifi_connect(); if(Err!=ESP_OK) return Err;
return Err; }
@ -129,7 +137,11 @@ esp_err_t WIFI_Connect(const char *SSID, const char *Pass, int8_t MinSig)
WIFI_Config.sta.scan_method = WIFI_ALL_CHANNEL_SCAN;
WIFI_Config.sta.sort_method = WIFI_CONNECT_AP_BY_SIGNAL;
WIFI_Config.sta.threshold.rssi = MinSig;
Err = esp_wifi_set_config(ESP_IF_WIFI_STA, &WIFI_Config); if(Err!=ESP_OK) return Err;
#if ESP_IDF_VERSION_MINOR<3
Err = esp_wifi_set_config(ESP_IF_WIFI_STA, &WIFI_Config); if(Err!=ESP_OK) return Err; // v4.1
#else
Err = esp_wifi_set_config(WIFI_IF_STA, &WIFI_Config); if(Err!=ESP_OK) return Err; // v4.3
#endif
Err = esp_wifi_connect(); if(Err!=ESP_OK) return Err;
return Err; }

Wyświetl plik

@ -2,7 +2,13 @@
#define __WIFI_H__
#include "tcpip_adapter.h"
#include "esp_wifi.h"
#if ESP_IDF_VERSION_MINOR<3
#include "esp_wifi.h" // v4.1
#else
#include <esp_wifi.h> // v4.3
#endif
#include "esp_event_loop.h"
extern tcpip_adapter_ip_info_t WIFI_IP; // WIFI local IP address, mask and gateway

Wyświetl plik

@ -781,7 +781,8 @@ CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1024
CONFIG_FREERTOS_ISR_STACKSIZE=1536
# CONFIG_FREERTOS_LEGACY_HOOKS is not set
CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16
# CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION is not set
CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION=y
# CONFIG_FREERTOS_ENABLE_STATIC_TASK_CLEAN_UP is not set
CONFIG_FREERTOS_TIMER_TASK_PRIORITY=1
CONFIG_FREERTOS_TIMER_TASK_STACK_DEPTH=2048
CONFIG_FREERTOS_TIMER_QUEUE_LENGTH=10
@ -850,7 +851,7 @@ CONFIG_LWIP_MAX_SOCKETS=10
# CONFIG_LWIP_SO_REUSE is not set
# CONFIG_LWIP_SO_RCVBUF is not set
# CONFIG_LWIP_NETBUF_RECVINFO is not set
# CONFIG_LWIP_IP_FRAG is not set
CONFIG_LWIP_IP_FRAG=y
# CONFIG_LWIP_IP_REASSEMBLY is not set
# CONFIG_LWIP_STATS is not set
CONFIG_LWIP_ETHARP_TRUST_IP_MAC=y
@ -1501,7 +1502,8 @@ CONFIG_MB_EVENT_QUEUE_TIMEOUT=20
CONFIG_MB_TIMER_PORT_ENABLED=y
CONFIG_MB_TIMER_GROUP=0
CONFIG_MB_TIMER_INDEX=0
# CONFIG_SUPPORT_STATIC_ALLOCATION is not set
CONFIG_SUPPORT_STATIC_ALLOCATION=y
# CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set
CONFIG_TIMER_TASK_PRIORITY=1
CONFIG_TIMER_TASK_STACK_DEPTH=2048
CONFIG_TIMER_QUEUE_LENGTH=10