kopia lustrzana https://github.com/pjalocha/esp32-ogn-tracker
Update from other projects, cleanups, attempt to run with SkyDemon and SafeSky
rodzic
e18b1b7ed5
commit
10a2845380
|
@ -80,17 +80,18 @@
|
|||
#define WITH_LORAWAN
|
||||
|
||||
#define WITH_AP // WiFi Access Point: can work together with BT_SPP
|
||||
// #define WITH_AP_BUTTON // only starts when button pressed at sartup
|
||||
#define WITH_AP_BUTTON // only starts when button pressed at sartup
|
||||
// #define WITH_BT_SPP // Bluetooth serial port for smartphone/tablet link: can work together with WiFi Access point
|
||||
// #define WITH_STRATUX // beta-code: connect to Stratux WiFi and serve as GPS and OGN transmitter/receiver
|
||||
// #define WITH_APRS // alpha-code: attempt to connect to the wifi router for uploading the log files to APRS
|
||||
|
||||
#define WITH_HTTP // HTTP server, works with AP dna should work with Stratux as well
|
||||
|
||||
#define WITH_SD // use the SD card in SPI mode and FAT file system
|
||||
#define WITH_SPIFFS_FAT
|
||||
#define WITH_SPIFFS // use SPIFFS file system in Flash
|
||||
#define WITH_SPIFFS_FAT // use FAT on the SPIFFS
|
||||
#define WITH_LOG // log own positions and other received to SPIFFS and possibly to uSD
|
||||
#define WITH_SD // use the SD card in SPI mode and FAT file system
|
||||
#define WITH_SDLOG // log console and IGC to the SD card
|
||||
|
||||
// #define WITH_ENCRYPT // Encrypt (optionally) the position
|
||||
|
||||
|
|
|
@ -76,21 +76,22 @@
|
|||
|
||||
#define WITH_ADSL
|
||||
// #define WITH_PAW
|
||||
#define WITH_FANET
|
||||
// #define WITH_FANET
|
||||
#define WITH_LORAWAN
|
||||
|
||||
#define WITH_AP // WiFi Access Point: can work together with BT_SPP
|
||||
// #define WITH_AP_BUTTON // only starts when button pressed at sartup
|
||||
#define WITH_AP_BUTTON // only starts when button pressed at sartup
|
||||
// #define WITH_BT_SPP // Bluetooth serial port for smartphone/tablet link: can work together with WiFi Access point
|
||||
// #define WITH_STRATUX // beta-code: connect to Stratux WiFi and serve as GPS and OGN transmitter/receiver
|
||||
// #define WITH_APRS // alpha-code: attempt to connect to the wifi router for uploading the log files to APRS
|
||||
|
||||
#define WITH_HTTP // HTTP server, works with AP dna should work with Stratux as well
|
||||
|
||||
#define WITH_SD // use the SD card in SPI mode and FAT file system
|
||||
#define WITH_SPIFFS_FAT
|
||||
#define WITH_SPIFFS // use SPIFFS file system in Flash
|
||||
#define WITH_SPIFFS_FAT // use FAT on the SPIFFS
|
||||
#define WITH_LOG // log own positions and other received to SPIFFS and possibly to uSD
|
||||
#define WITH_SD // use the SD card in SPI mode and FAT file system
|
||||
#define WITH_SDLOG // log console and IGC to the SD card
|
||||
|
||||
// #define WITH_ENCRYPT // Encrypt (optionally) the position
|
||||
|
||||
|
|
|
@ -31,6 +31,8 @@
|
|||
// #define WITH_OLED // OLED display on the I2C: some TTGO modules are without OLED display
|
||||
// #define WITH_OLED2 // 2nd OLED display, I2C address next higher
|
||||
// #define WITH_U8G2_OLED // I2C OLED through the U8g2 library
|
||||
// #define WITH_U8G2_SH1106 // the bigger OLED controller
|
||||
// #define WITH_U8G2_FLIP // flip the OLED screen
|
||||
|
||||
#define WITH_RFM95 // RF chip selection: both HELTEC and TTGO use sx1276 which is same as RFM95
|
||||
// #define WITH_SX1262 // RF chip selection: both HELTEC and TTGO use sx1276 which is same as RFM95
|
||||
|
@ -74,11 +76,11 @@
|
|||
|
||||
#define WITH_ADSL
|
||||
// #define WITH_PAW
|
||||
// #define WITH_FANET
|
||||
#define WITH_FANET
|
||||
#define WITH_LORAWAN
|
||||
|
||||
#define WITH_AP // WiFi Access Point: can work together with BT_SPP
|
||||
// #define WITH_AP_BUTTON // only starts when button pressed at sartup
|
||||
#define WITH_AP_BUTTON // only starts when button pressed at sartup
|
||||
// #define WITH_BT_SPP // Bluetooth serial port for smartphone/tablet link: can work together with WiFi Access point
|
||||
// #define WITH_STRATUX // beta-code: connect to Stratux WiFi and serve as GPS and OGN transmitter/receiver
|
||||
// #define WITH_APRS // alpha-code: attempt to connect to the wifi router for uploading the log files to APRS
|
||||
|
|
161
main/adsl.h
161
main/adsl.h
|
@ -1,20 +1,21 @@
|
|||
#ifndef __ADSL_H__
|
||||
#define __ADSL_H__
|
||||
|
||||
// #include <stdlib.h>
|
||||
#include <stdlib.h>
|
||||
#include <math.h>
|
||||
// #include <string.h>
|
||||
// #include "radiodemod.h"
|
||||
// #include "intmath.h"
|
||||
#include "ognconv.h"
|
||||
// #include "bitcount.h"
|
||||
#include "bitcount.h"
|
||||
// #include "format.h"
|
||||
// #include "crc1021.h"
|
||||
|
||||
class ADSL_Packet
|
||||
{ public:
|
||||
|
||||
const static uint8_t TxBytes = 27; // including SYNC, Length and 24-bit CRC
|
||||
const static uint8_t SYNC1 = 0x72;
|
||||
const static uint8_t TxBytes = 27; // including SYNC, Length, actual packet content (1+20 bytes) and 3-byte CRC
|
||||
const static uint8_t SYNC1 = 0x72; // two SYNC bytes - Lemgth byte can be considered the 3rd SYNC byte as it is fixed
|
||||
const static uint8_t SYNC2 = 0x4B;
|
||||
|
||||
uint8_t SYNC[2]; // two bytes for correct alignment: can contain the last two SYNC bytes
|
||||
|
@ -51,11 +52,15 @@ class ADSL_Packet
|
|||
} ;
|
||||
uint8_t CRC[3]; // 24-bit (is aligned to 32-bit)
|
||||
|
||||
// uint8_t Spare;
|
||||
// uint32_t Time; // [sec] receive time or other estimate
|
||||
// --------------------------------------------------------------------------------------------------------
|
||||
|
||||
public:
|
||||
void Init(void) { SYNC[0]=SYNC1; SYNC[1]=SYNC2; Length=TxBytes-3; Version=0x00; Type=0x02; }
|
||||
void Init(void)
|
||||
{ SYNC[0]=SYNC1; SYNC[1]=SYNC2;
|
||||
Length=TxBytes-3; Version=0x00;
|
||||
for(int Idx=0; Idx<5; Idx++)
|
||||
Word[Idx]=0;
|
||||
Type=0x02; }
|
||||
|
||||
void Print(void) const
|
||||
{ printf(" v%02X %4.1fs: %02X:%06X [%+09.5f,%+010.5f]deg %dm %+4.1fm/s %05.1fdeg %3.1fm/s\n",
|
||||
|
@ -82,11 +87,16 @@ class ADSL_Packet
|
|||
static void set3bytes(uint8_t *Byte, uint32_t Word) { Byte[0]=Word; Byte[1]=Word>>8; Byte[2]=Word>>16; }
|
||||
|
||||
static uint32_t get4bytes(const uint8_t *Byte)
|
||||
{ uint32_t Word =Byte[3]; Word<<=8;
|
||||
Word|=Byte[2]; Word<<=8;
|
||||
Word|=Byte[1]; Word<<=8;
|
||||
Word|=Byte[0];
|
||||
return Word; }
|
||||
{ uint32_t A = Byte[0];
|
||||
uint32_t B = Byte[1];
|
||||
uint32_t C = Byte[2];
|
||||
uint32_t D = Byte[3];
|
||||
return A | (B<<8) | (C<<16) | (D<<24); }
|
||||
// { uint32_t Word =Byte[3]; Word<<=8;
|
||||
// Word|=Byte[2]; Word<<=8;
|
||||
// Word|=Byte[1]; Word<<=8;
|
||||
// Word|=Byte[0];
|
||||
// return Word; }
|
||||
static void set4bytes(uint8_t *Byte, uint32_t Word) { Byte[0]=Word; Byte[1]=Word>>8; Byte[2]=Word>>16; Byte[3]=Word>>24; }
|
||||
|
||||
uint32_t getAddress(void) const
|
||||
|
@ -100,7 +110,7 @@ class ADSL_Packet
|
|||
uint8_t getAddrTable(void) const { return Address[0]&0x3F; }
|
||||
void setAddrTable(uint8_t Table) { Address[0] = (Address[0]&0xC0) | Table; }
|
||||
|
||||
uint8_t getAddrType(void) const
|
||||
uint8_t getAddrTypeOGN(void) const
|
||||
{ uint8_t Table=getAddrTable();
|
||||
if(Table==0x05) return 1; // ICAO
|
||||
if(Table==0x06) return 2; // FLARM
|
||||
|
@ -108,52 +118,73 @@ class ADSL_Packet
|
|||
if(Table==0x08) return 2; // FANET => FLARM ?
|
||||
return 0; }
|
||||
|
||||
void setAddrType(uint8_t AddrType)
|
||||
void setAddrTypeOGN(uint8_t AddrType)
|
||||
{ if(AddrType==0) setAddrTable(0);
|
||||
else setAddrTable(AddrType+4); }
|
||||
|
||||
void setAcftType(uint8_t AcftType)
|
||||
void setAcftTypeOGN(uint8_t AcftType) // set OGN aircraft-type
|
||||
{ const uint8_t Map[16] = { 0, 4, 1, 3, // unknown, glider, tow-plane, helicopter
|
||||
8, 1, 7, 7, // sky-diver, drop plane, hang-glider, para-glider
|
||||
1, 2, 0, 5, // motor airplane, jet, UFO, balloon
|
||||
5,11, 0, 0 } ; // airship, UAV, ground vehicle, static object
|
||||
if(AcftType<16) AcftCat=Map[AcftType];
|
||||
else AcftCat=0; }
|
||||
uint8_t getAcftType(void) const
|
||||
uint8_t getAcftTypeOGN(void) const // get OGN aircraft-type
|
||||
{ const uint8_t Map[32] = { 0, 8, 9, 3, 1,12, 2, 7,
|
||||
4,13, 3,13,13,13, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0 } ;
|
||||
return Map[AcftCat]; }
|
||||
|
||||
uint8_t getHorPrec(void) const
|
||||
// --------------------------------------------------------------------------------------------------------
|
||||
|
||||
uint32_t getTime(uint16_t &msTime, uint32_t RefTime, int FwdMargin=3) const
|
||||
{ msTime=250*(TimeStamp&3);
|
||||
if(TimeStamp>=60) return 0;
|
||||
int Sec=RefTime%15;
|
||||
int DiffSec=(TimeStamp>>2)-Sec;
|
||||
if(DiffSec>FwdMargin) DiffSec-=15;
|
||||
else if(DiffSec<=(-15+FwdMargin)) DiffSec+=15;
|
||||
return RefTime+DiffSec; } // get out the correct position timestamp
|
||||
|
||||
uint8_t getHorAccur(void) const
|
||||
{ const uint8_t Map[8] = { 63, 63, 63, 63, 63, 30, 10, 3 } ;
|
||||
return Map[HorizAccuracy]; }
|
||||
void setHorPrec(uint8_t Prec)
|
||||
void setHorAccur(uint8_t Prec)
|
||||
{ if(Prec<= 3) HorizAccuracy=7;
|
||||
else if(Prec<=10) HorizAccuracy=6;
|
||||
else if(Prec<=30) HorizAccuracy=5;
|
||||
else HorizAccuracy=4;
|
||||
VelAccuracy = HorizAccuracy-4; }
|
||||
|
||||
uint8_t getVerPrec(void) const
|
||||
uint8_t getVerAccur(void) const // [m] vertical accuracy
|
||||
{ const uint8_t Map[8] = { 63, 63, 45, 15 } ;
|
||||
return Map[VertAccuracy]; }
|
||||
void setVerPrec(uint8_t Prec)
|
||||
void setVerAccur(uint8_t Prec)
|
||||
{ if(Prec<=15) HorizAccuracy=3;
|
||||
else if(Prec<=45) HorizAccuracy=2;
|
||||
else HorizAccuracy=1; }
|
||||
|
||||
static int32_t FNTtoUBX(int32_t Coord) { return ((int64_t)900007296*Coord+0x20000000)>>30; } // [FANET-cordic ] => [1e-7 deg]
|
||||
static int32_t OGNtoFNT(int32_t Coord) { return ((int64_t)Coord*83399317+(1<<21))>>22; } // [0.0001/60 deg] => [FANET cordic]
|
||||
static int32_t UBXtoFNT(int32_t Coord) { return ((int64_t)Coord*5003959 +(1<<21))>>22; } // [1e-7 deg] => [FANET cordic]
|
||||
static int32_t FNTtoOGN(int32_t Coord) { return ((int64_t)Coord*27000219 +(1<<28))>>29; } // [FANET cordic] => [0.0001/60 deg]
|
||||
static int32_t OGNtoFNT(int32_t Coord) { return ((int64_t)Coord*83399317 +(1<<21))>>22; } // [0.0001/60 deg] => [FANET cordic]
|
||||
static int32_t FNTtoUBX(int32_t Coord) { return ((int64_t)Coord*900007296+(1<<29))>>30; } // [FANET-cordic ] => [1e-7 deg]
|
||||
static int32_t UBXtoFNT(int32_t Coord) { return ((int64_t)Coord*5003959 +(1<<21))>>22; } // [1e-7 deg] => [FANET cordic]
|
||||
static float FNTtoFloat(int32_t Coord) // convert from FANET cordic units to float degrees
|
||||
{ const float Conv = 90.0007295677/0x40000000; // FANET cordic conversion factor (not exactly cordic)
|
||||
return Conv*Coord; }
|
||||
|
||||
int32_t getLatOGN(void) const { return FNTtoOGN(getLat()); }
|
||||
int32_t getLonOGN(void) const { return FNTtoOGN(getLon()); }
|
||||
|
||||
int32_t getLatUBX(void) const { return FNTtoUBX(getLat()); }
|
||||
int32_t getLonUBX(void) const { return FNTtoUBX(getLon()); }
|
||||
|
||||
int32_t getLat(void) const { int32_t Lat=get3bytes(Position ); Lat<<=8; Lat>>=1; return Lat; } // FANET-cordic
|
||||
int32_t getLon(void) const { int32_t Lon=get3bytes(Position+3); Lon<<=8; return Lon; } // FANET-cordic
|
||||
|
||||
void setLatOGN(int32_t Lat) { setLat(OGNtoFNT(Lat)); }
|
||||
void setLonOGN(int32_t Lon) { setLon(OGNtoFNT(Lon)); }
|
||||
|
||||
void setLat(int32_t Lat) { Lat = (Lat+0x40)>>7; set3bytes(Position , Lat); } // FANET-cordic
|
||||
void setLon(int32_t Lon) { Lon = (Lon+0x80)>>8; set3bytes(Position+3, Lon); } // FANET-cordic
|
||||
|
||||
|
@ -187,12 +218,34 @@ class ADSL_Packet
|
|||
{ Position[9] = (Position[9]&0x7F) | ((Word&0x01)<<7);
|
||||
Position[10] = Word>>1; }
|
||||
|
||||
// --------------------------------------------------------------------------------------------------------
|
||||
|
||||
// calculate distance vector [LatDist, LonDist] from a given reference [RefLat, Reflon]
|
||||
int calcDistanceVectorOGN(int32_t &LatDist, int32_t &LonDist, int32_t RefLat, int32_t RefLon, uint16_t LatCos=3000, int32_t MaxDist=0x7FFF)
|
||||
{ LatDist = ((getLatOGN()-RefLat)*1517+0x1000)>>13; // convert from 1/600000deg to meters (40000000m = 360deg) => x 5/27 = 1517/(1<<13)
|
||||
if(abs(LatDist)>MaxDist) return -1;
|
||||
LonDist = ((getLonOGN()-RefLon)*1517+0x1000)>>13;
|
||||
if(abs(LonDist)>(4*MaxDist)) return -1;
|
||||
LonDist = (LonDist*LatCos+0x800)>>12;
|
||||
if(abs(LonDist)>MaxDist) return -1;
|
||||
return 1; }
|
||||
|
||||
// sets position [Lat, Lon] according to given distance vector [LatDist, LonDist] from a reference point [RefLat, RefLon]
|
||||
void setDistanceVectorOGN(int32_t LatDist, int32_t LonDist, int32_t RefLat, int32_t RefLon, uint16_t LatCos=3000)
|
||||
{ setLatOGN(RefLat+(LatDist*27)/5);
|
||||
LonDist = (LonDist<<12)/LatCos; // LonDist/=cosine(Latitude)
|
||||
setLonOGN(RefLon+(LonDist*27)/5); }
|
||||
|
||||
// --------------------------------------------------------------------------------------------------------
|
||||
|
||||
void Scramble(void)
|
||||
{ XXTEA_Encrypt_Key0(Word, 5, 6); }
|
||||
|
||||
void Descramble(void)
|
||||
{ XXTEA_Decrypt_Key0(Word, 5, 6); }
|
||||
|
||||
// --------------------------------------------------------------------------------------------------------
|
||||
|
||||
static uint32_t PolyPass(uint32_t CRC, uint8_t Byte) // pass a single byte through the CRC polynomial
|
||||
{ const uint32_t Poly = 0xFFFA0480;
|
||||
CRC |= Byte;
|
||||
|
@ -221,6 +274,54 @@ class ADSL_Packet
|
|||
uint32_t checkCRC(void) const
|
||||
{ return checkPI((const uint8_t *)&Version, TxBytes-3); }
|
||||
|
||||
static int Correct(uint8_t *PktData, uint8_t *PktErr, const int MaxBadBits=6) // correct the manchester-decoded packet with dead/weak bits marked
|
||||
{ const int Bytes=TxBytes-3;
|
||||
uint32_t CRC = checkPI(PktData, Bytes); if(CRC==0) return 0;
|
||||
uint8_t ErrBit=FindCRCsyndrome(CRC);
|
||||
if(ErrBit!=0xFF) { FlipBit(PktData, ErrBit); return 1; }
|
||||
|
||||
uint8_t BadBitIdx[MaxBadBits]; // bad bit index
|
||||
uint8_t BadBitMask[MaxBadBits]; // bad bit mask
|
||||
uint32_t Syndrome[MaxBadBits]; // bad bit mask
|
||||
uint8_t BadBits=0; // count the bad bits
|
||||
for(uint8_t ByteIdx=0; ByteIdx<Bytes; ByteIdx++) // loop over bytes
|
||||
{ uint8_t Byte=PktErr[ByteIdx];
|
||||
uint8_t Mask=0x80;
|
||||
for(uint8_t BitIdx=0; BitIdx<8; BitIdx++) // loop over bits
|
||||
{ if(Byte&Mask)
|
||||
{ if(BadBits<MaxBadBits)
|
||||
{ BadBitIdx[BadBits]=ByteIdx; // store the bad bit index
|
||||
BadBitMask[BadBits]=Mask;
|
||||
Syndrome[BadBits]=CRCsyndrome(ByteIdx*8+BitIdx); }
|
||||
BadBits++;
|
||||
}
|
||||
Mask>>=1;
|
||||
}
|
||||
if(BadBits>MaxBadBits) break;
|
||||
}
|
||||
if(BadBits>MaxBadBits) return -1; // return failure when too many bad bits
|
||||
|
||||
uint8_t Loops = 1<<BadBits; uint8_t PrevGrayIdx=0;
|
||||
for(uint8_t Idx=1; Idx<Loops; Idx++) // loop through all combination of bad bit flips
|
||||
{ uint8_t GrayIdx= Idx ^ (Idx>>1); // use Gray code to change flip just one bit at a time
|
||||
uint8_t BitExp = GrayIdx^PrevGrayIdx;
|
||||
uint8_t Bit=0; while(BitExp>>=1) Bit++;
|
||||
PktData[BadBitIdx[Bit]]^=BadBitMask[Bit];
|
||||
CRC^=Syndrome[Bit]; if(CRC==0) return Count1s(GrayIdx);
|
||||
uint8_t ErrBit=FindCRCsyndrome(CRC);
|
||||
if(ErrBit!=0xFF)
|
||||
{ FlipBit(PktData, ErrBit);
|
||||
return Count1s(GrayIdx)+1; }
|
||||
PrevGrayIdx=GrayIdx; }
|
||||
|
||||
return -1; }
|
||||
|
||||
static void FlipBit(uint8_t *Byte, int BitIdx)
|
||||
{ int ByteIdx=BitIdx>>3;
|
||||
BitIdx&=7; BitIdx=7-BitIdx;
|
||||
uint8_t Mask=1; Mask<<=BitIdx;
|
||||
Byte[ByteIdx]^=Mask; }
|
||||
|
||||
static uint32_t CRCsyndrome(uint8_t Bit)
|
||||
{ const uint16_t PacketBytes = TxBytes-3;
|
||||
const uint16_t PacketBits = PacketBytes*8;
|
||||
|
@ -294,4 +395,18 @@ class ADSL_Packet
|
|||
|
||||
} __attribute__((packed));
|
||||
|
||||
class ADSL_RxPacket: public ADSL_Packet
|
||||
{ public:
|
||||
uint32_t sTime; // [ s] reception time
|
||||
uint16_t msTime; // [ms]
|
||||
int8_t RSSI; // [dBm]
|
||||
uint8_t BitErr; // number of bit errors
|
||||
|
||||
public:
|
||||
void setTime(double RxTime) { sTime=floor(RxTime); msTime=floor(1000.0*(RxTime-sTime)); }
|
||||
double getTime(void) const { return (double)sTime+0.001*msTime; }
|
||||
uint32_t SlotTime(void) const { uint32_t Slot=sTime; if(msTime<=300) Slot--; return Slot; }
|
||||
|
||||
};
|
||||
|
||||
#endif // __ADSL_H__
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#include "disp_lcd.h"
|
||||
|
||||
#ifdef WITH_U8G2_OLED
|
||||
const uint8_t DISP_Pages = 12;
|
||||
const uint8_t DISP_Pages = 13;
|
||||
static uint8_t DISP_Page = DEFAULT_DispPage ; //Fab501 before 0
|
||||
#endif
|
||||
#if defined(WITH_ST7789) || defined(WITH_ILI9341)
|
||||
|
@ -191,10 +191,15 @@ void vTaskDISP(void* pvParameters)
|
|||
case 6: OLED_DrawAltitudeAndSpeed (&U8G2_OLED, GPS); break;
|
||||
case 7: OLED_DrawRelay (&U8G2_OLED, GPS); break;
|
||||
case 8: OLED_DrawFlight (&U8G2_OLED, GPS); break;
|
||||
#ifdef WITH_LORAWAN
|
||||
case 9: OLED_DrawLoRaWAN (&U8G2_OLED, GPS); break;
|
||||
#endif
|
||||
#ifdef WITH_LOOKOUT
|
||||
case 10: OLED_DrawLookout (&U8G2_OLED, GPS); break;
|
||||
case 11: OLED_DrawTrafWarn (&U8G2_OLED, GPS); break;
|
||||
#endif
|
||||
#ifdef WITH_AP
|
||||
case 12: OLED_DrawNetwork (&U8G2_OLED, GPS); break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
#define STR(macro) QUOTE(macro)
|
||||
|
||||
#ifndef VERSION
|
||||
#define VERSION 0.0.0
|
||||
#define VERSION 0.1.3
|
||||
#endif
|
||||
|
||||
static char Line[128];
|
||||
|
@ -687,8 +687,31 @@ void OLED_DrawStatusBar(u8g2_t *OLED, GPS_Position *GPS) // status bar on top
|
|||
u8g2_DrawStr(OLED, 52, 10, Line);
|
||||
Sec++; if(Sec>=3) Sec=0; }
|
||||
|
||||
#ifdef WITH_AP
|
||||
void OLED_DrawNetwork(u8g2_t *OLED, GPS_Position *GPS)
|
||||
{ // u8g2_SetFont(OLED, u8g2_font_6x12_tr);
|
||||
u8g2_SetFont(OLED, u8g2_font_7x13_tf); // 5 lines, 12 pixels/line
|
||||
uint8_t Len=Format_String(Line, "AP: ");
|
||||
Len+=Format_String(Line+Len, (const char *)WIFI_Config.ap.ssid, 0, WIFI_Config.ap.ssid_len);
|
||||
Line[Len]=0;
|
||||
u8g2_DrawStr(OLED, 0, 24, Line);
|
||||
Len=Format_String(Line, "IP: ");
|
||||
Len+=IP_Print(Line+Len, WIFI_IP.ip.addr);
|
||||
// Len+=Format_String(Line+Len, " CH");
|
||||
// Len+=Format_UnsDec(Line+Len, WIFI_Config.ap.channel);
|
||||
Line[Len]=0;
|
||||
u8g2_DrawStr(OLED, 0, 36, Line);
|
||||
/*
|
||||
Len=Format_String(Line, "GW: ");
|
||||
Len+=IP_Print(Line+Len, WIFI_IP.gw.addr);
|
||||
Line[Len]=0;
|
||||
u8g2_DrawStr(OLED, 0, 48, Line);
|
||||
*/
|
||||
}
|
||||
#endif
|
||||
|
||||
void OLED_DrawSystem(u8g2_t *OLED, GPS_Position *GPS)
|
||||
{
|
||||
{ // u8g2_SetFont(OLED, u8g2_font_6x12_tr);
|
||||
u8g2_SetFont(OLED, u8g2_font_7x13_tf); // 5 lines, 12 pixels/line
|
||||
uint8_t Len=0;
|
||||
#ifdef WITH_MAVLINK
|
||||
|
|
|
@ -20,6 +20,7 @@ void OLED_DrawTrafWarn (u8g2_t *OLED, GPS_Position *GPS=0);
|
|||
void OLED_DrawBaro (u8g2_t *OLED, GPS_Position *GPS=0);
|
||||
void OLED_DrawBattery (u8g2_t *OLED, GPS_Position *GPS=0);
|
||||
void OLED_DrawStatusBar(u8g2_t *OLED, GPS_Position *GPS=0);
|
||||
void OLED_DrawNetwork (u8g2_t *OLED, GPS_Position *GPS=0);
|
||||
void OLED_DrawSystem (u8g2_t *OLED, GPS_Position *GPS=0);
|
||||
void OLED_DrawID (u8g2_t *OLED, GPS_Position *GPS=0);
|
||||
void OLED_DrawAltitudeAndSpeed(u8g2_t *OLED, GPS_Position *GPS=0);
|
||||
|
|
|
@ -104,16 +104,35 @@ static int GDL90_SendEsc(void (*Output)(char), uint8_t Byte) // shall we escap
|
|||
(*Output)((char)Byte); return 1; }
|
||||
|
||||
int GDL90_Send(void (*Output)(char), uint8_t ID, const uint8_t *Data, int Len)
|
||||
{ int Count=0; uint16_t CRC=0;
|
||||
(*Output)((char)GDL90_Flag); Count++;
|
||||
{ int OutLen=0; uint16_t CRC=0;
|
||||
(*Output)((char)GDL90_Flag); OutLen++;
|
||||
CRC=GDL90_CRC16(ID, CRC);
|
||||
Count+=GDL90_SendEsc(Output, ID);
|
||||
OutLen+=GDL90_SendEsc(Output, ID);
|
||||
for( int Idx=0; Idx<Len; Idx++)
|
||||
{ uint8_t Byte=Data[Idx];
|
||||
CRC=GDL90_CRC16(Byte, CRC);
|
||||
Count+=GDL90_SendEsc(Output, Byte); }
|
||||
Count+=GDL90_SendEsc(Output, CRC&0xFF);
|
||||
Count+=GDL90_SendEsc(Output, CRC>>8);
|
||||
(*Output)((char)GDL90_Flag); Count++;
|
||||
return Count; }
|
||||
OutLen+=GDL90_SendEsc(Output, Byte); }
|
||||
OutLen+=GDL90_SendEsc(Output, CRC&0xFF);
|
||||
OutLen+=GDL90_SendEsc(Output, CRC>>8);
|
||||
(*Output)((char)GDL90_Flag); OutLen++;
|
||||
return OutLen; }
|
||||
|
||||
static int GDL90_SendEsc(uint8_t *Out, uint8_t Byte) // shall we escape control characters as well ?
|
||||
{ // if(Byte<0x20 || Byte==GDL90_Flag || Byte==GDL90_Esc) { Out[0]=GDL90_Esc; Byte^=0x20; Out[]=Byte; return 2; }
|
||||
if(Byte==GDL90_Flag || Byte==GDL90_Esc) { Out[0]=GDL90_Esc; Byte^=0x20; Out[1]=Byte; return 2; } // ESCape some characters
|
||||
Out[0]=Byte; return 1; }
|
||||
|
||||
int GDL90_Send(uint8_t *Out, uint8_t ID, const uint8_t *Data, int Len)
|
||||
{ int OutLen=0; uint16_t CRC=0;
|
||||
Out[OutLen++]=GDL90_Flag;
|
||||
CRC=GDL90_CRC16(ID, CRC);
|
||||
OutLen+=GDL90_SendEsc(Out+OutLen, ID);
|
||||
for( int Idx=0; Idx<Len; Idx++)
|
||||
{ uint8_t Byte=Data[Idx];
|
||||
CRC=GDL90_CRC16(Byte, CRC);
|
||||
OutLen+=GDL90_SendEsc(Out+OutLen, Byte); }
|
||||
OutLen+=GDL90_SendEsc(Out+OutLen, CRC&0xFF);
|
||||
OutLen+=GDL90_SendEsc(Out+OutLen, CRC>>8);
|
||||
Out[OutLen++]=GDL90_Flag;
|
||||
return OutLen; }
|
||||
|
||||
|
|
150
main/gdl90.h
150
main/gdl90.h
|
@ -12,6 +12,8 @@ uint16_t GDL90_CRC16(uint8_t Byte, uint16_t CRC); // pass
|
|||
uint16_t GDL90_CRC16(const uint8_t *Data, uint8_t Len, uint16_t CRC=0); // pass a packet of bytes through the CRC
|
||||
|
||||
int GDL90_Send(void (*Output)(char), uint8_t ID, const uint8_t *Data, int Len); // transmit GDL90 packet with proper framing and CRC
|
||||
int GDL90_Send(uint8_t *Out, uint8_t ID, const uint8_t *Data, int Len);
|
||||
inline int GDL90_Send(char *Out, uint8_t ID, const uint8_t *Data, int Len) { return GDL90_Send((uint8_t *)Out, ID, Data, Len); }
|
||||
|
||||
// =================================================================================
|
||||
|
||||
|
@ -55,6 +57,13 @@ class GDL90_HEARTBEAT // Heart-beat packet to be send at every UTC second
|
|||
void Clear(void)
|
||||
{ Status1=0; Status2=0; TimeStamp=0; MsgCount[0]=0; MsgCount[1]=0; }
|
||||
|
||||
void Print(void) const
|
||||
{ uint32_t Time=getTimeStamp();
|
||||
int Hour=Time/3600; Time-=Hour*3600;
|
||||
int Min =Time/60; Time-=Min*60;
|
||||
int Sec =Time;
|
||||
printf("GDL90_HEARTBEAT: %02d:%02d:%02dZ %02X:%02X %4d:%4d\n", Hour, Min, Sec, Status1, Status2, getUplinkCount(), getDownlinkCount()); }
|
||||
|
||||
void setTimeStamp(uint32_t Time)
|
||||
{ Time%=86400; TimeStamp=Time; TimeStampMSB=Time>>16; }
|
||||
|
||||
|
@ -68,9 +77,81 @@ class GDL90_HEARTBEAT // Heart-beat packet to be send at every UTC second
|
|||
void setDownlinkCount(uint8_t Count) { MsgCount[0] = (MsgCount[0]&0xFC) | (Count>>8); MsgCount[1] = Count; }
|
||||
|
||||
int Send(void (*Output)(char)) const { return GDL90_Send(Output, 0, (const uint8_t *)this, Size); }
|
||||
int Send(char *Output ) const { return GDL90_Send(Output, 0, (const uint8_t *)this, Size); }
|
||||
|
||||
} __attribute__((packed));
|
||||
|
||||
class STX_HEARTBEAT
|
||||
{ public:
|
||||
static const int Size=1;
|
||||
union
|
||||
{ uint8_t Status;
|
||||
struct
|
||||
{ bool AHRS : 1;
|
||||
bool GPS : 1;
|
||||
uint8_t ProtVer: 6;
|
||||
} ;
|
||||
} ;
|
||||
|
||||
public:
|
||||
void Print(void) const
|
||||
{ printf("STX_HEARTBEAT: AHRS:%d GPS:%d v%d\n", AHRS, GPS, ProtVer); }
|
||||
|
||||
} ;
|
||||
|
||||
class STX_AHRS
|
||||
{ public:
|
||||
static const int Size=23;
|
||||
uint8_t Data[Size];
|
||||
|
||||
public:
|
||||
void Print(void) const
|
||||
{ printf("STX_AHRS:\n"); }
|
||||
|
||||
} ;
|
||||
|
||||
class STX_STATUS
|
||||
{ public:
|
||||
static const int Size=28;
|
||||
union
|
||||
{ uint8_t Data[Size];
|
||||
struct
|
||||
{ char X;
|
||||
uint8_t MsgType;
|
||||
uint8_t MsgVer;
|
||||
uint8_t Firmware[4];
|
||||
uint8_t Hardware[4];
|
||||
union
|
||||
{ uint8_t ValidFlags[2];
|
||||
} ;
|
||||
union
|
||||
{ uint8_t ConnFlags[2];
|
||||
} ;
|
||||
uint8_t SatLocked;
|
||||
uint8_t SatConnected;
|
||||
uint8_t TrafficTargets978[2];
|
||||
uint8_t TrafficTargets1090[2];
|
||||
uint8_t TraffcRate978[2];
|
||||
uint8_t TraffcRate1090[2];
|
||||
uint8_t CPUtemperature[2];
|
||||
uint8_t ADSBtowers;
|
||||
// 6x ADSBtowers bytes for coordinates
|
||||
} ;
|
||||
} ;
|
||||
|
||||
public:
|
||||
static uint16_t getTwoBytes(const uint8_t *Data) { uint16_t Val=Data[0]; return (Val<<8) | Data[1]; }
|
||||
// uint16_t getTargets(void) const { return getTwoBytes(TrafficTargets); }
|
||||
float getCPUtemp(void) const
|
||||
{ uint16_t Temp=getTwoBytes(CPUtemperature);
|
||||
if(Temp&0x8000) return -0.1f*(Temp&0x7FFF);
|
||||
else return +0.1f*Temp; }
|
||||
|
||||
void Print(void) const
|
||||
{ printf("STX_STATUS: %d/%dsats v%d.%d %+5.1fdegC\n", SatLocked, SatConnected, Firmware[0], Firmware[1], getCPUtemp()); }
|
||||
|
||||
} ;
|
||||
|
||||
// class GSL90_CONFIG // Initialization, ID=117
|
||||
// { public:
|
||||
// uint8_t Data[19];
|
||||
|
@ -82,17 +163,31 @@ class GDL90_GEOMALT // Geometrical altitude: ID = 11 (GPS ref. to Ellipsoid)
|
|||
uint8_t Data[Size];
|
||||
|
||||
public:
|
||||
void Clear(void) { for(int Idx=0; Idx<Size; Idx++) Data[Idx]=0; }
|
||||
|
||||
void setAltitude(int32_t Alt) // [5 feet] GPS altitude (ref. to Ellipsoid)
|
||||
{ if(Alt>0x7FFF) Alt=0x7FFF;
|
||||
else if(Alt<(-0x8000)) Alt=(-0x8000);
|
||||
Data[0]=Alt>>8; Data[1]=Alt&0x0FF; }
|
||||
int32_t getAltitude(void) const { int16_t Alt=Data[0]; Alt<<=8; Alt|=Data[1]; return Alt; }
|
||||
|
||||
void setWarning(bool Warn) // [bool]
|
||||
{ if(Warn) Data[2]|=0x80;
|
||||
else Data[2]&=0x7F; }
|
||||
bool getWarning(void) const { return Data[2]&0x80; }
|
||||
|
||||
void setFOM(uint16_t FOM) // [m] vertical Figure of Merit (accuracy ?)
|
||||
{ Data[2] = (Data[2]&0x80) | (FOM>>8);
|
||||
Data[3] = FOM&0xFF; }
|
||||
|
||||
uint16_t getFOM(void) const { uint16_t FOM=Data[2]&0x7F; FOM<<=8; FOM|=Data[3]; return FOM; }
|
||||
|
||||
int Send(void (*Output)(char)) const { return GDL90_Send(Output, 11, Data, Size); }
|
||||
int Send(char *Output ) const { return GDL90_Send(Output, 11, Data, Size); }
|
||||
|
||||
void Print(void) const
|
||||
{ printf("GDL90_GEOMALT: %dft (%dm) Warn:%d\n", getAltitude()*5, getFOM(), getWarning()); }
|
||||
|
||||
} ;
|
||||
|
||||
class GDL90_REPORT // Position report: Traffic: ID = 20, Ownship: ID = 10
|
||||
|
@ -126,7 +221,7 @@ class GDL90_REPORT // Position report: Traffic: ID = 20, Ownship: ID = 10
|
|||
static uint32_t get3bytes(const uint8_t *Byte) { uint32_t Word=Byte[0]; Word=(Word<<8) | Byte[1]; Word=(Word<<8) | Byte[2]; return Word; } // 3-byte value
|
||||
static void set3bytes(uint8_t *Byte, uint32_t Word) { Byte[0]=Word>>16; Byte[1]=Word>>8; Byte[2]=Word; }
|
||||
|
||||
void Clear(void) { for(int Idx=0; Idx<27; Idx++) Data[Idx]=0; } // clear all data (Lat/Lon = invalid)
|
||||
void Clear(void) { for(int Idx=0; Idx<Size; Idx++) Data[Idx]=0; } // clear all data (Lat/Lon = invalid)
|
||||
|
||||
uint8_t getAlertStatus(void) const { return Data[0]>>4; } // 0 = no alert, 1 = alert
|
||||
void setAlertStatus(uint8_t Status) { Data[0] = (Data[0]&0x0F) | (Status<<4); }
|
||||
|
@ -162,20 +257,25 @@ class GDL90_REPORT // Position report: Traffic: ID = 20, Ownship: ID = 10
|
|||
uint16_t getSpeed(void) const { uint16_t Speed=Data[13]; Speed=(Speed<<4) | (Data[14]>>4); return Speed; } // [knot]
|
||||
void setSpeed(uint16_t Speed) { if(Speed>0xFFE) Speed=0xFFE; Data[13] = Speed>>4; Data[14] = (Data[14]&0x0F) | (Speed<<4); } // [knot]
|
||||
void clrSpeed(void) { Data[13] = 0xFF; Data[14] = (Data[14]&0x0F) | 0xF0; } // Speed = invalid
|
||||
bool hasSpeed(void) const { return Data[13]!=0xFF || (Data[14]&0xF0)!=0xF0; }
|
||||
|
||||
int32_t getClimbRate(void) const
|
||||
{ int16_t Climb=Data[14]&0x0F; Climb=(Climb<<8)|Data[15]; Climb<<=4; return (int32_t)Climb*4; } // [fpm]
|
||||
{ int16_t Climb=Data[14]&0x0F; Climb=(Climb<<8)|Data[15]; Climb<<=4; return (int32_t)Climb<<2; } // [fpm]
|
||||
void setClimbRate(int32_t Climb) // [fpm]
|
||||
{ Climb = (Climb+32)>>6; if(Climb<(-510)) Climb=(-510); else if(Climb>510) Climb=510; // full 12-bit range is not being used
|
||||
Data[15] = Climb&0xFF; Data[14] = (Data[14]&0xF0) | ((Climb>>8)&0x0F); }
|
||||
void clrClimbRate(void) { Data[15]=0x00; Data[14] = (Data[14]&0xF0) | 0x08; } // set vertical rate = not available
|
||||
bool hasClimbRate(void) const { return Data[15]!=0x00 || (Data[14]&0x0F)!=0x08; }
|
||||
|
||||
uint8_t getHeading(void) const { return Data[16]; } // [cyclic]
|
||||
void setHeading(uint8_t Heading) { Data[16]=Heading; } // [cyclic]
|
||||
|
||||
uint8_t getAcftCat(void) const { return Data[17]; } // 1=light, 2=small, 3=large, 4=high vortex, 5=heavy, 6=high-G, 7=rotor, 9=glider, 10=airship, 11=parachute, 12=ULM/para/hang, 14=UAV, 15=space, 17=surf, 18=service
|
||||
uint8_t getAcftCatADSB(void) const { uint8_t Cat=getAcftCat(); Cat = (((Cat&0x18)<<1)+0xA0) | (Cat&7); return Cat; }
|
||||
|
||||
void setAcftCat(uint8_t Cat) { Data[17]=Cat; }
|
||||
void setAcftType(uint8_t AcftType) // set OGN-type aricrraft-type
|
||||
void setAcftCatADSB(uint8_t Cat) { if(Cat>=0xA0) Cat-=0xA0; Cat = ((Cat>>1)&0x18) | (Cat&7); setAcftCat(Cat); }
|
||||
void setAcftTypeOGN(uint8_t AcftType) // set OGN-type aircraft-type
|
||||
{ // 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, A, B, C, D, E, F
|
||||
const uint8_t OGNtype[16] = { 0, 9, 1, 7, 11, 1, 12, 12, 1, 3,15,10,10,14,18,19 } ; // conversion table from OGN aricraft-type
|
||||
setAcftCat(OGNtype[AcftType&0x0F]); }
|
||||
|
@ -199,13 +299,17 @@ class GDL90_REPORT // Position report: Traffic: ID = 20, Ownship: ID = 10
|
|||
void setPriority(uint8_t Prior) { Data[26] = (Data[26]&0x0F) | (Prior<<4); }
|
||||
|
||||
int Send(void (*Output)(char), uint8_t ID=10) const { return GDL90_Send(Output, ID, Data, Size); }
|
||||
int Send(char *Output , uint8_t ID=10) const { return GDL90_Send(Output, ID, Data, Size); }
|
||||
|
||||
void Print(void) const
|
||||
{ printf("%X:%06X %02X/%8s %X/%X %dft %+dfpm [%+09.5f,%+010.5f] %03.0f/%dkt\n",
|
||||
getAddrType(), getAddress(), getAcftCat(), getAcftCall(),
|
||||
getNIC(), getNACp(), getAltitude(), getClimbRate(),
|
||||
{ printf("%X:%06X %02X/%8s NIC:%X NACp:%X %5dft",
|
||||
getAddrType(), getAddress(), getAcftCatADSB(), getAcftCall(),
|
||||
getNIC(), getNACp(), getAltitude());
|
||||
if(hasClimbRate()) printf(" %+4dfpm", getClimbRate());
|
||||
printf(" [%+09.5f,%+010.5f] %03.0f/%dkt MI:%X Alrt:%X Prio:%X\n",
|
||||
(90.0/0x40000000)*getLatitude(), (90.0/0x40000000)*getLongitude(),
|
||||
(360.0/256)*getHeading(), getSpeed()); }
|
||||
(360.0/256)*getHeading(), getSpeed(),
|
||||
getMiscInd(), getAlertStatus(), getPriority()); }
|
||||
|
||||
} ;
|
||||
|
||||
|
@ -213,7 +317,7 @@ class GDL90_REPORT // Position report: Traffic: ID = 20, Ownship: ID = 10
|
|||
|
||||
class GDL90_RxMsg // receiver for the MAV messages
|
||||
{ public:
|
||||
static const uint8_t MaxBytes = 32; // max. number of bytes
|
||||
static const uint8_t MaxBytes = 60; // max. number of bytes
|
||||
static const uint8_t SYNC = 0x7E; // GDL90 sync byte
|
||||
static const uint8_t ESC = 0x7D; // GDL90 escape byte
|
||||
|
||||
|
@ -223,8 +327,24 @@ class GDL90_RxMsg // receiver for the MAV messages
|
|||
public:
|
||||
void Clear(void) { Len=0; Byte[Len]=0; }
|
||||
|
||||
void Print(void)
|
||||
{ printf("GDL90[%d] ", Len);
|
||||
uint8_t getID(void) const { return Byte[0]; }
|
||||
|
||||
bool isHeartBeat(void) const { return getID()== 0 && Len== 9; } // regular GDL90 heart-beat sent at 1Hz
|
||||
bool isGeomAlt(void) const { return getID()==11 && Len== 7; } // own height-above-Ellipsoid
|
||||
bool isOwnReport(void) const { return getID()==10 && Len==30; } // own position
|
||||
bool isTrafReport(void) const { return getID()==20 && Len==30; } // other aircraft position
|
||||
bool isForeFlight(void) const { return getID()==0x65; } // ForeFlight: can be software ID or AHRS
|
||||
bool isSkyLink(void) const { return getID()==0x31; } // SkyLink:
|
||||
bool isStxHeartBeat(void) const { return getID()==0xCC && Len== 4; } // Stratux heart-beat
|
||||
bool isStxAHRS(void) const { return getID()==0x4C && Len==26; } // Stratux AHRS
|
||||
bool isStxStatus(void) const // Stratux status
|
||||
{ if(getID()!='S') return 0;
|
||||
if(Len<31) return 0;
|
||||
uint8_t Towers=Byte[31];
|
||||
return Len == 31+Towers*6; }
|
||||
|
||||
void Print(void) const
|
||||
{ printf("GDL90[%2d:%3d] ", Len, Byte[0]);
|
||||
for(int Idx=0; Idx<Len; Idx++)
|
||||
printf("%02X", Byte[Idx]);
|
||||
printf("\n"); }
|
||||
|
@ -232,11 +352,11 @@ class GDL90_RxMsg // receiver for the MAV messages
|
|||
uint8_t ProcessByte(uint8_t RxByte) // process a single byte: add to the message or reject
|
||||
{ // printf("Process[%2d] 0x%02X\n", Len, RxByte);
|
||||
if(Len==0) // if the very first byte
|
||||
{ if(RxByte==SYNC) { Byte[Len]=RxByte; return 1; } // is SYNC then store it
|
||||
else if(Byte[Len]==SYNC)
|
||||
{ Byte[Len]=RxByte; if(RxByte==ESC) return 1;
|
||||
{ if(RxByte==SYNC) { Byte[Len]=RxByte; return 1; } // if SYNC then store it
|
||||
else if(Byte[Len]==SYNC) // if the packet before was SYNC
|
||||
{ Byte[Len]=RxByte; if(RxByte==ESC) return 1; // store the byte
|
||||
Len++; Byte[Len]=0; return 1; }
|
||||
else if(Byte[Len]==ESC)
|
||||
else if(Byte[Len]==ESC) // if the previous byte was ESC
|
||||
{ RxByte^=0x20; Byte[Len++]=RxByte; Byte[Len]=0; return 1; }
|
||||
else return 0; }
|
||||
if(RxByte==SYNC) // if not the very first byte and SYNC then the packet is possibly complete
|
||||
|
@ -245,7 +365,7 @@ class GDL90_RxMsg // receiver for the MAV messages
|
|||
for(int Idx=0; Idx<(Len-2); Idx++)
|
||||
{ CRC=GDL90_CRC16(Byte[Idx], CRC); }
|
||||
if( (CRC&0xFF)!=Byte[Len-2] || (CRC>>8)!=Byte[Len-1] ) { Clear(); return 0; }
|
||||
return 2; }
|
||||
return 2; } // packet complete and good CRC
|
||||
if(Byte[Len]==ESC) { RxByte^=0x20; } // if after an ESC then xor with 0x20
|
||||
Byte[Len]=RxByte; if(RxByte==ESC) return 1;
|
||||
Len++; // advance
|
||||
|
|
174
main/lookout.h
174
main/lookout.h
|
@ -18,27 +18,30 @@
|
|||
|
||||
class LookOut_Target // describes a flying aircrafts
|
||||
{ public:
|
||||
union
|
||||
{ uint32_t ID; // ID of the target = aircraft ID
|
||||
struct
|
||||
{ uint32_t Address:24; //
|
||||
uint8_t AddrType: 2; //
|
||||
uint8_t AcftType: 4; //
|
||||
} ;
|
||||
} ;
|
||||
Acft_RelPos Pos; // Position relative to the reference Lat/Lon/Alt
|
||||
int8_t Pred; // [0.5sec] amount of time by which own position has been predicted/extrapolated
|
||||
uint8_t GpsPrec; // GPS position error (includes prediction errors)
|
||||
union
|
||||
{ uint32_t ID; // ID of the target = aircraft ID
|
||||
struct
|
||||
{ uint32_t Address:24; // 24-bit address
|
||||
uint8_t AddrType: 8; // ADS-L address-type
|
||||
} ;
|
||||
} ;
|
||||
Acft_RelPos Pos; // Position relative to the reference Lat/Lon/Alt
|
||||
int8_t Pred; // [0.5sec] amount of time by which own position has been predicted/extrapolated
|
||||
uint8_t GpsPrec; // GPS position error (includes prediction errors)
|
||||
|
||||
uint8_t SysMask; // bit mask for RF systems received: 0=FLR, 1=OGN, 2=PilotAware, 3=FANET, 4=ADS-L, 5=ADS-B
|
||||
|
||||
uint8_t AcftType; // ADS-B, ADSL or FLARN/OGN aircraft-type
|
||||
char Call[11];
|
||||
|
||||
union
|
||||
{ uint8_t Flags; // flags
|
||||
{ uint8_t Flags; // single-bit flags
|
||||
struct
|
||||
{ // bool isMoving :1; // is a moving target
|
||||
bool isTracked :1; // is being tracked or only stored
|
||||
// bool isHidden :1; // hidden track, should normally not be revealed
|
||||
// bool hasStdAlt :1; // has pressure StdAlt
|
||||
bool Reported :1; // this target has already been reported with $PFLAA or GDL90
|
||||
uint8_t Sys :3; // 0=FLR, 1=OGN, 2=PilotAware, 3=FANET, 4=ADS-B
|
||||
bool Alloc :1; // is allocated or not (a free slot, where a new target can go into)
|
||||
} ;
|
||||
} ;
|
||||
|
@ -46,7 +49,7 @@ class LookOut_Target // describes a flying aircrafts
|
|||
union
|
||||
{ uint32_t Rank; // rank: lowest means shorter time margin, shorter distance margin thus bigger thread
|
||||
struct
|
||||
{ uint16_t DistMargin; // [0.5m] remaining safety margin: if positive, then considered no thread at all
|
||||
{ uint16_t DistMargin; // [0.5m] remaining safety margin: if positive, then considered not a thread at all
|
||||
uint8_t TimeMargin; // [0.5s] time to target (if no distance margin left)
|
||||
uint8_t WarnLevel; // assigned warning level: 0, 1, 2 or 3
|
||||
} ;
|
||||
|
@ -69,7 +72,7 @@ class LookOut_Target // describes a flying aircrafts
|
|||
uint16_t MissDist; // [0.5m] estimated closest approach distance
|
||||
|
||||
public:
|
||||
void Clear(void) { Pred=0; Flags=0; HorDist=0; MissDist=0; Rank=0xFFFF; }
|
||||
void Clear(void) { Pred=0; Flags=0; HorDist=0; MissDist=0; Call[0]=0; Rank=0xFFFF; }
|
||||
|
||||
// uint16_t HorRelSpeed(void) const { }
|
||||
|
||||
|
@ -87,7 +90,9 @@ class LookOut_Target // describes a flying aircrafts
|
|||
uint16_t getRelHorSpeed(void) const { return Acft_RelPos::FastDistance(Vx, Vy); } // relative horiz. speed of the target
|
||||
|
||||
void Print(void) const
|
||||
{ printf("%08lX/%+5.1fs/%7.1fm/%7.1fm/%5.1fs/%5.1fm/%+5.1fs/w%d", (long int)ID,
|
||||
{ if(Call[0]) printf("%-8s", Call);
|
||||
else printf("%08X", ID);
|
||||
printf("/%+5.1fs/%7.1fm/%7.1fm/%5.1fs/%5.1fm/%+5.1fs/w%d",
|
||||
0.5*Pred, 0.5*DistMargin, 0.5*HorDist, 0.5*TimeMargin, 0.5*MissDist, 0.5*MissTime, WarnLevel);
|
||||
// printf(" [%+7.1f,%+7.1f,%+7.1f]m [%+5.1f,%+5.1f,%+5.1f]m/s", 0.5*dX, 0.5*dY, 0.5*dZ, 0.5*Vx, 0.5*Vy, 0.5*Vz);
|
||||
// printf(" [%+5.2f,%+5.2f]m/s^-2", 0.0625*Ax, 0.0625*Ay);
|
||||
|
@ -101,33 +106,36 @@ class LookOut_Target // describes a flying aircrafts
|
|||
uint8_t WritePFLAA(char *NMEA)
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_String(NMEA+Len, "$PFLAA,"); // sentence name and alarm-level (but no alarms for trackers)
|
||||
NMEA[Len++]='0'+WarnLevel;
|
||||
NMEA[Len++]='0'+WarnLevel; // warning level
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_SignDec(NMEA+Len, dX/2);
|
||||
Len+=Format_SignDec(NMEA+Len, dX/2, 1, 0, 1); // [m] distance in Latitude
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_SignDec(NMEA+Len, dY/2);
|
||||
Len+=Format_SignDec(NMEA+Len, dY/2, 1, 0, 1); // [m] distance in longitude
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_SignDec(NMEA+Len, dZ/2); // [m] relative altitude
|
||||
Len+=Format_SignDec(NMEA+Len, dZ/2, 1, 0, 1); // [m] relative altitude
|
||||
NMEA[Len++]=',';
|
||||
uint8_t AddrType = (ID>>24)&0x03;
|
||||
#ifdef WITH_SKYDEMON // SkyDemon hack which accepts only 1 or 2
|
||||
// #ifdef WITH_SKYDEMON // SkyDemon hack which accepts only 1 or 2
|
||||
if(AddrType!=1) AddrType=2;
|
||||
#endif
|
||||
NMEA[Len++]='0'+AddrType; // address-type (3=OGN)
|
||||
// #endif
|
||||
NMEA[Len++]='0'+AddrType; // address-type (3=OGN, but not accepted by SkyDemon)
|
||||
NMEA[Len++]=',';
|
||||
uint32_t Addr = ID&0xFFFFFF; // [24-bit] address
|
||||
Len+=Format_Hex(NMEA+Len, (uint8_t)(Addr>>16)); // 24-bit address: RND, ICAO, FLARM, OGN
|
||||
Len+=Format_Hex(NMEA+Len, (uint16_t)Addr);
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_UnsDec(NMEA+Len, (225*Pos.Heading+0x800)>>12, 4, 1); // [deg] heading (by GPS)
|
||||
// Len+=Format_UnsDec(NMEA+Len, ((uint32_t)Pos.Heading*225+0x800)>>12, 4, 1); // [deg] heading (by GPS)
|
||||
Len+=Format_UnsDec(NMEA+Len, ((uint32_t)Pos.Heading*45+0x1000)>>13); // [deg] heading - without decimal part
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_SignDec(NMEA+Len, (225*Pos.Turn+0x800)>>12, 2, 1); // [deg/sec] turn rate
|
||||
// Len+=Format_SignDec(NMEA+Len, ((int32_t)Pos.Turn*225+0x800)>>12, 2, 1); // [deg/sec] turn rate
|
||||
if(Pos.hasTurn) Len+=Format_SignDec(NMEA+Len, ((int32_t)Pos.Turn*45+0x1000)>>13, 1, 0, 1); // [deg/s] turning rate - without decimal part
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_UnsDec(NMEA+Len, 5*Pos.Speed, 2, 1); // [approx. m/s] ground speed
|
||||
// Len+=Format_UnsDec(NMEA+Len, (uint32_t)Pos.Speed*5, 2, 1); // [approx. m/s] ground speed
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Pos.Speed/2, 1); // [approx. m/s] ground speed - without decimal
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_SignDec(NMEA+Len, 5*Pos.Climb, 2, 1); // [m/s] climb/sink rate
|
||||
if(Pos.hasClimb) Len+=Format_SignDec(NMEA+Len, (int32_t)Pos.Climb*5, 2, 1, 1); // [m/s] climb/sink rate - with decimal part
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]=HexDigit(ID>>26); // [0..F] aircraft-type: 1=glider, 2=tow plane, etc.
|
||||
NMEA[Len++]=AcftType; // [0..F] aircraft-type: 1=glider, 2=tow plane, etc.
|
||||
Len+=NMEA_AppendCheckCRNL(NMEA, Len);
|
||||
NMEA[Len]=0;
|
||||
return Len; } // return number of formatted characters
|
||||
|
@ -136,9 +144,16 @@ class LookOut_Target // describes a flying aircrafts
|
|||
|
||||
// =======================================================================================================
|
||||
|
||||
class LookOut
|
||||
template <const uint8_t MaxTgts=32>
|
||||
class LookOut
|
||||
{ public:
|
||||
uint32_t ID; // ID of me (own aircraft)
|
||||
union
|
||||
{ uint32_t ID; // own ID
|
||||
struct
|
||||
{ uint32_t Address:24; //
|
||||
uint8_t AddrType: 8; // ADS-L address-type
|
||||
} ;
|
||||
} ;
|
||||
Acft_RelPos Pos; // Own position relative to the reference Lat/Lon/Alt
|
||||
|
||||
uint32_t RefTime; // [sec] ref. T for the local T,X,Y,Z coord. system
|
||||
|
@ -147,6 +162,7 @@ class LookOut
|
|||
int32_t RefLon; // [1/60000deg]
|
||||
int32_t RefAlt; // [m]
|
||||
int16_t LatCos; // [2^-12]
|
||||
int16_t GeoidSepar; // [m]
|
||||
|
||||
int8_t Pred; // [0.5sec] amount of time by which position has been predicted/extrapolated
|
||||
|
||||
|
@ -163,16 +179,18 @@ class LookOut
|
|||
uint8_t WeakestIdx; // index for the weakest target (or a not allocated target)
|
||||
uint32_t WeakestRank; // rank of the weakest target
|
||||
|
||||
uint8_t AcftType;
|
||||
|
||||
uint8_t Targets; // [aircrafts] actual number of targets monitored
|
||||
uint8_t WorstTgtIdx; // [] most dangereous target
|
||||
uint8_t WorstTgtTime; // [0.5s] time to closest approach
|
||||
|
||||
const static uint8_t MaxTargets = 32; // maximum number of targets
|
||||
const static uint8_t MaxTargets = MaxTgts; // maximum number of targets
|
||||
LookOut_Target Target[MaxTargets]; // array of Targets
|
||||
|
||||
const static int32_t DistRange = 7000; // [m] drop immediately anything beyond this distance
|
||||
const static int16_t MinHorizSepar = 30; // [m] minimum horizontal separation
|
||||
const static int16_t MinVertSepar = 20; // [m] minimum vertical separation
|
||||
const static int32_t DistRange = 10000; // [m] drop immediately anything beyond this distance
|
||||
const static int16_t MinHorizSepar = 100; // [m] minimum horizontal separation
|
||||
const static int16_t MinVertSepar = 50; // [m] minimum vertical separation
|
||||
const static int16_t WarnTime = 20; // [sec] target warning prior to impact
|
||||
|
||||
Acft_RelPos PredMe, PredTgt; // for temporary storage of predictions.
|
||||
|
@ -225,7 +243,7 @@ class LookOut
|
|||
if(WarnLevel>0) Tgt = Target + WorstTgtIdx;
|
||||
uint8_t Len=0;
|
||||
Len+=Format_String(NMEA+Len, "$PFLAU,");
|
||||
Len+=Format_UnsDec(NMEA+Len, Targets, 1); // number of targets received
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Targets, 1); // number of targets received
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]='0'+hasPosition; // TX status
|
||||
NMEA[Len++]=',';
|
||||
|
@ -241,17 +259,20 @@ class LookOut
|
|||
NMEA[Len++]='0'+((WarnLevel>0)<<1); // alarm-type: 0=none, 2=aircraft, 3=obstacle/zone/terrain
|
||||
NMEA[Len++]=',';
|
||||
if(Tgt) // [m] relative vertical distance
|
||||
{ Len+=Format_SignDec(NMEA+Len, (Tgt->dZ)>>1, 1); }
|
||||
{ Len+=Format_SignDec(NMEA+Len, (int32_t)Tgt->dZ>>1, 1, 0, 1); }
|
||||
NMEA[Len++]=',';
|
||||
if(Tgt) // [m] relative horizontal distance
|
||||
{ Len+=Format_UnsDec(NMEA+Len, (Tgt->HorDist)>>1, 1); }
|
||||
{ Len+=Format_UnsDec(NMEA+Len, (uint32_t)Tgt->HorDist>>1, 1); }
|
||||
NMEA[Len++]=',';
|
||||
if(Tgt) // ID
|
||||
#ifdef WITH_SKYDEMON
|
||||
{ Len+=Format_Hex(NMEA+Len, Tgt->ID & 0x00FFFFFF); } // maybe just 6 digits should be produced ?
|
||||
#else
|
||||
{ Len+=Format_Hex(NMEA+Len, Tgt->ID); }
|
||||
#endif
|
||||
{ uint32_t Addr=Tgt->ID;
|
||||
Len+=Format_Hex(NMEA+Len, (uint8_t)(Addr>>16)); // 24-bit address: RND, ICAO, FLARM, OGN
|
||||
Len+=Format_Hex(NMEA+Len, (uint16_t)Addr); }
|
||||
// #ifdef WITH_SKYDEMON
|
||||
// { Len+=Format_Hex(NMEA+Len, Tgt->ID & 0x00FFFFFF); } // maybe just 6 digits should be produced ?
|
||||
// #else
|
||||
// { Len+=Format_Hex(NMEA+Len, Tgt->ID); }
|
||||
// #endif
|
||||
Len+=NMEA_AppendCheckCRNL(NMEA, Len);
|
||||
NMEA[Len]=0;
|
||||
return Len; }
|
||||
|
@ -265,7 +286,7 @@ class LookOut
|
|||
{ Report.Clear();
|
||||
Report.setAddress(ID&0xFFFFFF);
|
||||
Report.setAddrType(((ID>>24)&0x03)!=1); // ICAO or non-ICAO
|
||||
Report.setAcftType(ID>>26);
|
||||
Report.setAcftTypeOGN(ID>>26);
|
||||
Report.setAcftCall(ID);
|
||||
int32_t Alt = RefAlt+(Pos.Z>>1)+(Pos.dStdAlt>>1); // [m]
|
||||
Report.setAltitude(MetersToFeet(Alt));
|
||||
|
@ -282,7 +303,7 @@ class LookOut
|
|||
Report.setAlertStatus(Tgt->WarnLevel>0);
|
||||
Report.setAddress(Tgt->ID&0xFFFFFF);
|
||||
Report.setAddrType(((Tgt->ID>>24)&0x03)!=1);
|
||||
Report.setAcftType(Tgt->ID>>26);
|
||||
Report.setAcftTypeOGN(Tgt->ID>>26);
|
||||
Report.setAcftCall(Tgt->ID);
|
||||
int32_t Alt = RefAlt+(Tgt->Pos.Z>>1)+(Tgt->Pos.dStdAlt>>1); // [m]
|
||||
Report.setAltitude(MetersToFeet(Alt));
|
||||
|
@ -342,7 +363,9 @@ class LookOut
|
|||
template <class OGNx_Packet>
|
||||
int32_t Start(OGNx_Packet &OwnPos, uint32_t RxTime)
|
||||
{ Clear();
|
||||
ID = OwnPos.getAddressAndType() | ((uint32_t)OwnPos.Position.AcftType<<26) ;
|
||||
// ID = OwnPos.getAddressAndType() | ((uint32_t)OwnPos.Position.AcftType<<26) ;
|
||||
ID = OwnPos.Header.Address |((uint32_t)OwnPos.Header.AddrType<<24);
|
||||
AcftType = OwnPos.Position.AcftType;
|
||||
RefTime = OwnPos.getTime(RxTime); // set reference time
|
||||
RefLat = OwnPos.DecodeLatitude(); // and reference positon
|
||||
RefLon = OwnPos.DecodeLongitude();
|
||||
|
@ -392,28 +415,69 @@ class LookOut
|
|||
if( (!Tgt->Alloc) || (Tgt->DistMargin>0) ) return 0; // return NULL if target is not a thread
|
||||
return Tgt; } // return the pointer to the most dangerous target
|
||||
|
||||
const LookOut_Target *ProcessTarget(ADSL_Packet &Packet, uint32_t RxTime) // process a position of another aircraft in ADS-L format
|
||||
{ // printf("ProcessTarget(%d) ... entry\n", WeakestIdx);
|
||||
LookOut_Target *New = Target+WeakestIdx; // get a free or lowest rank slot
|
||||
New->Clear(); // put the new position there
|
||||
if(New->Pos.Read(Packet, RxTime, RefTime, RefLat, RefLon, RefAlt, LatCos, GeoidSepar, DistRange)<0) return 0; // calculate the position against the reference position
|
||||
if(!New->Pos.hasStdAlt) // if no baro altitude
|
||||
{ if(Pos.hasStdAlt) { New->Pos.dStdAlt=Pos.dStdAlt; New->Pos.hasStdAlt=1; } } // take it from own
|
||||
New->Address = Packet.getAddress();
|
||||
New->AddrType = Packet.getAddrTypeOGN();
|
||||
New->AcftType = Packet.getAcftTypeOGN();
|
||||
return ProcessTarget(New); }
|
||||
|
||||
template <class OGNx_Packet>
|
||||
const LookOut_Target *ProcessTarget(OGNx_Packet &Packet, uint32_t RxTime) // process positions of other aircrafts
|
||||
const LookOut_Target *ProcessTarget(OGNx_Packet &Packet, uint32_t RxTime, const char *Call=0) // process a position of another aircraft in OGN format
|
||||
{ // printf("ProcessTarget(%d) ... entry\n", WeakestIdx);
|
||||
LookOut_Target *New = Target+WeakestIdx; // get a free or lowest rank slot
|
||||
New->Clear(); // put the new position there
|
||||
if(New->Pos.Read(Packet, RxTime, RefTime, RefLat, RefLon, RefAlt, LatCos, DistRange)<0) return 0; // calculate the position against the reference position
|
||||
if(!New->Pos.hasStdAlt) // if no baro altitude
|
||||
{ if(Pos.hasStdAlt) { New->Pos.dStdAlt=Pos.dStdAlt; New->Pos.hasStdAlt=1;} } // take it from own
|
||||
uint32_t ID = Packet.getAddressAndType() | ((uint32_t)Packet.Position.AcftType<<26) ; // get ID
|
||||
New->ID = ID; // set ID of this position
|
||||
// printf("ProcessTarget() ... %08X\n", ID);
|
||||
uint8_t OldIdx; // possible previous index to the same ID
|
||||
New->Address = Packet.Header.Address;
|
||||
New->AddrType = Packet.Header.AddrType;
|
||||
New->AcftType = Packet.Position.AcftType;
|
||||
if(Call) { strncpy(New->Call, Call, 10); New->Call[10]=0; }
|
||||
else New->Call[0]=0;
|
||||
return ProcessTarget(New); }
|
||||
|
||||
const LookOut_Target *ProcessTarget(LookOut_Target *New)
|
||||
{ // printf("ProcessTarget() ... %08X\n", ID);
|
||||
uint8_t OldIdx;
|
||||
LookOut_Target *Old = 0; // possible previous index to the same ID
|
||||
for(OldIdx=0; OldIdx<MaxTargets; OldIdx++) // scan targets already on the list
|
||||
{ if(Target[OldIdx].Alloc==0) continue; // skip not allocated
|
||||
if(OldIdx==WeakestIdx) continue; // skip the new position
|
||||
if(Target[OldIdx].ID==ID) break; } // to find previous position for the target
|
||||
if(Target[OldIdx].ID==New->ID) break; } // to find previous position for the target
|
||||
if(OldIdx<MaxTargets) // if found
|
||||
{ if((Target[OldIdx].Pos.T-Target[OldIdx].Pred)>Target[WeakestIdx].Pos.T) return Target+OldIdx; // if position is not really newer than stop processing this (not new) position
|
||||
Target[OldIdx].Alloc=0; } // mark old position as "not allocated"
|
||||
|
||||
{ Old = Target+OldIdx;
|
||||
if((Old->Pos.T-Old->Pred)>Target[WeakestIdx].Pos.T) // if position is not really newer
|
||||
return Old; // then stop processing this (not new) position
|
||||
Old->Alloc=0; } // mark old position as "not allocated"
|
||||
New->Alloc=1; // mark this position as allocated
|
||||
|
||||
if(Old && Old->Call[0] && New->Call[0]==0) { strncpy(New->Call, Old->Call, 10); New->Call[10]=0; } // copy the call
|
||||
|
||||
if(Old && (!New->Pos.hasTurn || !New->Pos.hasClimb))
|
||||
{ int16_t Told = Old->Pos.T - Old->Pred;
|
||||
int16_t dT = New->Pos.T - Told;
|
||||
int32_t dZ = 0;
|
||||
if(Old->Pos.hasClimb)
|
||||
{ dZ = (Old->Pos.Climb*Old->Pred)>>1; }
|
||||
if(!New->Pos.hasClimb && dT>1)
|
||||
{ New->Pos.Climb = (New->Pos.Z-(Old->Pos.Z-dZ))/dT*2;
|
||||
New->Pos.hasClimb=1; }
|
||||
int16_t dH=0;
|
||||
if(Old->Pos.hasTurn)
|
||||
{ dH = (Old->Pos.Turn*Old->Pred)>>1; }
|
||||
if(!New->Pos.hasTurn && dT>1)
|
||||
{ dH = New->Pos.Heading-(Old->Pos.Heading-dH);
|
||||
New->Pos.Turn = dH/dT*2 ;
|
||||
New->Pos.hasTurn=1; }
|
||||
// printf("Climb/Turn %08X dT=%3.1fs ", New->ID, 0.5*dT); New->Pos.Print();
|
||||
}
|
||||
|
||||
AdjustRefTime(New->Pos.T); // possibly adjust the time reference after this new position time
|
||||
// printf("ProcessTarget() ... AdjustRefTime()\n");
|
||||
|
||||
|
@ -553,7 +617,7 @@ class LookOut
|
|||
TimeDelta/=2; // [sec]
|
||||
RefTime+=TimeDelta; // shift time reference
|
||||
Pos.T-=2*TimeDelta; // shift the relative time on my own position
|
||||
if(Pos.T<(-2*30)) hasPosition=0; // if older than 30sec declare "no position"
|
||||
if(Pos.T<(-2*30) || Pos.T>(+2*30)) hasPosition=0; // if older than 30sec declare "no position"
|
||||
for(uint8_t Idx=0; Idx<MaxTargets; Idx++) // go over the targets
|
||||
{ LookOut_Target &Tgt = Target[Idx]; if(!Tgt.Alloc) continue; // skip unallocated
|
||||
Tgt.Pos.T-=2*TimeDelta; // shift the relative time
|
||||
|
|
|
@ -137,7 +137,7 @@ void app_main(void)
|
|||
|
||||
#ifdef WITH_SDLOG
|
||||
Log_Mutex = xSemaphoreCreateMutex();
|
||||
xTaskCreate(vTaskSDLOG, "SDLOG", 3000, 0, tskIDLE_PRIORITY+1, 0);
|
||||
xTaskCreate(vTaskSDLOG, "SDLOG", 4000, 0, tskIDLE_PRIORITY+1, 0);
|
||||
#endif
|
||||
|
||||
#ifdef WITH_LOG
|
||||
|
|
|
@ -7,13 +7,13 @@ uint8_t NMEA_Check(uint8_t *NMEA, uint8_t Len) // NMEA check-sum
|
|||
return Check; }
|
||||
|
||||
uint8_t NMEA_AppendCheck(uint8_t *NMEA, uint8_t Len)
|
||||
{ uint8_t Check=NMEA_Check(NMEA+1, Len-1);
|
||||
NMEA[Len ]='*';
|
||||
uint8_t Digit=Check>>4; NMEA[Len+1] = Digit<10 ? Digit+'0':Digit+'A'-10;
|
||||
{ uint8_t Check=NMEA_Check(NMEA+1, Len-1); // exclude the starting '$'
|
||||
NMEA[Len ]='*'; // add '*'
|
||||
uint8_t Digit=Check>>4; NMEA[Len+1] = Digit<10 ? Digit+'0':Digit+'A'-10; // and checksum in hex
|
||||
Digit=Check&0xF; NMEA[Len+2] = Digit<10 ? Digit+'0':Digit+'A'-10;
|
||||
return 3; }
|
||||
return 3; } // return number of characters added
|
||||
|
||||
uint8_t NMEA_AppendCheckCRNL(uint8_t *NMEA, uint8_t Len)
|
||||
{ uint8_t CheckLen=NMEA_AppendCheck(NMEA, Len);
|
||||
Len+=CheckLen; NMEA[Len]='\n';
|
||||
return CheckLen+1; }
|
||||
{ uint8_t CheckLen=NMEA_AppendCheck(NMEA, Len); // add *XY
|
||||
Len+=CheckLen; NMEA[Len++]='\r'; NMEA[Len++]='\n'; NMEA[Len]=0; // add CR, LF, NL
|
||||
return CheckLen+2; }
|
||||
|
|
|
@ -35,8 +35,13 @@ inline uint8_t NMEA_AppendCheckCRNL(char *NMEA, uint8_t Len) { return NMEA_Appen
|
|||
if(Len==0) // if data is empty
|
||||
{ if(Byte!='$') return; // then ignore all bytes but '$'
|
||||
Data[Len++]=Byte; // start storing the frame
|
||||
setLoading(); Check=0x00; Parms=0; // set state to "isLoading", clear checksum
|
||||
} else // if not empty (being loaded)
|
||||
setLoading(); Check=0x00; Parms=0; } // set state to "isLoading", clear checksum
|
||||
/*
|
||||
if(Byte=='$') // should '$' sign restart an ongoing NMEA sentence ?
|
||||
{ Len=0; Data[Len++]=Byte;
|
||||
setLoading(); Check=0x00; Parms=0; }
|
||||
*/
|
||||
else
|
||||
{ if((Byte=='\r')||(Byte=='\n')) // if CR (or NL ?) then frame is complete
|
||||
{ setComplete(); if(Len<MaxLen) Data[Len]=0;
|
||||
return; }
|
||||
|
|
262
main/ogn.h
262
main/ogn.h
|
@ -16,7 +16,7 @@
|
|||
#include "bitcount.h"
|
||||
#include "nmea.h"
|
||||
#include "ubx.h"
|
||||
#include "mavlink.h"
|
||||
// #include "mavlink.h"
|
||||
|
||||
#include "ldpc.h"
|
||||
|
||||
|
@ -64,12 +64,12 @@ template <class OGNx_Packet, class OGNy_Packet>
|
|||
// ---------------------------------------------------------------------------------------------------------------------
|
||||
|
||||
template <class OGNx_Packet=OGN1_Packet>
|
||||
class OGN_TxPacket // OGN packet with FEC code, like for transmission
|
||||
class OGN_TxPacket // OGN packet with FEC code, ready for transmission
|
||||
{ public:
|
||||
static const int Words = 7;
|
||||
static const int Bytes = 26;
|
||||
|
||||
OGNx_Packet Packet; // OGN packet
|
||||
OGNx_Packet Packet; // OGN packet [20 bytes = 160 bits]
|
||||
|
||||
uint32_t FEC[2]; // Gallager code: 48 check bits for 160 user bits
|
||||
|
||||
|
@ -83,7 +83,7 @@ template <class OGNx_Packet=OGN1_Packet>
|
|||
Len+=Format_Hex(Out+Len, (uint8_t)(Addr>>16));
|
||||
Len+=Format_Hex(Out+Len, (uint16_t)Addr);
|
||||
Out[Len++]=' ';
|
||||
Len+=Format_UnsDec(Out+Len, (uint16_t)Packet.Position.Time, 2);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Packet.Position.Time, 2);
|
||||
Out[Len++]=' ';
|
||||
Len+=Format_Latitude(Out+Len, Packet.DecodeLatitude());
|
||||
Out[Len++]=' ';
|
||||
|
@ -383,7 +383,7 @@ template <class OGNx_Packet=OGN1_Packet>
|
|||
{ uint8_t Len=0;
|
||||
Len+=Format_String(NMEA+Len, "$POGNT,"); // sentence name
|
||||
if(Packet.Position.Time<60)
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint16_t)Packet.Position.Time, 2); // [sec] time
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Packet.Position.Time, 2); // [sec] time
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]=HexDigit(Packet.Position.AcftType); // [0..F] aircraft-type: 1=glider, 2=tow plane, etc.
|
||||
NMEA[Len++]=',';
|
||||
|
@ -398,7 +398,7 @@ template <class OGNx_Packet=OGN1_Packet>
|
|||
NMEA[Len++]='0'+Packet.Position.FixQuality; // [] fix quality
|
||||
NMEA[Len++]='0'+Packet.Position.FixMode; // [] fix mode
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint16_t)(Packet.DecodeDOP()+10),2,1); // [] Dilution of Precision
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)(Packet.DecodeDOP()+10),2,1); // [] Dilution of Precision
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_Latitude(NMEA+Len, Packet.DecodeLatitude()); // [] Latitude
|
||||
NMEA[Len++]=',';
|
||||
|
@ -417,9 +417,9 @@ template <class OGNx_Packet=OGN1_Packet>
|
|||
NMEA[Len++]=',';
|
||||
Len+=Format_SignDec(NMEA+Len, Packet.DecodeTurnRate(), 2, 1); // [deg/s] turning rate (by GPS)
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_SignDec(NMEA+Len, -(int16_t)RxRSSI/2); // [dBm] received signal level
|
||||
Len+=Format_SignDec(NMEA+Len, -(int32_t)RxRSSI/2); // [dBm] received signal level
|
||||
NMEA[Len++]=',';
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint16_t)RxErr); // [bits] corrected transmisison errors
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)RxErr); // [bits] corrected transmisison errors
|
||||
Len+=NMEA_AppendCheckCRNL(NMEA, Len);
|
||||
NMEA[Len]=0;
|
||||
return Len; }
|
||||
|
@ -477,9 +477,9 @@ template <class OGNx_Packet=OGN1_Packet>
|
|||
Len+=Format_Hex(Out+Len, (uint8_t)(Addr>>16));
|
||||
Len+=Format_Hex(Out+Len, (uint16_t)Addr);
|
||||
Out[Len++]=' ';
|
||||
Len+=Format_SignDec(Out+Len, -(int16_t)RxRSSI/2); Out[Len++]='d'; Out[Len++]='B'; Out[Len++]='m';
|
||||
Len+=Format_SignDec(Out+Len, -(int32_t)RxRSSI/2); Out[Len++]='d'; Out[Len++]='B'; Out[Len++]='m';
|
||||
Out[Len++]=' ';
|
||||
Len+=Format_UnsDec(Out+Len, (uint16_t)Packet.Position.Time, 2);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Packet.Position.Time, 2);
|
||||
Out[Len++]='s'; Out[Len++]=' ';
|
||||
Len+=Format_Latitude(Out+Len, Packet.DecodeLatitude());
|
||||
Out[Len++]=' ';
|
||||
|
@ -487,9 +487,9 @@ template <class OGNx_Packet=OGN1_Packet>
|
|||
Out[Len++]=' ';
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Packet.DecodeAltitude()); Out[Len++]='m';
|
||||
Out[Len++]=' ';
|
||||
Len+=Format_UnsDec(Out+Len, Packet.DecodeSpeed(), 2, 1); Out[Len++]='m'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Packet.DecodeSpeed(), 2, 1); Out[Len++]='m'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Out[Len++]=' ';
|
||||
Len+=Format_SignDec(Out+Len, Packet.DecodeClimbRate(), 2, 1); Out[Len++]='m'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Len+=Format_SignDec(Out+Len, (int32_t)Packet.DecodeClimbRate(), 2, 1); Out[Len++]='m'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Out[Len++]=' ';
|
||||
Out[Len++]='r';
|
||||
Len+=Format_Hex(Out+Len, Rank);
|
||||
|
@ -663,7 +663,7 @@ template<class OGNx_Packet, uint8_t Size=8>
|
|||
{ Out[Len++]='/'; Len+=Format_Hex(Out+Len, Packet[Idx].Packet.getAddressAndType() ); // print address-type and address
|
||||
Out[Len++]=':';
|
||||
if(Packet[Idx].Packet.Header.Encrypted) Len+=Format_String(Out+Len, "ee");
|
||||
else Len+=Format_UnsDec(Out+Len, Packet[Idx].Packet.Position.Time, 2); // [sec] print time
|
||||
else Len+=Format_UnsDec(Out+Len, (uint32_t)Packet[Idx].Packet.Position.Time, 2); // [sec] print time
|
||||
}
|
||||
}
|
||||
Out[Len++]=' '; Len+=Format_Hex(Out+Len, Sum); // sum of all Ranks
|
||||
|
@ -685,29 +685,29 @@ class GPS_Time
|
|||
|
||||
uint8_t FormatDate(char *Out, char Sep='.') const
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_UnsDec(Out+Len, Day, 2);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Day, 2);
|
||||
Out[Len++]=Sep;
|
||||
Len+=Format_UnsDec(Out+Len, Month, 2);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Month, 2);
|
||||
Out[Len++]=Sep;
|
||||
Len+=Format_UnsDec(Out+Len, Year, 2);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Year, 2);
|
||||
Out[Len]=0; return Len; }
|
||||
|
||||
uint8_t FormatTime(char *Out, char Sep=':') const
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_UnsDec(Out+Len, Hour, 2);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Hour, 2);
|
||||
Out[Len++]=Sep;
|
||||
Len+=Format_UnsDec(Out+Len, Min, 2);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Min, 2);
|
||||
Out[Len++]=Sep;
|
||||
Len+=Format_UnsDec(Out+Len, Sec, 2);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Sec, 2);
|
||||
Out[Len++]='.';
|
||||
Len+=Format_UnsDec(Out+Len, mSec, 3);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)mSec, 3);
|
||||
Out[Len]=0; return Len; }
|
||||
|
||||
bool isTimeValid(void) const // is the GPS time-of-day valid
|
||||
{ return (Hour>=0) && (Min>=0) && (Sec>=0); } // all data must have been correctly read: negative means not correctly read)
|
||||
|
||||
bool isDateValid(void) const // is the GPS date valid ?
|
||||
{ return (Year>=0) && (Month>=0) && (Day>=0); }
|
||||
{ return (Year<70) && (Year>0) && (Month>0) && (Day>0); } // MTK GPS can produce fake date with year 1980, so we treat it as invalid
|
||||
|
||||
int8_t incrTimeFrac(int16_t msFrac) // [ms]
|
||||
{ mSec+=msFrac;
|
||||
|
@ -805,6 +805,8 @@ class GPS_Time
|
|||
Days -= 365*Year + (Year/4);
|
||||
Month = Days/31;
|
||||
Day = Days-(uint16_t)Month*31+1; Month++;
|
||||
uint8_t MaxDay=MonthDays();
|
||||
if(Day>MaxDay) { Day-=MaxDay; Month++; }
|
||||
uint32_t CheckTime = getUnixTime();
|
||||
if(CheckTime<Time) incrDate((Time-CheckTime)/SecsPerDay); }
|
||||
|
||||
|
@ -1042,28 +1044,28 @@ class GPS_Position: public GPS_Time
|
|||
Out[Len++]=isTimeValid() ?'T':'_';
|
||||
Out[Len++]=isDateValid() ?'D':'_';
|
||||
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, (uint16_t)Hour, 2);
|
||||
Out[Len++]=':'; Len+=Format_UnsDec(Out+Len, (uint16_t)Min, 2);
|
||||
Out[Len++]=':'; Len+=Format_UnsDec(Out+Len, (uint16_t)Sec, 2);
|
||||
Out[Len++]='.'; Len+=Format_UnsDec(Out+Len, (uint16_t)mSec, 3);
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, (uint16_t)FixQuality);
|
||||
Out[Len++]='/'; Len+=Format_UnsDec(Out+Len, (uint16_t)FixMode);
|
||||
Out[Len++]='/'; Len+=Format_UnsDec(Out+Len, (uint16_t)Satellites, 2);
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, PDOP, 2, 1);
|
||||
Out[Len++]='/'; Len+=Format_UnsDec(Out+Len, HDOP, 2, 1);
|
||||
Out[Len++]='/'; Len+=Format_UnsDec(Out+Len, VDOP, 2, 1);
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, (uint32_t)Hour, 2);
|
||||
Out[Len++]=':'; Len+=Format_UnsDec(Out+Len, (uint32_t)Min, 2);
|
||||
Out[Len++]=':'; Len+=Format_UnsDec(Out+Len, (uint32_t)Sec, 2);
|
||||
Out[Len++]='.'; Len+=Format_UnsDec(Out+Len, (uint32_t)mSec, 3);
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, (uint32_t)FixQuality);
|
||||
Out[Len++]='/'; Len+=Format_UnsDec(Out+Len, (uint32_t)FixMode);
|
||||
Out[Len++]='/'; Len+=Format_UnsDec(Out+Len, (uint32_t)Satellites, 2);
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, (uint32_t)PDOP, 2, 1);
|
||||
Out[Len++]='/'; Len+=Format_UnsDec(Out+Len, (uint32_t)HDOP, 2, 1);
|
||||
Out[Len++]='/'; Len+=Format_UnsDec(Out+Len, (uint32_t)VDOP, 2, 1);
|
||||
Out[Len++]=' ';
|
||||
Out[Len++]='['; Len+=Format_SignDec(Out+Len, Latitude/6, 7, 5);
|
||||
Out[Len++]=','; Len+=Format_SignDec(Out+Len, Longitude/6, 8, 5);
|
||||
Out[Len++]=']'; Out[Len++]='d'; Out[Len++]='e'; Out[Len++]='g';
|
||||
Out[Len++]=' '; Len+=Format_SignDec(Out+Len, Altitude, 4, 1); Out[Len++]='m';
|
||||
Out[Len++]='/'; Len+=Format_SignDec(Out+Len, GeoidSeparation, 4, 1); Out[Len++]='m';
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, Speed, 2, 1); Out[Len++]='m'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, Heading, 4, 1); Out[Len++]='d'; Out[Len++]='e'; Out[Len++]='g';
|
||||
Out[Len++]=' '; Len+=Format_SignDec(Out+Len, ClimbRate, 2, 1); Out[Len++]='m'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Out[Len++]=' '; Len+=Format_SignDec(Out+Len, TurnRate, 2, 1); Out[Len++]='d'; Out[Len++]='e'; Out[Len++]='g'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Out[Len++]='/'; Len+=Format_SignDec(Out+Len, (int32_t)GeoidSeparation, 4, 1); Out[Len++]='m';
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, (uint32_t)Speed, 2, 1); Out[Len++]='m'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, (uint32_t)Heading, 4, 1); Out[Len++]='d'; Out[Len++]='e'; Out[Len++]='g';
|
||||
Out[Len++]=' '; Len+=Format_SignDec(Out+Len, (int32_t)ClimbRate, 2, 1); Out[Len++]='m'; Out[Len++]='/'; Out[Len++]='s';
|
||||
Out[Len++]=' '; Len+=Format_SignDec(Out+Len, (int32_t)TurnRate, 2, 1); Out[Len++]='d'; Out[Len++]='e'; Out[Len++]='g'; Out[Len++]='/'; Out[Len++]='s';
|
||||
if(hasBaro)
|
||||
{ Out[Len++]=' '; Len+=Format_SignDec(Out+Len, Temperature, 2, 1); Out[Len++]='C';
|
||||
{ Out[Len++]=' '; Len+=Format_SignDec(Out+Len, (int32_t)Temperature, 2, 1); Out[Len++]='C';
|
||||
Out[Len++]=' '; Len+=Format_UnsDec(Out+Len, Pressure/4 ); Out[Len++]='P'; Out[Len++]='a';
|
||||
Out[Len++]=' '; Len+=Format_SignDec(Out+Len, StdAltitude, 2, 1); Out[Len++]='m'; }
|
||||
Out[Len++]='\n'; Out[Len++]=0; return Len; }
|
||||
|
@ -1150,41 +1152,106 @@ class GPS_Position: public GPS_Time
|
|||
ReadAltitude(*RxMsg.ParmPtr(9), (const char *)RxMsg.ParmPtr(8)); // Altitude
|
||||
ReadGeoidSepar(*RxMsg.ParmPtr(11), (const char *)RxMsg.ParmPtr(10)); // Geoid separation
|
||||
calcLatitudeCosine();
|
||||
return 1; }
|
||||
NMEAframes++; return 1; }
|
||||
|
||||
uint8_t WriteGGA(char *GGA)
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_String(GGA+Len, "$GPGGA,");
|
||||
Len+=Format_UnsDec(GGA+Len, (uint16_t)Hour, 2);
|
||||
Len+=Format_UnsDec(GGA+Len, (uint16_t)Min, 2);
|
||||
Len+=Format_UnsDec(GGA+Len, (uint16_t)Sec, 2);
|
||||
GGA[Len++]='.';
|
||||
Len+=Format_UnsDec(GGA+Len, (uint16_t)mSec, 3);
|
||||
GGA[Len++]=',';
|
||||
Len+=Format_Latitude(GGA+Len, Latitude);
|
||||
GGA[Len]=GGA[Len-1]; GGA[Len-1]=','; Len++;
|
||||
GGA[Len++]=',';
|
||||
Len+=Format_Longitude(GGA+Len, Longitude);
|
||||
GGA[Len]=GGA[Len-1]; GGA[Len-1]=','; Len++;
|
||||
GGA[Len++]=',';
|
||||
GGA[Len++]='0'+FixQuality;
|
||||
GGA[Len++]=',';
|
||||
Len+=Format_UnsDec(GGA+Len, (uint16_t)Satellites);
|
||||
GGA[Len++]=',';
|
||||
Len+=Format_UnsDec(GGA+Len, (uint16_t)HDOP, 2, 1);
|
||||
GGA[Len++]=',';
|
||||
Len+=Format_SignDec(GGA+Len, Altitude, 3, 1);
|
||||
GGA[Len++]=',';
|
||||
GGA[Len++]='M';
|
||||
GGA[Len++]=',';
|
||||
Len+=Format_SignDec(GGA+Len, GeoidSeparation, 3, 1);
|
||||
GGA[Len++]=',';
|
||||
GGA[Len++]='M';
|
||||
GGA[Len++]=',';
|
||||
GGA[Len++]=',';
|
||||
Len += NMEA_AppendCheckCRNL(GGA, Len);
|
||||
GGA[Len]=0;
|
||||
return Len; }
|
||||
uint8_t WritePGRMZ(char *NMEA)
|
||||
{ uint8_t Len=Format_String(NMEA, "$PGRMZ,");
|
||||
if(hasBaro) Len+=Format_SignDec(NMEA+Len, MetersToFeet(StdAltitude)/10, 1, 0, 1);
|
||||
Len+=Format_String(NMEA+Len, ",f,"); // normally f for feet, but metres and m works with XcSoar
|
||||
NMEA[Len++]='0'+FixMode; // 1 = no fix, 2 = 2D, 3 = 3D
|
||||
Len+=NMEA_AppendCheckCRNL(NMEA, Len);
|
||||
NMEA[Len]=0; return Len; }
|
||||
|
||||
uint8_t WriteGSA(char *NMEA) const
|
||||
{ uint8_t Len=Format_String(NMEA+Len, "$GPGSA,A,");
|
||||
NMEA[Len++]='0'+FixMode;
|
||||
Len+=Format_String(NMEA+Len, ",,,,,,,,,,,,,");
|
||||
if(isValid()) Len+=Format_UnsDec(NMEA+Len, (uint32_t)PDOP, 2, 1);
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) Len+=Format_UnsDec(NMEA+Len, (uint32_t)HDOP, 2, 1);
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) Len+=Format_UnsDec(NMEA+Len, (uint32_t)VDOP, 2, 1);
|
||||
Len += NMEA_AppendCheckCRNL(NMEA, Len);
|
||||
NMEA[Len]=0; return Len; }
|
||||
|
||||
uint8_t WriteRMC(char *NMEA) const
|
||||
{ uint8_t Len=Format_String(NMEA+Len, "$GPRMC,");
|
||||
if(isTimeValid())
|
||||
{ Len+=Format_UnsDec(NMEA+Len, (uint32_t)Hour, 2);
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Min, 2);
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Sec, 2);
|
||||
NMEA[Len++]='.';
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)mSec, 3);
|
||||
Len--; }
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++] = isValid()?'A':'V';
|
||||
NMEA[Len++]=',';
|
||||
if(isValid())
|
||||
{ Len+=Format_Latitude(NMEA+Len, Latitude);
|
||||
// NMEA[Len+1]=NMEA[Len-1]; NMEA[Len-1]='0'; NMEA[Len]=','; Len+=2; }
|
||||
NMEA[Len]=NMEA[Len-1]; NMEA[Len-1]=','; Len++; }
|
||||
else NMEA[Len++]=',';
|
||||
NMEA[Len++]=',';
|
||||
if(isValid())
|
||||
{ Len+=Format_Longitude(NMEA+Len, Longitude);
|
||||
// NMEA[Len+1]=NMEA[Len-1]; NMEA[Len-1]='0'; NMEA[Len]=','; Len+=2; }
|
||||
NMEA[Len]=NMEA[Len-1]; NMEA[Len-1]=','; Len++; }
|
||||
else NMEA[Len++]=',';
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) Len+=Format_UnsDec(NMEA+Len, ((uint32_t)Speed*1985+512)>>10, 2, 1); // [0.1m/s] => [0.1kt]
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) Len+=Format_UnsDec(NMEA+Len, (uint32_t)Heading, 2, 1);
|
||||
NMEA[Len++]=',';
|
||||
if(isDateValid())
|
||||
{ Len+=Format_UnsDec(NMEA+Len, (uint32_t)Day, 2);
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Month, 2);
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Year, 2); }
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]=isValid()?'A':'N';
|
||||
Len += NMEA_AppendCheckCRNL(NMEA, Len);
|
||||
NMEA[Len]=0; return Len; }
|
||||
|
||||
uint8_t WriteGGA(char *NMEA) const
|
||||
{ uint8_t Len=Format_String(NMEA+Len, "$GPGGA,");
|
||||
if(isTimeValid())
|
||||
{ Len+=Format_UnsDec(NMEA+Len, (uint32_t)Hour, 2);
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Min, 2);
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)Sec, 2);
|
||||
NMEA[Len++]='.';
|
||||
Len+=Format_UnsDec(NMEA+Len, (uint32_t)mSec, 3);
|
||||
Len--; }
|
||||
NMEA[Len++]=',';
|
||||
if(isValid())
|
||||
{ Len+=Format_Latitude(NMEA+Len, Latitude);
|
||||
// NMEA[Len+1]=NMEA[Len-1]; NMEA[Len-1]='0'; NMEA[Len]=','; Len+=2; }
|
||||
NMEA[Len]=NMEA[Len-1]; NMEA[Len-1]=','; Len++; }
|
||||
else NMEA[Len++]=',';
|
||||
NMEA[Len++]=',';
|
||||
if(isValid())
|
||||
{ Len+=Format_Longitude(NMEA+Len, Longitude);
|
||||
// NMEA[Len+1]=NMEA[Len-1]; NMEA[Len-1]='0'; NMEA[Len]=','; Len+=2; }
|
||||
NMEA[Len]=NMEA[Len-1]; NMEA[Len-1]=','; Len++; }
|
||||
else NMEA[Len++]=',';
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) NMEA[Len++]='0'+FixQuality;
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) Len+=Format_UnsDec(NMEA+Len, (uint32_t)Satellites);
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) Len+=Format_UnsDec(NMEA+Len, (uint32_t)HDOP, 2, 1);
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) Len+=Format_SignDec(NMEA+Len, Altitude, 3, 1, 1);
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]='M';
|
||||
NMEA[Len++]=',';
|
||||
if(isValid()) Len+=Format_SignDec(NMEA+Len, GeoidSeparation, 3, 1, 1);
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]='M';
|
||||
NMEA[Len++]=',';
|
||||
NMEA[Len++]=',';
|
||||
Len += NMEA_AppendCheckCRNL(NMEA, Len);
|
||||
NMEA[Len]=0; return Len; }
|
||||
|
||||
int8_t ReadGGA(const char *GGA)
|
||||
{ if( (memcmp(GGA, "$GPGGA", 6)!=0) && (memcmp(GGA, "$GNGGA", 6)!=0) ) return -1; // check if the right sequence
|
||||
|
@ -1200,7 +1267,7 @@ class GPS_Position: public GPS_Time
|
|||
ReadAltitude(GGA[Index[9]], GGA+Index[8]); // Altitude
|
||||
ReadGeoidSepar(GGA[Index[11]], GGA+Index[10]); // Geoid separation
|
||||
calcLatitudeCosine();
|
||||
return 1; }
|
||||
NMEAframes++; return 1; }
|
||||
|
||||
int8_t ReadGSA(NMEA_RxMsg &RxMsg)
|
||||
{ if(RxMsg.Parms<17) return -1;
|
||||
|
@ -1208,7 +1275,7 @@ class GPS_Position: public GPS_Time
|
|||
ReadPDOP((const char *)RxMsg.ParmPtr(14)); // total dilution of precision
|
||||
ReadHDOP((const char *)RxMsg.ParmPtr(15)); // horizontal dilution of precision
|
||||
ReadVDOP((const char *)RxMsg.ParmPtr(16)); // vertical dilution of precision
|
||||
return 1; }
|
||||
NMEAframes++; return 1; }
|
||||
|
||||
int8_t ReadGSA(const char *GSA)
|
||||
{ if( (memcmp(GSA, "$GPGSA", 6)!=0) && (memcmp(GSA, "$GNGSA", 6)!=0) ) return -1; // check if the right sequence
|
||||
|
@ -1217,7 +1284,7 @@ class GPS_Position: public GPS_Time
|
|||
ReadPDOP(GSA+Index[14]);
|
||||
ReadHDOP(GSA+Index[15]);
|
||||
ReadVDOP(GSA+Index[16]);
|
||||
return 1; }
|
||||
NMEAframes++; return 1; }
|
||||
/*
|
||||
int8_t ReadGSV(NMEA_RxMsg &RxMsg)
|
||||
{ //
|
||||
|
@ -1238,7 +1305,7 @@ class GPS_Position: public GPS_Time
|
|||
ReadSpeed((const char *)RxMsg.ParmPtr(6)); // Speed
|
||||
ReadHeading((const char *)RxMsg.ParmPtr(7)); // Heading
|
||||
calcLatitudeCosine();
|
||||
return 1; }
|
||||
NMEAframes++; return 1; }
|
||||
|
||||
int8_t ReadRMC(const char *RMC)
|
||||
{ if( (memcmp(RMC, "$GPRMC", 6)!=0) && (memcmp(RMC, "$GNRMC", 6)!=0) ) return -1; // check if the right sequence
|
||||
|
@ -1250,7 +1317,7 @@ class GPS_Position: public GPS_Time
|
|||
ReadSpeed(RMC+Index[6]);
|
||||
ReadHeading(RMC+Index[7]);
|
||||
calcLatitudeCosine();
|
||||
return 1; }
|
||||
NMEAframes++; return 1; }
|
||||
/*
|
||||
int32_t calcTimeDiff(GPS_Position &RefPos) const
|
||||
{ int32_t TimeDiff = ((int32_t)Min*6000+(int16_t)Sec*100+FracSec) - ((int32_t)RefPos.Min*6000+(int16_t)RefPos.Sec*100+RefPos.FracSec);
|
||||
|
@ -1302,7 +1369,7 @@ class GPS_Position: public GPS_Time
|
|||
// useBaro, Sec, mSec, hasBaro, RefPos.hasBaro, TimeDiff, 0.1*Altitude, 0.1*StdAltitude, 0.1*ClimbRate);
|
||||
hasClimb=1; hasTurn=1; hasAccel=1;
|
||||
return TimeDiff; } // [ms]
|
||||
|
||||
/*
|
||||
void Write(MAV_GPS_RAW_INT *MAV) const
|
||||
{ MAV->time_usec = (int64_t)1000000*getUnixTime()+1000*mSec; // [usec]
|
||||
MAV->lat = ((int64_t)50*Latitude+1)/3;
|
||||
|
@ -1346,7 +1413,7 @@ class GPS_Position: public GPS_Time
|
|||
Pressure = 100*4*MAV->press_abs;
|
||||
Temperature = MAV->temperature/10;
|
||||
hasBaro=1; }
|
||||
|
||||
*/
|
||||
static int32_t getCordic(int32_t Coord) { return ((int64_t)Coord*83399993+(1<<21))>>22; } // [0.0001/60 deg] => [cordic]
|
||||
int32_t getCordicLatitude (void) const { return getCordic(Latitude ); }
|
||||
int32_t getCordicLongitude(void) const { return getCordic(Longitude); }
|
||||
|
@ -1355,7 +1422,7 @@ class GPS_Position: public GPS_Time
|
|||
// 180 0x066FF300 0x80000000 0x7FFFBC00
|
||||
static int32_t getFANETcordic(int32_t Coord) { return ((int64_t)Coord*83399317+(1<<21))>>22; } // [0.0001/60 deg] => [FANET cordic]
|
||||
|
||||
void EncodeAirPos(FANET_Packet &Packet, uint8_t AcftType=1, bool Track=1)
|
||||
void EncodeAirPos(FANET_Packet &Packet, uint8_t AcftType=1, bool Track=1) const
|
||||
{ int32_t Alt = Altitude; if(Alt<0) Alt=0; else Alt=(Alt+5)/10;
|
||||
int32_t Lat = getFANETcordic(Latitude); // Latitude: [0.0001/60deg] => [cordic]
|
||||
int32_t Lon = getFANETcordic(Longitude); // Longitude: [0.0001/60deg] => [cordic]
|
||||
|
@ -1380,13 +1447,18 @@ class GPS_Position: public GPS_Time
|
|||
Report.setHeading((HeadAngle+0x80)>>8); // [8-bit cordic]
|
||||
Report.setMiscInd(0x2); //
|
||||
Report.setSpeed((SpeedKts+5)/10); // [knot]
|
||||
Report.setClimbRate(6*MetersToFeet(ClimbRate));
|
||||
}
|
||||
Report.setClimbRate(6*MetersToFeet(ClimbRate)); }
|
||||
|
||||
void Encode(GDL90_GEOMALT &GeomAlt) const
|
||||
{ GeomAlt.Clear();
|
||||
int32_t Alt = MetersToFeet(Altitude+GeoidSeparation); // [0.1feet]
|
||||
GeomAlt.setAltitude((Alt+25)/50); // [5feet]
|
||||
GeomAlt.setFOM((HDOP*3+5)/10); } // [m]
|
||||
|
||||
void Encode(ADSL_Packet &Packet) const
|
||||
{ Packet.setAlt((Altitude+GeoidSeparation+5)/10);
|
||||
Packet.setLat(Packet.OGNtoFNT(Latitude));
|
||||
Packet.setLon(Packet.OGNtoFNT(Longitude));
|
||||
Packet.setLatOGN(Latitude);
|
||||
Packet.setLonOGN(Longitude);
|
||||
Packet.TimeStamp = (Sec*4+mSec/250)&0x3F;
|
||||
Packet.setSpeed(((uint32_t)Speed*4+5)/10);
|
||||
Packet.setClimb(((int32_t)ClimbRate*8+5)/10);
|
||||
|
@ -1395,8 +1467,8 @@ class GPS_Position: public GPS_Time
|
|||
Packet.setTrack(((uint32_t)Heading*32+112)/225);
|
||||
Packet.Integrity[0]=0; Packet.Integrity[1]=0;
|
||||
if((FixQuality>0)&&(FixMode>=2))
|
||||
{ Packet.setHorPrec((HDOP*2+5)/10);
|
||||
Packet.setVerPrec((VDOP*3+5)/10); }
|
||||
{ Packet.setHorAccur((HDOP*2+5)/10);
|
||||
Packet.setVerAccur((VDOP*3+5)/10); }
|
||||
}
|
||||
|
||||
// template <class OGNx_Packet>
|
||||
|
@ -1615,27 +1687,27 @@ class GPS_Position: public GPS_Time
|
|||
char LonW = Out[Len-2];
|
||||
Out[Len-2]=Out[Len-3]; Out[Len-3]=Out[Len-4]; Out[Len-4]='.';
|
||||
Out[Len++]=Icon[1];
|
||||
Len+=Format_UnsDec(Out+Len, Heading/10, 3); // [deg] Heading
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Heading/10, 3); // [deg] Heading
|
||||
Out[Len++]='/';
|
||||
Len+=Format_UnsDec(Out+Len, ((uint32_t)Speed*199+512)>>10, 3); // [kt] speed
|
||||
Out[Len++] = '/'; Out[Len++] = 'A'; Out[Len++] = '='; Len+=Format_UnsDec(Out+Len, (MetersToFeet(Altitude)+5)/10, 6); // [feet] altitude
|
||||
Out[Len++] = '/'; Out[Len++] = 'A'; Out[Len++] = '='; Len+=Format_UnsDec(Out+Len, ((uint32_t)MetersToFeet(Altitude)+5)/10, 6); // [feet] altitude
|
||||
Out[Len++]=' '; Out[Len++]='!'; Out[Len++]='W'; Out[Len++]=LatW; Out[Len++]=LonW; Out[Len++]='!'; // more accurate Lat/Lon
|
||||
Out[Len++]=' '; Out[Len++]='i'; Out[Len++]='d'; Len+=Format_Hex(Out+Len, ID); // ID
|
||||
|
||||
Out[Len++] = ' '; Len+=Format_SignDec(Out+Len, ((int32_t)ClimbRate*10079+256)>>9, 3); Out[Len++] = 'f'; Out[Len++] = 'p'; Out[Len++] = 'm'; // [fpm]
|
||||
Out[Len++] = ' '; Len+=Format_SignDec(Out+Len, TurnRate/3, 2, 1); Out[Len++] = 'r'; Out[Len++] = 'o'; Out[Len++] = 't'; // [ROT]
|
||||
Out[Len++] = ' '; Len+=Format_SignDec(Out+Len, (int32_t)TurnRate/3, 2, 1); Out[Len++] = 'r'; Out[Len++] = 'o'; Out[Len++] = 't'; // [ROT]
|
||||
|
||||
if(hasBaro)
|
||||
{ int32_t Alt=(StdAltitude+5)/10; // [m] standard pressure altitude
|
||||
if(Alt<0) Alt=0;
|
||||
Out[Len++] = ' '; Out[Len++] = 'F'; Out[Len++] = 'L';
|
||||
Len+=Format_UnsDec(Out+Len, MetersToFeet((uint32_t)Alt), 5, 2); } // [feet] "Flight Level"
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)MetersToFeet((uint32_t)Alt), 5, 2); } // [feet] "Flight Level"
|
||||
|
||||
uint16_t DOP=PDOP; if(DOP==0) DOP=HDOP;
|
||||
uint16_t HorPrec=(DOP*2+5)/10; if(HorPrec>63) HorPrec=63; // [m]
|
||||
uint16_t VerPrec=(DOP*3+5)/10; if(VerPrec>63) VerPrec=63; // [m]
|
||||
Out[Len++] = ' '; Out[Len++] = 'g'; Out[Len++] = 'p'; Out[Len++] = 's';
|
||||
Len+=Format_UnsDec(Out+Len, HorPrec); Out[Len++] = 'x'; Len+=Format_UnsDec(Out+Len, VerPrec);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)HorPrec); Out[Len++] = 'x'; Len+=Format_UnsDec(Out+Len, (uint32_t)VerPrec);
|
||||
|
||||
Out[Len]=0; return Len; }
|
||||
|
||||
|
@ -1643,16 +1715,16 @@ class GPS_Position: public GPS_Time
|
|||
{ int Len=0;
|
||||
bool Neg = Coord<0; if(Neg) Coord=(-Coord);
|
||||
int32_t Deg = Coord/600000;
|
||||
Len+=Format_UnsDec(Out+Len, Deg, DegSize);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Deg, DegSize);
|
||||
Coord-=Deg*600000; Coord/=10;
|
||||
Len+=Format_UnsDec(Out+Len, Coord, 5);
|
||||
Len+=Format_UnsDec(Out+Len, (uint32_t)Coord, 5);
|
||||
Out[Len++]=SignChar[Neg];
|
||||
return Len; }
|
||||
|
||||
int WriteHHMMSS(char *Out) const
|
||||
{ Format_UnsDec(Out , Hour, 2);
|
||||
Format_UnsDec(Out+2, Min , 2);
|
||||
Format_UnsDec(Out+4, Sec , 2);
|
||||
{ Format_UnsDec(Out , (uint32_t)Hour, 2);
|
||||
Format_UnsDec(Out+2, (uint32_t)Min , 2);
|
||||
Format_UnsDec(Out+4, (uint32_t)Sec , 2);
|
||||
return 6; }
|
||||
|
||||
int WriteIGC(char *Out) const // write IGC B-record
|
||||
|
|
112
main/ognconv.cpp
112
main/ognconv.cpp
|
@ -4,7 +4,21 @@
|
|||
#include "format.h"
|
||||
#include "ognconv.h"
|
||||
|
||||
// #pragma GCC optimize("O2") // XXTEA does not run at default -0s optimization - reason not understood
|
||||
// ==============================================================================================
|
||||
// Coordinate scales:
|
||||
// - uBlox GPS and FLARM: LSB = 1e-7 deg
|
||||
// - OGN-Tracker: LSB = 0.0001/60 deg
|
||||
// - FANET/ADS-L pseudo-cordic: LSB =
|
||||
// - True cordic: 2^32 = 360 deg
|
||||
|
||||
int32_t Coord_FNTtoOGN(int32_t Coord) { return ((int64_t)Coord*27000219 +(1<<28))>>29; } // [FANET cordic] => [0.0001/60 deg]
|
||||
int32_t Coord_OGNtoFNT(int32_t Coord) { return ((int64_t)Coord*83399317 +(1<<21))>>22; } // [0.0001/60 deg] => [FANET cordic]
|
||||
|
||||
int32_t Coord_FNTtoUBX(int32_t Coord) { return ((int64_t)Coord*900007296+(1<<29))>>30; } // [FANET cordic ] => [1e-7 deg]
|
||||
int32_t Coord_UBXtoFNT(int32_t Coord) { return ((int64_t)Coord*5003959 +(1<<21))>>22; } // [1e-7 deg] => [FANET cordic]
|
||||
|
||||
int32_t Coord_CRDtoOGN(int32_t Coord) { return ((int64_t)Coord*421875 +(1<<22))>>23; } // [32-bit cordic] => [0.0001/60 deg]
|
||||
int32_t Coord_OGNtoCRD(int32_t Coord) { return ((int64_t)Coord*83399993 +(1<<21))>>22; } // [0.0001/60 deg] => [32-bit cordic]
|
||||
|
||||
// ==============================================================================================
|
||||
|
||||
|
@ -13,6 +27,64 @@ int32_t MetersToFeet(int32_t Altitude) { return (Altitude*3360+512)>>10; } // [m
|
|||
|
||||
// ==============================================================================================
|
||||
|
||||
uint8_t AcftType_OGNtoADSB(uint8_t AcftType)
|
||||
// no-inf0, glider, tow, heli, parachute, drop-plane, hang-glider, para-glider, powered, jet, UFO, balloon, Zeppelin, UAV, ground vehicle, fixed object
|
||||
{ const uint8_t AcftCat[16] = { 0x00, 0xB1, 0xA1, 0xA7, 0xB3, 0xA1, 0xB4, 0xB4, 0xA1, 0xA2, 0x00, 0xB2, 0xB2, 0xB6, 0xC3, 0xC4 };
|
||||
return AcftCat[AcftType]; }
|
||||
|
||||
uint8_t AcftType_FNTtoADSB(uint8_t AcftType)
|
||||
// no-info, para-glider, hang-glider, balloon, glider, powered, heli, UAV
|
||||
{ const uint8_t AcftCat[8] = { 0, 0xB4, 0xB4, 0xB2, 0xB1, 0xA1, 0xA7, 0xB6 } ;
|
||||
return AcftCat[AcftType]; }
|
||||
|
||||
uint8_t AcftType_ADSBtoOGN(uint8_t AcftCat)
|
||||
{ // if(AcftCat&0x38) return 0;
|
||||
uint8_t Upp = AcftCat>>4;
|
||||
uint8_t Low = AcftCat&7;
|
||||
if(Upp==0xA)
|
||||
{ if(Low==1) return 8;
|
||||
if(Low==7) return 3;
|
||||
return 9; }
|
||||
if(Upp=0xB)
|
||||
{ const uint8_t Map[8] = { 0, 0xB, 1, 4, 7, 0, 0xD, 0 };
|
||||
return Map[Low]; }
|
||||
if(Upp==0xC)
|
||||
{ if(Low>=4) return 0xF;
|
||||
if(Low==3) return 0xE;
|
||||
return 0; }
|
||||
return 0; }
|
||||
|
||||
uint8_t AcftType_OGNtoGDL(uint8_t AcftType)
|
||||
// no-info, glider, tow, heli, parachute, drop-plane, hang-glider, para-glider, powered, jet, UFO, balloon, Zeppelin, UAV, ground vehicle, static-object
|
||||
{ const uint8_t AcftCat[16] = { 0, 9, 1, 7, 11, 1, 12, 12, 1, 2, 0, 10, 10, 14, 18, 19 } ;
|
||||
return AcftCat[AcftType]; }
|
||||
|
||||
uint8_t AcftType_OGNtoADSL(uint8_t AcftType) // OGN to ADS-L aircraft-type
|
||||
{ const uint8_t Map[16] = { 0, 4, 1, 3, // unknown, glider, tow-plane, helicopter
|
||||
8, 1, 7, 7, // sky-diver, drop plane, hang-glider, para-glider
|
||||
1, 2, 0, 5, // motor airplane, jet, UFO, balloon
|
||||
5,11, 0, 0 } ; // airship, UAV, ground vehicle, static object
|
||||
return Map[AcftType]; }
|
||||
|
||||
uint8_t AcftType_ADSLtoOGN(uint8_t AcftCat) // ADS-L to OGN aircraft-type
|
||||
{ const uint8_t Map[32] = { 0, 8, 9, 3, 1,12, 2, 7,
|
||||
4,13, 3,13,13,13, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0 } ;
|
||||
return Map[AcftCat]; }
|
||||
|
||||
uint8_t AcftType_FNTtoOGN(uint8_t AcftType)
|
||||
// no-info, para-glider, hang-glider, balloon, glider, powered, heli, UAV
|
||||
{ const uint8_t OGNtype[8] = { 0, 7, 6, 0xB, 1, 8, 3, 0xD } ;
|
||||
return OGNtype[AcftType]; }
|
||||
|
||||
uint8_t AcftType_FNTtoADSL(uint8_t AcftType)
|
||||
// no-info, para-glider, hang-glider, balloon, glider, powered, heli, UAV
|
||||
{ const uint8_t AcftCat[8] = { 0, 12, 12, 10, 9, 1, 7, 14 } ;
|
||||
return AcftCat[AcftType]; }
|
||||
|
||||
// ==============================================================================================
|
||||
|
||||
uint16_t EncodeUR2V8(uint16_t Value) // Encode unsigned 12bit (0..3832) as 10bit
|
||||
{ if(Value<0x100) { }
|
||||
else if(Value<0x300) Value = 0x100 | ((Value-0x100)>>1);
|
||||
|
@ -161,7 +233,8 @@ void TEA_Encrypt (uint32_t* Data, const uint32_t *Key, int Loops)
|
|||
{ sum += delta;
|
||||
v0 += ((v1<<4) + k0) ^ (v1 + sum) ^ ((v1>>5) + k1);
|
||||
v1 += ((v0<<4) + k2) ^ (v0 + sum) ^ ((v0>>5) + k3); } // end cycle
|
||||
Data[0]=v0; Data[1]=v1; }
|
||||
Data[0]=v0; Data[1]=v1;
|
||||
}
|
||||
|
||||
void TEA_Decrypt (uint32_t* Data, const uint32_t *Key, int Loops)
|
||||
{ uint32_t v0=Data[0], v1=Data[1]; // set up
|
||||
|
@ -171,7 +244,8 @@ void TEA_Decrypt (uint32_t* Data, const uint32_t *Key, int Loops)
|
|||
{ v1 -= ((v0<<4) + k2) ^ (v0 + sum) ^ ((v0>>5) + k3);
|
||||
v0 -= ((v1<<4) + k0) ^ (v1 + sum) ^ ((v1>>5) + k1);
|
||||
sum -= delta; } // end cycle
|
||||
Data[0]=v0; Data[1]=v1; }
|
||||
Data[0]=v0; Data[1]=v1;
|
||||
}
|
||||
|
||||
void TEA_Encrypt_Key0 (uint32_t* Data, int Loops)
|
||||
{ uint32_t v0=Data[0], v1=Data[1]; // set up
|
||||
|
@ -180,7 +254,8 @@ void TEA_Encrypt_Key0 (uint32_t* Data, int Loops)
|
|||
{ sum += delta;
|
||||
v0 += (v1<<4) ^ (v1 + sum) ^ (v1>>5);
|
||||
v1 += (v0<<4) ^ (v0 + sum) ^ (v0>>5); } // end cycle
|
||||
Data[0]=v0; Data[1]=v1; }
|
||||
Data[0]=v0; Data[1]=v1;
|
||||
}
|
||||
|
||||
void TEA_Decrypt_Key0 (uint32_t* Data, int Loops)
|
||||
{ uint32_t v0=Data[0], v1=Data[1]; // set up
|
||||
|
@ -189,22 +264,23 @@ void TEA_Decrypt_Key0 (uint32_t* Data, int Loops)
|
|||
{ v1 -= (v0<<4) ^ (v0 + sum) ^ (v0>>5);
|
||||
v0 -= (v1<<4) ^ (v1 + sum) ^ (v1>>5);
|
||||
sum -= delta; } // end cycle
|
||||
Data[0]=v0; Data[1]=v1; }
|
||||
Data[0]=v0; Data[1]=v1;
|
||||
}
|
||||
|
||||
// ==============================================================================================
|
||||
// XXTEA encryption/decryption
|
||||
|
||||
static uint32_t XXTEA_MX(uint32_t E, uint32_t Y, uint32_t Z, uint32_t P, uint32_t Sum, const uint32_t Key[4])
|
||||
{ return (((Z>>5) ^ (Y<<2)) + ((Y>>3) ^ (Z<<4))) ^ ((Sum^Y) + (Key[(P&3)^E] ^ Z)); }
|
||||
static uint32_t XXTEA_MX(uint8_t E, uint32_t Y, uint32_t Z, uint8_t P, uint32_t Sum, const uint32_t Key[4])
|
||||
{ return ((((Z>>5) ^ (Y<<2)) + ((Y>>3) ^ (Z<<4))) ^ ((Sum^Y) + (Key[(P&3)^E] ^ Z))); }
|
||||
|
||||
void XXTEA_Encrypt(uint32_t *Data, uint32_t Words, const uint32_t Key[4], uint32_t Loops)
|
||||
void XXTEA_Encrypt(uint32_t *Data, uint8_t Words, const uint32_t Key[4], uint8_t Loops)
|
||||
{ const uint32_t Delta = 0x9e3779b9;
|
||||
uint32_t Sum = 0;
|
||||
uint32_t Z = Data[Words-1]; uint32_t Y;
|
||||
for( ; Loops; Loops--)
|
||||
{ Sum += Delta;
|
||||
uint32_t E = (Sum>>2)&3;
|
||||
for (uint32_t P=0; P<(Words-1); P++)
|
||||
uint8_t E = (Sum>>2)&3;
|
||||
for (uint8_t P=0; P<(Words-1); P++)
|
||||
{ Y = Data[P+1];
|
||||
Z = Data[P] += XXTEA_MX(E, Y, Z, P, Sum, Key); }
|
||||
Y = Data[0];
|
||||
|
@ -212,13 +288,13 @@ void XXTEA_Encrypt(uint32_t *Data, uint32_t Words, const uint32_t Key[4], uint32
|
|||
}
|
||||
}
|
||||
|
||||
void XXTEA_Decrypt(uint32_t *Data, uint32_t Words, const uint32_t Key[4], uint32_t Loops)
|
||||
void XXTEA_Decrypt(uint32_t *Data, uint8_t Words, const uint32_t Key[4], uint8_t Loops)
|
||||
{ const uint32_t Delta = 0x9e3779b9;
|
||||
uint32_t Sum = Loops*Delta;
|
||||
uint32_t Y = Data[0]; uint32_t Z;
|
||||
for( ; Loops; Loops--)
|
||||
{ uint32_t E = (Sum>>2)&3;
|
||||
for (uint32_t P=Words-1; P; P--)
|
||||
{ uint8_t E = (Sum>>2)&3;
|
||||
for (uint8_t P=Words-1; P; P--)
|
||||
{ Z = Data[P-1];
|
||||
Y = Data[P] -= XXTEA_MX(E, Y, Z, P, Sum, Key); }
|
||||
Z = Data[Words-1];
|
||||
|
@ -228,27 +304,27 @@ void XXTEA_Decrypt(uint32_t *Data, uint32_t Words, const uint32_t Key[4], uint32
|
|||
}
|
||||
|
||||
static uint32_t XXTEA_MX_KEY0(uint32_t Y, uint32_t Z, uint32_t Sum)
|
||||
{ return (((Z>>5) ^ (Y<<2)) + ((Y>>3) ^ (Z<<4))) ^ ((Sum^Y) + Z); }
|
||||
{ return ((((Z>>5) ^ (Y<<2)) + ((Y>>3) ^ (Z<<4))) ^ ((Sum^Y) + Z)); }
|
||||
|
||||
void XXTEA_Encrypt_Key0(uint32_t *Data, uint32_t Words, uint32_t Loops)
|
||||
void XXTEA_Encrypt_Key0(uint32_t *Data, uint8_t Words, uint8_t Loops)
|
||||
{ const uint32_t Delta = 0x9e3779b9;
|
||||
uint32_t Sum = 0;
|
||||
uint32_t Z = Data[Words-1]; uint32_t Y;
|
||||
for( ; Loops; Loops--)
|
||||
{ Sum += Delta;
|
||||
for (uint32_t P=0; P<(Words-1); P++)
|
||||
for (uint8_t P=0; P<(Words-1); P++)
|
||||
{ Y = Data[P+1];
|
||||
Z = Data[P] += XXTEA_MX_KEY0(Y, Z, Sum); }
|
||||
Y = Data[0];
|
||||
Z = Data[Words-1] += XXTEA_MX_KEY0(Y, Z, Sum); }
|
||||
}
|
||||
|
||||
void XXTEA_Decrypt_Key0(uint32_t *Data, uint32_t Words, uint32_t Loops)
|
||||
void XXTEA_Decrypt_Key0(uint32_t *Data, uint8_t Words, uint8_t Loops)
|
||||
{ const uint32_t Delta = 0x9e3779b9;
|
||||
uint32_t Sum = Loops*Delta;
|
||||
uint32_t Y = Data[0]; uint32_t Z;
|
||||
for( ; Loops; Loops--)
|
||||
{ for (uint32_t P=Words-1; P; P--)
|
||||
{ for (uint8_t P=Words-1; P; P--)
|
||||
{ Z = Data[P-1];
|
||||
Y = Data[P] -= XXTEA_MX_KEY0(Y, Z, Sum); }
|
||||
Z = Data[Words-1];
|
||||
|
|
|
@ -3,9 +3,27 @@
|
|||
|
||||
#include <stdint.h>
|
||||
|
||||
int32_t Coord_FNTtoOGN(int32_t Coord);
|
||||
int32_t Coord_OGNtoFNT(int32_t Coord);
|
||||
|
||||
int32_t Coord_FNTtoUBX(int32_t Coord);
|
||||
int32_t Coord_UBXtoFNT(int32_t Coord);
|
||||
|
||||
int32_t Coord_CRDtoOGN(int32_t Coord);
|
||||
int32_t Coord_OGNtoCRD(int32_t Coord);
|
||||
|
||||
int32_t FeetToMeters(int32_t Altitude); //
|
||||
int32_t MetersToFeet(int32_t Altitude); //
|
||||
|
||||
uint8_t AcftType_OGNtoADSB(uint8_t AcftType);
|
||||
uint8_t AcftType_FNTtoADSB(uint8_t AcftType);
|
||||
uint8_t AcftType_ADSBtoOGN(uint8_t AcftCat);
|
||||
uint8_t AcftType_OGNtoGDL(uint8_t AcftType);
|
||||
uint8_t AcftType_OGNtoADSL(uint8_t AcftType);
|
||||
uint8_t AcftType_ADSLtoOGN(uint8_t AcftCat);
|
||||
uint8_t AcftType_FNTtoOGN(uint8_t AcftType);
|
||||
uint8_t AcftType_FNTtoADSL(uint8_t AcftType);
|
||||
|
||||
uint16_t EncodeUR2V8(uint16_t Value); // Encode unsigned 12bit (0..3832) as 10bit
|
||||
uint16_t DecodeUR2V8(uint16_t Value); // Decode 10bit 0..0x3FF
|
||||
|
||||
|
@ -73,11 +91,11 @@ void TEA_Decrypt (uint32_t* Data, const uint32_t *Key, int Loops);
|
|||
void TEA_Encrypt_Key0 (uint32_t* Data, int Loops);
|
||||
void TEA_Decrypt_Key0 (uint32_t* Data, int Loops);
|
||||
|
||||
void XXTEA_Encrypt(uint32_t *Data, uint32_t Words, const uint32_t Key[4], uint32_t Loops);
|
||||
void XXTEA_Decrypt(uint32_t *Data, uint32_t Words, const uint32_t Key[4], uint32_t Loops);
|
||||
void XXTEA_Encrypt(uint32_t *Data, uint8_t Words, const uint32_t Key[4], uint8_t Loops);
|
||||
void XXTEA_Decrypt(uint32_t *Data, uint8_t Words, const uint32_t Key[4], uint8_t Loops);
|
||||
|
||||
void XXTEA_Encrypt_Key0(uint32_t *Data, uint32_t Words, uint32_t Loops);
|
||||
void XXTEA_Decrypt_Key0(uint32_t *Data, uint32_t Words, uint32_t Loops);
|
||||
void XXTEA_Encrypt_Key0(uint32_t *Data, uint8_t Words, uint8_t Loops);
|
||||
void XXTEA_Decrypt_Key0(uint32_t *Data, uint8_t Words, uint8_t Loops);
|
||||
|
||||
void XorShift32(uint32_t &Seed); // simple random number generator
|
||||
void XorShift64(uint64_t &Seed);
|
||||
|
|
|
@ -270,7 +270,7 @@ uint16_t StratuxPort;
|
|||
|
||||
FreqPlan = DEFAULT_FreqPlan; // [0..5]
|
||||
PPSdelay = DEFAULT_PPSdelay; // [ms]
|
||||
PageMask = 0xFF;
|
||||
PageMask = 0xFFFF;
|
||||
InitialPage = 0;
|
||||
AltitudeUnit = 0; // meter
|
||||
SpeedUnit = 0; // km/h
|
||||
|
|
|
@ -35,7 +35,7 @@ GDL90_REPORT GDL_REPORT;
|
|||
|
||||
#ifdef WITH_LOOKOUT // traffic awareness and warnings
|
||||
#include "lookout.h"
|
||||
LookOut Look;
|
||||
LookOut<32> Look;
|
||||
#ifdef WITH_SOUND
|
||||
const char *Dir[16] = { "N", "NNE", "NE", "NEE", "E", "SEE", "SE", "SSE", "S", "SSW", "SW", "SWW", "W", "NWW", "NW", "NNW" };
|
||||
const char *RelDir[8] = { "A", "AR", "R", "BR", "B", "BL", "L", "AL" };
|
||||
|
@ -648,9 +648,9 @@ void vTaskPROC(void* pvParameters)
|
|||
ADSL_Packet *Packet = ADSL_TxFIFO.getWrite();
|
||||
Packet->Init();
|
||||
Packet->setAddress (Parameters.Address);
|
||||
Packet->setAddrType(Parameters.AddrType);
|
||||
Packet->setAddrTypeOGN(Parameters.AddrType);
|
||||
Packet->setRelay(0);
|
||||
Packet->setAcftType(Parameters.AcftType);
|
||||
Packet->setAcftTypeOGN(Parameters.AcftType);
|
||||
Position->Encode(*Packet);
|
||||
Packet->Scramble(); // this call hangs when -Os is used to compile
|
||||
Packet->setCRC();
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
#ifdef WITH_LOOKOUT // traffic awareness and warnings
|
||||
#include "lookout.h"
|
||||
extern LookOut Look;
|
||||
extern LookOut<32> Look;
|
||||
#endif
|
||||
|
||||
extern uint32_t BatteryVoltage; // [1/256 mV] averaged
|
||||
|
|
|
@ -11,10 +11,11 @@
|
|||
|
||||
#include "gdl90.h"
|
||||
#include "ogn.h"
|
||||
#include "adsl.h"
|
||||
|
||||
// =======================================================================================================
|
||||
|
||||
class Acft_RelPos // 3-D relative position with speed and turn rate
|
||||
class Acft_RelPos // 3-D relative position with speed and turn rate
|
||||
{ public:
|
||||
int16_t T; // [0.5sec]
|
||||
int16_t X,Y,Z; // [0.5m]
|
||||
|
@ -39,8 +40,13 @@ class Acft_RelPos // 3-D relative position with speed and turn rate
|
|||
|
||||
public:
|
||||
void Print(void) const
|
||||
{ printf("%+7.1fs: [%+7.1f,%+7.1f,%+7.1f]m %5.1fm/s %05.1fdeg %+5.1fm/s %+5.1fdeg/s [%3.1fm]",
|
||||
0.5*T, 0.5*X, 0.5*Y, 0.5*Z, 0.5*Speed, (360.0/0x10000)*Heading, 0.5*Climb, (360.0/0x10000)*Turn, 0.5*Error);
|
||||
{ printf("%+7.1fs: [%+7.1f,%+7.1f,%+7.1f]m %5.1fm/s %05.1fdeg",
|
||||
0.5*T, 0.5*X, 0.5*Y, 0.5*Z, 0.5*Speed, (360.0/0x10000)*Heading);
|
||||
if(hasClimb) printf(" %+5.1fm/s", 0.5*Climb);
|
||||
else printf(" ---.-m/s");
|
||||
if(hasTurn) printf(" %+5.1fdeg/s", (360.0/0x10000)*Turn);
|
||||
else printf(" ---.-deg/s");
|
||||
printf(" [%3.1fm]", 0.5*Error);
|
||||
// printf(" [%+6.2f,%+6.2f]m/s^2", 0.0625*Ax, 0.0625*Ay);
|
||||
// if(R) printf(" R:%+8.1fm [%+7.1f, %+7.1f]", 0.5*R, 0.5*Ox, 0.5*Oy);
|
||||
printf("\n"); }
|
||||
|
@ -189,17 +195,19 @@ class Acft_RelPos // 3-D relative position with speed and turn rate
|
|||
|
||||
void StepFwd(int16_t Time) // [0.5s] predict the position into the future
|
||||
{ int16_t Vx, Vy;
|
||||
int16_t Time1 = Time>>1;
|
||||
int16_t Time2 = Time-Time1;
|
||||
int16_t Time1 = Time>>1; // [s]
|
||||
int16_t Time2 = Time-Time1; // [0.5s]
|
||||
getSpeedVector(Vx, Vy);
|
||||
int16_t dX = Time1*Vx; int16_t dY = Time1*Vy;
|
||||
Heading += (Time*Turn)>>1;
|
||||
int16_t dX = Time1*Vx;
|
||||
int16_t dY = Time1*Vy;
|
||||
if(hasTurn) Heading += (Time*Turn)>>1;
|
||||
calcDir(); // calcAccel();
|
||||
getSpeedVector(Vx, Vy);
|
||||
dX += Time2*Vx; dY += Time2*Vy;
|
||||
dX += Time2*Vx;
|
||||
dY += Time2*Vy;
|
||||
X += dX/2;
|
||||
Y += dY/2;
|
||||
Z += (Time*Climb)>>1;
|
||||
if(hasClimb) Z += (Time*Climb)>>1;
|
||||
T += Time; }
|
||||
|
||||
void StepFwdSecs(int16_t Secs) // [sec] predict the position Secs into the future
|
||||
|
@ -208,44 +216,44 @@ class Acft_RelPos // 3-D relative position with speed and turn rate
|
|||
int16_t Secs2=Secs-Secs1;
|
||||
getSpeedVector(Vx, Vy);
|
||||
X += Secs1*Vx; Y += Secs1*Vy;
|
||||
Heading += Secs*Turn;
|
||||
if(hasTurn) Heading += Secs*Turn;
|
||||
calcDir(); // calcAccel();
|
||||
getSpeedVector(Vx, Vy);
|
||||
X += Secs2*Vx; Y += Secs2*Vy;
|
||||
Z += Secs*Climb;
|
||||
if(hasClimb) Z += Secs*Climb;
|
||||
T += 2*Secs; }
|
||||
|
||||
void StepFwd4secs(void) // predict the position four second into the future
|
||||
{ int16_t Vx, Vy;
|
||||
getSpeedVector(Vx, Vy);
|
||||
X += 2*Vx; Y += 2*Vy;
|
||||
Heading += 4*Turn;
|
||||
if(hasTurn) Heading += 4*Turn;
|
||||
calcDir(); // calcAccel();
|
||||
getSpeedVector(Vx, Vy);
|
||||
X += 2*Vx; Y += 2*Vy;
|
||||
Z += 4*Climb;
|
||||
if(hasClimb) Z += 4*Climb;
|
||||
T += 8; }
|
||||
|
||||
void StepFwd2secs(void) // predict the position two seconds into the future
|
||||
{ int16_t Vx, Vy;
|
||||
getSpeedVector(Vx, Vy); // get hor. speed vector from speed and dir. vector
|
||||
X += Vx; Y += Vy; // incr. the hor. coordinates by half the speed
|
||||
Heading += 2*Turn; // increment the heading by the turning rate
|
||||
if(hasTurn) Heading += 2*Turn; // increment the heading by the turning rate
|
||||
calcDir(); // calcAccel(); // recalc. direction and acceleration
|
||||
getSpeedVector(Vx, Vy); // recalc. the speed vector
|
||||
X += Vx; Y += Vy; // incr. horizotal coord. by half the speed vector
|
||||
Z += 2*Climb; // increment the rel. altitude by the climb rate
|
||||
if(hasClimb) Z += 2*Climb; // increment the rel. altitude by the climb rate
|
||||
T += 4; } // increment time by 2sec
|
||||
|
||||
void StepFwd1sec(void) // predict the position one second into the future
|
||||
{ int16_t Vx, Vy;
|
||||
getSpeedVector(Vx, Vy);
|
||||
X += Vx/2; Y += Vy/2;
|
||||
Heading += Turn;
|
||||
if(hasTurn) Heading += Turn;
|
||||
calcDir(); // calcAccel();
|
||||
getSpeedVector(Vx, Vy);
|
||||
X += Vx/2; Y += Vy/2;
|
||||
Z += Climb;
|
||||
if(hasClimb) Z += Climb;
|
||||
T += 2; }
|
||||
|
||||
template <class OGNx_Packet> // zero the position, read differentials from an OGN packet
|
||||
|
@ -258,8 +266,42 @@ class Acft_RelPos // 3-D relative position with speed and turn rate
|
|||
calcDir();
|
||||
Error = (2*Packet.DecodeDOP()+22)/5; }
|
||||
|
||||
int32_t Read(ADSL_Packet &Packet, uint32_t RxTime, uint32_t RefTime,
|
||||
int32_t RefLat, int32_t RefLon, int32_t RefAlt, uint16_t LatCos=3000, int16_t GeoidSepar=40, int32_t MaxDist=15000)
|
||||
{ Flags=0;
|
||||
uint16_t msTime=0;
|
||||
uint32_t PosTime=Packet.getTime(msTime, RxTime);
|
||||
if(PosTime) T = PosTime-RefTime; // [sec]
|
||||
else T = RxTime-RefTime;
|
||||
T<<=1; if(msTime>=500) T++; // [0.5sec]
|
||||
int32_t LatDist, LonDist; // [1/60000deg]
|
||||
if(Packet.calcDistanceVectorOGN(LatDist, LonDist, RefLat, RefLon, LatCos, MaxDist)<0) return -1; // [m, m, , , , m]
|
||||
X = LatDist*2; // [m] => [0.5m] relative along latitude
|
||||
Y = LonDist*2; // [m] => [0.5m] relative along longitude
|
||||
Z = Packet.getAlt()-RefAlt-GeoidSepar; Z*=2;
|
||||
Speed = Packet.getSpeed()/2;
|
||||
Heading = Packet.getTrack()<<7;
|
||||
if(Packet.hasClimb())
|
||||
{ Climb=Packet.getClimb()/4;
|
||||
hasClimb=1; }
|
||||
calcDir();
|
||||
Error=Packet.getHorAccur();
|
||||
return 0; }
|
||||
|
||||
void Write(ADSL_Packet &Packet, uint8_t RefTime, int32_t RefLat, int32_t RefLon, int32_t RefAlt, uint16_t LatCos=3000, int16_t GeoidSepar=40)
|
||||
{ int16_t Time=RefTime+(T>>1);
|
||||
Packet.TimeStamp = ((Time%15)<<2) | ((T&1)<<1);
|
||||
Packet.setDistanceVectorOGN(X>>1, Y>>1, RefLat, RefLon, LatCos);
|
||||
Packet.setAlt(RefAlt+(Z>>1)+GeoidSepar); //
|
||||
Packet.setSpeed(Speed*2); // [0.5m/s] => [0.25m/s]
|
||||
Packet.setTrack(Heading>>7); // [cordic]
|
||||
Packet.setClimb(Climb*4); // [0.5m/s] => [0.125m/s]
|
||||
Packet.setHorAccur(Error);
|
||||
Packet.setVerAccur(Error+Error/2); }
|
||||
|
||||
template <class OGNx_Packet> // read position from an OGN packet, use provided reference
|
||||
int32_t Read(OGNx_Packet &Packet, uint32_t RxTime, uint32_t RefTime, int32_t RefLat, int32_t RefLon, int32_t RefAlt, uint16_t LatCos=3000, int32_t MaxDist=10000)
|
||||
int32_t Read(OGNx_Packet &Packet, uint32_t RxTime, uint32_t RefTime,
|
||||
int32_t RefLat, int32_t RefLon, int32_t RefAlt, uint16_t LatCos=3000, int32_t MaxDist=15000)
|
||||
{ Flags=0;
|
||||
uint32_t PosTime=Packet.getTime(RxTime);
|
||||
if(PosTime) T = PosTime-RefTime; // [sec]
|
||||
|
@ -267,8 +309,8 @@ class Acft_RelPos // 3-D relative position with speed and turn rate
|
|||
T<<=1; // [0.5sec]
|
||||
int32_t LatDist, LonDist; // [1/60000deg]
|
||||
if(Packet.calcDistanceVector(LatDist, LonDist, RefLat, RefLon, LatCos, MaxDist)<0) return -1; // [m, m, , , , m]
|
||||
X = LatDist<<1; // [m] => [0.5m] relative along latitude
|
||||
Y = LonDist<<1; // [m] => [0.5m] relative along longitude
|
||||
X = LatDist*2; // [m] => [0.5m] relative along latitude
|
||||
Y = LonDist*2; // [m] => [0.5m] relative along longitude
|
||||
Z = (Packet.DecodeAltitude()-RefAlt)<<1; // [m] => [0.5m] relative vertical
|
||||
if(Packet.hasBaro()) { dStdAlt=Packet.getBaroAltDiff()<<1; hasStdAlt=1; }
|
||||
Speed = (Packet.DecodeSpeed()+2)/5; // [0.1m/s] => [0.5m/s]
|
||||
|
@ -277,7 +319,7 @@ class Acft_RelPos // 3-D relative position with speed and turn rate
|
|||
{ Climb = Packet.DecodeClimbRate()/5; // [0.1m/s] => [0.5m/s]
|
||||
hasClimb = 1; }
|
||||
if(Packet.hasTurnRate())
|
||||
{ Turn = ((int32_t)Packet.DecodeTurnRate()*1165+32)>>6; // [0.1deg/s] => [360/0x10000deg/s]
|
||||
{ Turn = ((int32_t)Packet.DecodeTurnRate()*1165+32)>>6; // [0.1deg/s] => [360/0x10000deg/s]
|
||||
hasTurn = 1; }
|
||||
calcDir();
|
||||
Error = (2*Packet.DecodeDOP()+22)/5;
|
||||
|
|
|
@ -3,11 +3,11 @@
|
|||
#include "wifi.h"
|
||||
#include "format.h"
|
||||
|
||||
wifi_config_t WIFI_Config; // WIFI config: ESSID, etc.
|
||||
wifi_config_t WIFI_Config; // WIFI config: ESSID, etc.
|
||||
tcpip_adapter_ip_info_t WIFI_IP = { 0, 0, 0 }; // WIFI local IP address, mask and gateway
|
||||
WIFI_State_t WIFI_State;
|
||||
WIFI_State_t WIFI_State = { 0 };
|
||||
|
||||
bool WIFI_isConnected(void) { return WIFI_IP.ip.addr!=0; } // return "connected" status when IP from DHCP is there
|
||||
bool WIFI_isConnected(void) { return WIFI_IP.ip.addr!=0; } // return "connected" status when IP from DHCP is there
|
||||
bool WIFI_isAP(void) { return WIFI_Config.ap.ssid_len!=0; } // return if AP mode enabled
|
||||
|
||||
static esp_err_t WIFI_event_handler(void *ctx, system_event_t *event)
|
||||
|
@ -49,10 +49,9 @@ static esp_err_t WIFI_event_handler(void *ctx, system_event_t *event)
|
|||
return ESP_OK; }
|
||||
|
||||
esp_err_t WIFI_Init(void)
|
||||
{
|
||||
|
||||
//Fab501 test to change IP to 192.168.1.1 for comptability with SkyDemon
|
||||
|
||||
{
|
||||
/* this produces as error during startup
|
||||
// Fab501 test to change IP to 192.168.1.1 for comptability with SkyDemon
|
||||
esp_netif_init();
|
||||
ESP_ERROR_CHECK(esp_event_loop_create_default());
|
||||
esp_netif_t* wifiAP = esp_netif_create_default_wifi_ap();
|
||||
|
@ -63,8 +62,8 @@ esp_err_t WIFI_Init(void)
|
|||
esp_netif_dhcps_stop(wifiAP);
|
||||
esp_netif_set_ip_info(wifiAP, &ipInfo);
|
||||
esp_netif_dhcps_start(wifiAP);
|
||||
|
||||
// end of Fab501 changes
|
||||
// end of Fab501 changes
|
||||
*/
|
||||
esp_err_t Err;
|
||||
tcpip_adapter_init();
|
||||
Err = esp_event_loop_init(WIFI_event_handler, NULL); if(Err!=ESP_OK) return Err;
|
||||
|
@ -90,11 +89,6 @@ esp_err_t WIFI_StartAP(const char *SSID, const char *Pass, int MaxConnections)
|
|||
else WIFI_Config.ap.password[0]=0;
|
||||
WIFI_Config.ap.max_connection = MaxConnections;
|
||||
WIFI_Config.ap.authmode = (Pass && Pass[0]) ? WIFI_AUTH_WPA_WPA2_PSK:WIFI_AUTH_OPEN;
|
||||
// tcpip_adapter_ip_info_t IPinfo; // attempt to change the IP range to 192.168.1.1 but does not work
|
||||
// IP4_ADDR(&IPinfo.ip, 192,168,1,1);
|
||||
// IP4_ADDR(&IPinfo.gw, 192,168,1,1);
|
||||
// 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 ?
|
||||
#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
|
||||
|
@ -102,6 +96,13 @@ esp_err_t WIFI_StartAP(const char *SSID, const char *Pass, int MaxConnections)
|
|||
Err = esp_wifi_set_config(WIFI_IF_AP, &WIFI_Config); if(Err!=ESP_OK) return Err; // v4.3
|
||||
#endif
|
||||
Err = esp_wifi_start();
|
||||
// IP4_ADDR(&IPinfo.ip, 192,168,1,1);
|
||||
// IP4_ADDR(&IPinfo.gw, 192,168,1,1);
|
||||
// IP4_ADDR(&IPinfo.netmask, 255,255,255,0);
|
||||
// esp_netif_dhcps_stop(TCPIP_ADAPTER_IF_AP);
|
||||
// esp_netif_set_ip_info(TCPIP_ADAPTER_IF_AP, &WIFI_IP);
|
||||
// esp_netif_dhcps_start(TCPIP_ADAPTER_IF_AP);
|
||||
tcpip_adapter_get_ip_info(TCPIP_ADAPTER_IF_AP, &WIFI_IP);
|
||||
return Err; }
|
||||
|
||||
esp_err_t WIFI_Stop(void)
|
||||
|
@ -185,7 +186,7 @@ void IP_Print(void (*Output)(char), uint32_t IP)
|
|||
IP>>=8; }
|
||||
}
|
||||
|
||||
uint8_t AP_Print(char *Out, wifi_ap_record_t *AP) // print numbers for a found Wi-Fi Access Point
|
||||
uint8_t AP_Print(char *Out, wifi_ap_record_t *AP) // print numbers for a discovered Wi-Fi Access Point
|
||||
{ uint8_t Len=0;
|
||||
for(uint8_t Idx=0; Idx<6; Idx++)
|
||||
{ Len+=Format_Hex(Out+Len, AP->bssid[Idx]); Out[Len++]=':'; }
|
||||
|
|
14
main/wifi.h
14
main/wifi.h
|
@ -11,8 +11,6 @@
|
|||
|
||||
#include "esp_event_loop.h"
|
||||
|
||||
extern tcpip_adapter_ip_info_t WIFI_IP; // WIFI local IP address, mask and gateway
|
||||
|
||||
typedef union
|
||||
{ uint32_t Flags;
|
||||
struct
|
||||
|
@ -22,10 +20,14 @@ typedef union
|
|||
} ;
|
||||
} WIFI_State_t;
|
||||
|
||||
extern WIFI_State_t WIFI_State;
|
||||
extern WIFI_State_t WIFI_State;
|
||||
|
||||
extern wifi_config_t WIFI_Config;
|
||||
extern tcpip_adapter_ip_info_t WIFI_IP; // WIFI local IP address, mask and gateway
|
||||
|
||||
bool WIFI_isConnected(void);
|
||||
bool WIFI_isAP(void);
|
||||
|
||||
esp_err_t WIFI_Init(void);
|
||||
esp_err_t WIFI_setPowerSave(bool ON);
|
||||
esp_err_t WIFI_Start(void);
|
||||
|
@ -35,11 +37,15 @@ esp_err_t WIFI_setTxPower(int8_t TxPwr=40);
|
|||
esp_err_t WIFI_Connect(wifi_ap_record_t *AP, const char *Pass, int8_t MinSig=(-90));
|
||||
esp_err_t WIFI_Connect(const char *SSID, const char *Pass, int8_t MinSig=(-90));
|
||||
esp_err_t WIFI_Disconnect(void);
|
||||
|
||||
uint32_t WIFI_getLocalIP(void);
|
||||
|
||||
esp_err_t WIFI_ActiveScan(wifi_ap_record_t *AP, uint16_t &APs);
|
||||
esp_err_t WIFI_PassiveScan(wifi_ap_record_t *AP, uint16_t &APs);
|
||||
|
||||
uint8_t AP_Print(char *Out, wifi_ap_record_t *AP);
|
||||
|
||||
uint8_t IP_Print(char *Out, uint32_t IP);
|
||||
void IP_Print(void (*Output)(char), uint32_t IP);
|
||||
void IP_Print(void (*Output)(char), uint32_t IP);
|
||||
|
||||
#endif // __WIFI_H__
|
||||
|
|
|
@ -8,4 +8,4 @@ factory,app,factory,0x10000,1800K,
|
|||
# SPIFFS in Flash
|
||||
# intlog,data,spiffs,,0x1F0000,
|
||||
# FAT in Flash
|
||||
intlog,data,fat,,0x1F0000,
|
||||
intlog,data,fat,,0x210000,
|
||||
|
|
|
294
sdkconfig
294
sdkconfig
|
@ -2,7 +2,6 @@
|
|||
# Automatically generated file. DO NOT EDIT.
|
||||
# Espressif IoT Development Framework (ESP-IDF) Project Configuration
|
||||
#
|
||||
CONFIG_IDF_TARGET_ARCH_XTENSA=y
|
||||
CONFIG_IDF_TARGET="esp32"
|
||||
CONFIG_IDF_TARGET_ESP32=y
|
||||
CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000
|
||||
|
@ -32,14 +31,12 @@ CONFIG_APP_BUILD_USE_FLASH_SECTIONS=y
|
|||
CONFIG_APP_COMPILE_TIME_DATE=y
|
||||
# CONFIG_APP_EXCLUDE_PROJECT_VER_VAR is not set
|
||||
# CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR is not set
|
||||
# CONFIG_APP_PROJECT_VER_FROM_CONFIG is not set
|
||||
CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16
|
||||
# end of Application manager
|
||||
|
||||
#
|
||||
# Bootloader config
|
||||
#
|
||||
CONFIG_BOOTLOADER_OFFSET_IN_FLASH=0x1000
|
||||
CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y
|
||||
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_DEBUG is not set
|
||||
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_PERF is not set
|
||||
|
@ -60,8 +57,6 @@ CONFIG_BOOTLOADER_WDT_ENABLE=y
|
|||
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
||||
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
||||
# CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP is not set
|
||||
# CONFIG_BOOTLOADER_SKIP_VALIDATE_ON_POWER_ON is not set
|
||||
# CONFIG_BOOTLOADER_SKIP_VALIDATE_ALWAYS is not set
|
||||
CONFIG_BOOTLOADER_RESERVE_RTC_SIZE=0
|
||||
# CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC is not set
|
||||
# end of Bootloader config
|
||||
|
@ -86,7 +81,6 @@ CONFIG_ESPTOOLPY_BAUD_921600B=y
|
|||
CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200
|
||||
CONFIG_ESPTOOLPY_BAUD=921600
|
||||
CONFIG_ESPTOOLPY_COMPRESSED=y
|
||||
# CONFIG_ESPTOOLPY_NO_STUB is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_QIO is not set
|
||||
# CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set
|
||||
CONFIG_ESPTOOLPY_FLASHMODE_DIO=y
|
||||
|
@ -110,7 +104,6 @@ CONFIG_ESPTOOLPY_BEFORE="default_reset"
|
|||
CONFIG_ESPTOOLPY_AFTER_RESET=y
|
||||
# CONFIG_ESPTOOLPY_AFTER_NORESET is not set
|
||||
CONFIG_ESPTOOLPY_AFTER="hard_reset"
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_CONSOLE is not set
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_9600B is not set
|
||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_57600B is not set
|
||||
CONFIG_ESPTOOLPY_MONITOR_BAUD_115200B=y
|
||||
|
@ -153,7 +146,6 @@ CONFIG_COMPILER_STACK_CHECK_MODE_NORM=y
|
|||
CONFIG_COMPILER_STACK_CHECK=y
|
||||
# CONFIG_COMPILER_WARN_WRITE_STRINGS is not set
|
||||
CONFIG_COMPILER_DISABLE_GCC8_WARNINGS=y
|
||||
# CONFIG_COMPILER_DUMP_RTL_FILES is not set
|
||||
# end of Compiler options
|
||||
|
||||
#
|
||||
|
@ -168,20 +160,13 @@ CONFIG_APPTRACE_DEST_NONE=y
|
|||
CONFIG_APPTRACE_LOCK_ENABLE=y
|
||||
# end of Application Level Tracing
|
||||
|
||||
#
|
||||
# ESP-ASIO
|
||||
#
|
||||
# CONFIG_ASIO_SSL_SUPPORT is not set
|
||||
# end of ESP-ASIO
|
||||
|
||||
#
|
||||
# Bluetooth
|
||||
#
|
||||
CONFIG_BT_ENABLED=y
|
||||
CONFIG_BT_CTRL_ESP32=y
|
||||
|
||||
#
|
||||
# Bluetooth controller(ESP32 Dual Mode Bluetooth)
|
||||
# Bluetooth controller
|
||||
#
|
||||
# CONFIG_BTDM_CTRL_MODE_BLE_ONLY is not set
|
||||
# CONFIG_BTDM_CTRL_MODE_BR_EDR_ONLY is not set
|
||||
|
@ -192,16 +177,7 @@ CONFIG_BTDM_CTRL_BR_EDR_MAX_SYNC_CONN=0
|
|||
# CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_HCI is not set
|
||||
CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_PCM=y
|
||||
CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_EFF=1
|
||||
CONFIG_BTDM_CTRL_PCM_ROLE_EDGE_CONFIG=y
|
||||
CONFIG_BTDM_CTRL_PCM_ROLE_MASTER=y
|
||||
# CONFIG_BTDM_CTRL_PCM_ROLE_SLAVE is not set
|
||||
CONFIG_BTDM_CTRL_PCM_POLAR_FALLING_EDGE=y
|
||||
# CONFIG_BTDM_CTRL_PCM_POLAR_RISING_EDGE is not set
|
||||
CONFIG_BTDM_CTRL_PCM_ROLE_EFF=0
|
||||
CONFIG_BTDM_CTRL_PCM_POLAR_EFF=0
|
||||
# CONFIG_BTDM_CTRL_AUTO_LATENCY is not set
|
||||
CONFIG_BTDM_CTRL_LEGACY_AUTH_VENDOR_EVT=y
|
||||
CONFIG_BTDM_CTRL_LEGACY_AUTH_VENDOR_EVT_EFF=y
|
||||
CONFIG_BTDM_CTRL_BLE_MAX_CONN_EFF=2
|
||||
CONFIG_BTDM_CTRL_BR_EDR_MAX_ACL_CONN_EFF=2
|
||||
CONFIG_BTDM_CTRL_BR_EDR_MAX_SYNC_CONN_EFF=0
|
||||
|
@ -212,10 +188,10 @@ CONFIG_BTDM_CTRL_HCI_MODE_VHCI=y
|
|||
#
|
||||
# MODEM SLEEP Options
|
||||
#
|
||||
CONFIG_BTDM_CTRL_MODEM_SLEEP=y
|
||||
CONFIG_BTDM_CTRL_MODEM_SLEEP_MODE_ORIG=y
|
||||
# CONFIG_BTDM_CTRL_MODEM_SLEEP_MODE_EVED is not set
|
||||
CONFIG_BTDM_CTRL_LPCLK_SEL_MAIN_XTAL=y
|
||||
CONFIG_BTDM_MODEM_SLEEP=y
|
||||
CONFIG_BTDM_MODEM_SLEEP_MODE_ORIG=y
|
||||
# CONFIG_BTDM_MODEM_SLEEP_MODE_EVED is not set
|
||||
CONFIG_BTDM_LPCLK_SEL_MAIN_XTAL=y
|
||||
# end of MODEM SLEEP Options
|
||||
|
||||
CONFIG_BTDM_BLE_DEFAULT_SCA_250PPM=y
|
||||
|
@ -233,37 +209,7 @@ CONFIG_BTDM_BLE_ADV_REPORT_FLOW_CTRL_NUM=100
|
|||
CONFIG_BTDM_BLE_ADV_REPORT_DISCARD_THRSHOLD=20
|
||||
CONFIG_BTDM_COEX_BT_OPTIONS=y
|
||||
CONFIG_BTDM_COEX_BLE_ADV_HIGH_PRIORITY=y
|
||||
# end of Bluetooth controller(ESP32 Dual Mode Bluetooth)
|
||||
|
||||
CONFIG_BT_CTRL_MODE_EFF=1
|
||||
CONFIG_BT_CTRL_BLE_MAX_ACT=10
|
||||
CONFIG_BT_CTRL_BLE_MAX_ACT_EFF=10
|
||||
CONFIG_BT_CTRL_BLE_STATIC_ACL_TX_BUF_NB=0
|
||||
CONFIG_BT_CTRL_PINNED_TO_CORE=0
|
||||
CONFIG_BT_CTRL_HCI_TL=1
|
||||
CONFIG_BT_CTRL_ADV_DUP_FILT_MAX=30
|
||||
CONFIG_BT_CTRL_HW_CCA_EFF=0
|
||||
CONFIG_BT_CTRL_DFT_TX_POWER_LEVEL_EFF=0
|
||||
CONFIG_BT_CTRL_BLE_ADV_REPORT_FLOW_CTRL_SUPP=y
|
||||
CONFIG_BT_CTRL_BLE_ADV_REPORT_FLOW_CTRL_NUM=100
|
||||
CONFIG_BT_CTRL_BLE_ADV_REPORT_DISCARD_THRSHOLD=20
|
||||
CONFIG_BT_CTRL_BLE_SCAN_DUPL=y
|
||||
CONFIG_BT_CTRL_SCAN_DUPL_TYPE=0
|
||||
CONFIG_BT_CTRL_SCAN_DUPL_CACHE_SIZE=100
|
||||
|
||||
#
|
||||
# MODEM SLEEP Options
|
||||
#
|
||||
# end of MODEM SLEEP Options
|
||||
|
||||
CONFIG_BT_CTRL_SLEEP_MODE_EFF=0
|
||||
CONFIG_BT_CTRL_SLEEP_CLOCK_EFF=0
|
||||
CONFIG_BT_CTRL_HCI_TL_EFF=1
|
||||
|
||||
#
|
||||
# MODEM SLEEP Options
|
||||
#
|
||||
# end of MODEM SLEEP Options
|
||||
# end of Bluetooth controller
|
||||
|
||||
CONFIG_BT_BLUEDROID_ENABLED=y
|
||||
# CONFIG_BT_NIMBLE_ENABLED is not set
|
||||
|
@ -280,19 +226,15 @@ CONFIG_BT_CLASSIC_ENABLED=y
|
|||
# CONFIG_BT_A2DP_ENABLE is not set
|
||||
CONFIG_BT_SPP_ENABLED=y
|
||||
# CONFIG_BT_HFP_ENABLE is not set
|
||||
# CONFIG_BT_HID_HOST_ENABLED is not set
|
||||
CONFIG_BT_SSP_ENABLED=y
|
||||
CONFIG_BT_BLE_ENABLED=y
|
||||
CONFIG_BT_GATTS_ENABLE=y
|
||||
# CONFIG_BT_GATTS_PPCP_CHAR_GAP is not set
|
||||
# CONFIG_BT_BLE_BLUFI_ENABLE is not set
|
||||
CONFIG_BT_GATT_SR_PROFILES=8
|
||||
# CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_MANUAL is not set
|
||||
CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_AUTO=y
|
||||
CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_MODE=0
|
||||
CONFIG_BT_GATTC_ENABLE=y
|
||||
# CONFIG_BT_GATTC_CACHE_NVS_FLASH is not set
|
||||
CONFIG_BT_GATTC_CONNECT_RETRY_COUNT=3
|
||||
CONFIG_BT_BLE_SMP_ENABLE=y
|
||||
# CONFIG_BT_SMP_SLAVE_CON_PARAMS_UPD_ENABLE is not set
|
||||
# CONFIG_BT_STACK_NO_LOG is not set
|
||||
|
@ -471,14 +413,12 @@ CONFIG_BT_LOG_BLUFI_TRACE_LEVEL=2
|
|||
# end of BT DEBUG LOG LEVEL
|
||||
|
||||
CONFIG_BT_ACL_CONNECTIONS=4
|
||||
CONFIG_BT_MULTI_CONNECTION_ENBALE=y
|
||||
# CONFIG_BT_ALLOCATION_FROM_SPIRAM_FIRST is not set
|
||||
# CONFIG_BT_BLE_DYNAMIC_ENV_MEMORY is not set
|
||||
# CONFIG_BT_BLE_HOST_QUEUE_CONG_CHECK is not set
|
||||
CONFIG_BT_SMP_ENABLE=y
|
||||
# CONFIG_BT_BLE_ACT_SCAN_REP_ADV_SCAN is not set
|
||||
CONFIG_BT_BLE_ESTAB_LINK_CONN_TOUT=30
|
||||
# CONFIG_BT_BLE_RPA_SUPPORTED is not set
|
||||
CONFIG_BT_RESERVE_DRAM=0xdb5c
|
||||
# end of Bluedroid Options
|
||||
# end of Bluetooth
|
||||
|
@ -514,16 +454,6 @@ CONFIG_SPI_MASTER_ISR_IN_IRAM=y
|
|||
CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
||||
# end of SPI configuration
|
||||
|
||||
#
|
||||
# TWAI configuration
|
||||
#
|
||||
# CONFIG_TWAI_ISR_IN_IRAM is not set
|
||||
# CONFIG_TWAI_ERRATA_FIX_BUS_OFF_REC is not set
|
||||
# CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST is not set
|
||||
# CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID is not set
|
||||
# CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT is not set
|
||||
# end of TWAI configuration
|
||||
|
||||
#
|
||||
# UART configuration
|
||||
#
|
||||
|
@ -535,12 +465,6 @@ CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
|||
#
|
||||
# CONFIG_RTCIO_SUPPORT_RTC_GPIO_DESC is not set
|
||||
# end of RTCIO configuration
|
||||
|
||||
#
|
||||
# GPIO Configuration
|
||||
#
|
||||
# CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set
|
||||
# end of GPIO Configuration
|
||||
# end of Driver configurations
|
||||
|
||||
#
|
||||
|
@ -558,10 +482,8 @@ CONFIG_EFUSE_MAX_BLK_LEN=192
|
|||
# ESP-TLS
|
||||
#
|
||||
CONFIG_ESP_TLS_USING_MBEDTLS=y
|
||||
# CONFIG_ESP_TLS_USE_SECURE_ELEMENT is not set
|
||||
# CONFIG_ESP_TLS_SERVER is not set
|
||||
# CONFIG_ESP_TLS_PSK_VERIFICATION is not set
|
||||
# CONFIG_ESP_TLS_INSECURE is not set
|
||||
# end of ESP-TLS
|
||||
|
||||
#
|
||||
|
@ -584,6 +506,10 @@ CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR=y
|
|||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4
|
||||
# CONFIG_ESP32_ULP_COPROC_ENABLED is not set
|
||||
CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=0
|
||||
# CONFIG_ESP32_PANIC_PRINT_HALT is not set
|
||||
CONFIG_ESP32_PANIC_PRINT_REBOOT=y
|
||||
# CONFIG_ESP32_PANIC_SILENT_REBOOT is not set
|
||||
# CONFIG_ESP32_PANIC_GDBSTUB is not set
|
||||
CONFIG_ESP32_DEBUG_OCDAWARE=y
|
||||
CONFIG_ESP32_BROWNOUT_DET=y
|
||||
CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_0=y
|
||||
|
@ -615,12 +541,13 @@ CONFIG_ESP32_XTAL_FREQ=0
|
|||
# CONFIG_ESP32_RTCDATA_IN_FAST_MEM is not set
|
||||
# CONFIG_ESP32_USE_FIXED_STATIC_RAM_SIZE is not set
|
||||
CONFIG_ESP32_DPORT_DIS_INTERRUPT_LVL=5
|
||||
# CONFIG_ESP32_IRAM_AS_8BIT_ACCESSIBLE_MEMORY is not set
|
||||
# end of ESP32-specific
|
||||
|
||||
CONFIG_ESP32C3_DEBUG_OCDAWARE=y
|
||||
CONFIG_ESP32C3_BROWNOUT_DET=y
|
||||
CONFIG_ESP32C3_LIGHTSLEEP_GPIO_RESET_WORKAROUND=y
|
||||
#
|
||||
# Power Management
|
||||
#
|
||||
# CONFIG_PM_ENABLE is not set
|
||||
# end of Power Management
|
||||
|
||||
#
|
||||
# Cache config
|
||||
|
@ -632,16 +559,6 @@ CONFIG_ESP32S2_ULP_COPROC_RESERVE_MEM=0
|
|||
CONFIG_ESP32S2_DEBUG_OCDAWARE=y
|
||||
CONFIG_ESP32S2_BROWNOUT_DET=y
|
||||
|
||||
#
|
||||
# Cache config
|
||||
#
|
||||
# end of Cache config
|
||||
|
||||
CONFIG_ESP32S3_TRACEMEM_RESERVE_DRAM=0x0
|
||||
CONFIG_ESP32S3_ULP_COPROC_RESERVE_MEM=0
|
||||
CONFIG_ESP32S3_DEBUG_OCDAWARE=y
|
||||
CONFIG_ESP32S3_BROWNOUT_DET=y
|
||||
|
||||
#
|
||||
# ADC-Calibration
|
||||
#
|
||||
|
@ -653,17 +570,17 @@ CONFIG_ADC_CAL_LUT_ENABLE=y
|
|||
#
|
||||
# Common ESP-related
|
||||
#
|
||||
# CONFIG_ESP_TIMER_PROFILING is not set
|
||||
CONFIG_ESP_ERR_TO_NAME_LOOKUP=y
|
||||
CONFIG_ESP_SYSTEM_EVENT_QUEUE_SIZE=32
|
||||
CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=2048
|
||||
CONFIG_ESP_MAIN_TASK_STACK_SIZE=3000
|
||||
CONFIG_ESP_IPC_TASK_STACK_SIZE=1024
|
||||
CONFIG_ESP_TIMER_TASK_STACK_SIZE=2048
|
||||
CONFIG_ESP_MINIMAL_SHARED_STACK_SIZE=2048
|
||||
CONFIG_ESP_CONSOLE_UART_DEFAULT=y
|
||||
# CONFIG_ESP_CONSOLE_UART_CUSTOM is not set
|
||||
# CONFIG_ESP_CONSOLE_NONE is not set
|
||||
CONFIG_ESP_CONSOLE_UART=y
|
||||
CONFIG_ESP_CONSOLE_MULTIPLE_UART=y
|
||||
# CONFIG_ESP_CONSOLE_UART_NONE is not set
|
||||
CONFIG_ESP_CONSOLE_UART_NUM=0
|
||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
||||
CONFIG_ESP_INT_WDT=y
|
||||
|
@ -673,10 +590,6 @@ CONFIG_ESP_TASK_WDT=y
|
|||
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
||||
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||
# CONFIG_ESP_PANIC_HANDLER_IRAM is not set
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_STA=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y
|
||||
CONFIG_ESP_MAC_ADDR_UNIVERSE_ETH=y
|
||||
# end of Common ESP-related
|
||||
|
||||
#
|
||||
|
@ -724,7 +637,6 @@ CONFIG_HTTPD_MAX_URI_LEN=512
|
|||
CONFIG_HTTPD_ERR_RESP_NO_DELAY=y
|
||||
CONFIG_HTTPD_PURGE_BUF_LEN=32
|
||||
# CONFIG_HTTPD_LOG_PURGE_DATA is not set
|
||||
# CONFIG_HTTPD_WS_SUPPORT is not set
|
||||
# end of HTTP Server
|
||||
|
||||
#
|
||||
|
@ -748,41 +660,6 @@ CONFIG_ESP_NETIF_TCPIP_LWIP=y
|
|||
CONFIG_ESP_NETIF_TCPIP_ADAPTER_COMPATIBLE_LAYER=y
|
||||
# end of ESP NETIF Adapter
|
||||
|
||||
#
|
||||
# Power Management
|
||||
#
|
||||
# CONFIG_PM_ENABLE is not set
|
||||
# end of Power Management
|
||||
|
||||
#
|
||||
# ESP System Settings
|
||||
#
|
||||
# CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set
|
||||
CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y
|
||||
# CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set
|
||||
# CONFIG_ESP_SYSTEM_PANIC_GDBSTUB is not set
|
||||
CONFIG_ESP_SYSTEM_SINGLE_CORE_MODE=y
|
||||
CONFIG_ESP_SYSTEM_RTC_FAST_MEM_AS_HEAP_DEPCHECK=y
|
||||
CONFIG_ESP_SYSTEM_ALLOW_RTC_FAST_MEM_AS_HEAP=y
|
||||
CONFIG_ESP_SYSTEM_PD_FLASH=y
|
||||
|
||||
#
|
||||
# Memory protection
|
||||
#
|
||||
# end of Memory protection
|
||||
# end of ESP System Settings
|
||||
|
||||
#
|
||||
# High resolution timer (esp_timer)
|
||||
#
|
||||
# CONFIG_ESP_TIMER_PROFILING is not set
|
||||
CONFIG_ESP_TIME_FUNCS_USE_RTC_TIMER=y
|
||||
CONFIG_ESP_TIME_FUNCS_USE_ESP_TIMER=y
|
||||
CONFIG_ESP_TIMER_TASK_STACK_SIZE=2048
|
||||
# CONFIG_ESP_TIMER_IMPL_FRC2 is not set
|
||||
CONFIG_ESP_TIMER_IMPL_TG0_LAC=y
|
||||
# end of High resolution timer (esp_timer)
|
||||
|
||||
#
|
||||
# Wi-Fi
|
||||
#
|
||||
|
@ -805,8 +682,6 @@ CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32
|
|||
CONFIG_ESP32_WIFI_IRAM_OPT=y
|
||||
CONFIG_ESP32_WIFI_RX_IRAM_OPT=y
|
||||
CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y
|
||||
# CONFIG_ESP_WIFI_SLP_IRAM_OPT is not set
|
||||
# CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set
|
||||
# end of Wi-Fi
|
||||
|
||||
#
|
||||
|
@ -821,9 +696,9 @@ CONFIG_ESP32_PHY_MAX_TX_POWER=20
|
|||
#
|
||||
# Core dump
|
||||
#
|
||||
# CONFIG_ESP_COREDUMP_ENABLE_TO_FLASH is not set
|
||||
# CONFIG_ESP_COREDUMP_ENABLE_TO_UART is not set
|
||||
CONFIG_ESP_COREDUMP_ENABLE_TO_NONE=y
|
||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set
|
||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set
|
||||
CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y
|
||||
# end of Core dump
|
||||
|
||||
#
|
||||
|
@ -858,26 +733,21 @@ CONFIG_FATFS_LFN_NONE=y
|
|||
CONFIG_FATFS_FS_LOCK=0
|
||||
CONFIG_FATFS_TIMEOUT_MS=10000
|
||||
CONFIG_FATFS_PER_FILE_CACHE=y
|
||||
# CONFIG_FATFS_USE_FASTSEEK is not set
|
||||
# end of FAT Filesystem support
|
||||
|
||||
#
|
||||
# Modbus configuration
|
||||
#
|
||||
CONFIG_FMB_COMM_MODE_TCP_EN=y
|
||||
CONFIG_FMB_TCP_PORT_DEFAULT=502
|
||||
CONFIG_FMB_TCP_PORT_MAX_CONN=5
|
||||
CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20
|
||||
CONFIG_FMB_COMM_MODE_RTU_EN=y
|
||||
CONFIG_FMB_COMM_MODE_ASCII_EN=y
|
||||
CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150
|
||||
CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200
|
||||
CONFIG_FMB_QUEUE_LENGTH=20
|
||||
CONFIG_FMB_PORT_TASK_STACK_SIZE=4096
|
||||
CONFIG_FMB_SERIAL_TASK_STACK_SIZE=2048
|
||||
CONFIG_FMB_SERIAL_BUF_SIZE=256
|
||||
CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8
|
||||
CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000
|
||||
CONFIG_FMB_PORT_TASK_PRIO=10
|
||||
CONFIG_FMB_SERIAL_TASK_PRIO=10
|
||||
# CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT is not set
|
||||
CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20
|
||||
CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20
|
||||
|
@ -896,7 +766,6 @@ CONFIG_FREERTOS_UNICORE=y
|
|||
CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF
|
||||
CONFIG_FREERTOS_CORETIMER_0=y
|
||||
# CONFIG_FREERTOS_CORETIMER_1 is not set
|
||||
CONFIG_FREERTOS_OPTIMIZED_SCHEDULER=y
|
||||
CONFIG_FREERTOS_HZ=1000
|
||||
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
||||
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set
|
||||
|
@ -922,11 +791,10 @@ CONFIG_FREERTOS_USE_TRACE_FACILITY=y
|
|||
CONFIG_FREERTOS_USE_STATS_FORMATTING_FUNCTIONS=y
|
||||
# CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID is not set
|
||||
# CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS is not set
|
||||
# CONFIG_FREERTOS_DEBUG_INTERNALS is not set
|
||||
CONFIG_FREERTOS_CHECK_MUTEX_GIVEN_BY_OWNER=y
|
||||
# CONFIG_FREERTOS_CHECK_PORT_CRITICAL_COMPLIANCE is not set
|
||||
# CONFIG_FREERTOS_PLACE_FUNCTIONS_INTO_FLASH is not set
|
||||
CONFIG_FREERTOS_DEBUG_OCDAWARE=y
|
||||
# CONFIG_FREERTOS_FPU_IN_ISR is not set
|
||||
# end of FreeRTOS
|
||||
|
||||
#
|
||||
|
@ -938,7 +806,6 @@ CONFIG_HEAP_POISONING_DISABLED=y
|
|||
CONFIG_HEAP_TRACING_OFF=y
|
||||
# CONFIG_HEAP_TRACING_STANDALONE is not set
|
||||
# CONFIG_HEAP_TRACING_TOHOST is not set
|
||||
# CONFIG_HEAP_ABORT_WHEN_ALLOCATION_FAILS is not set
|
||||
# end of Heap memory debugging
|
||||
|
||||
#
|
||||
|
@ -983,11 +850,8 @@ CONFIG_LWIP_MAX_SOCKETS=8
|
|||
# CONFIG_LWIP_SO_REUSE is not set
|
||||
# CONFIG_LWIP_SO_RCVBUF is not set
|
||||
# CONFIG_LWIP_NETBUF_RECVINFO is not set
|
||||
CONFIG_LWIP_IP4_FRAG=y
|
||||
CONFIG_LWIP_IP6_FRAG=y
|
||||
# CONFIG_LWIP_IP4_REASSEMBLY is not set
|
||||
# CONFIG_LWIP_IP6_REASSEMBLY is not set
|
||||
# CONFIG_LWIP_IP_FORWARD 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
|
||||
CONFIG_LWIP_ESP_GRATUITOUS_ARP=y
|
||||
|
@ -1004,7 +868,6 @@ CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8
|
|||
# end of DHCP server
|
||||
|
||||
# CONFIG_LWIP_AUTOIP is not set
|
||||
CONFIG_LWIP_IPV6=y
|
||||
# CONFIG_LWIP_IPV6_AUTOCONFIG is not set
|
||||
CONFIG_LWIP_NETIF_LOOPBACK=y
|
||||
CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8
|
||||
|
@ -1014,7 +877,6 @@ CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8
|
|||
#
|
||||
CONFIG_LWIP_MAX_ACTIVE_TCP=16
|
||||
CONFIG_LWIP_MAX_LISTENING_TCP=16
|
||||
CONFIG_LWIP_TCP_HIGH_SPEED_RETRANSMISSION=y
|
||||
CONFIG_LWIP_TCP_MAXRTX=12
|
||||
CONFIG_LWIP_TCP_SYNMAXRTX=6
|
||||
CONFIG_LWIP_TCP_MSS=1436
|
||||
|
@ -1029,7 +891,6 @@ CONFIG_LWIP_TCP_QUEUE_OOSEQ=y
|
|||
CONFIG_LWIP_TCP_OVERSIZE_MSS=y
|
||||
# CONFIG_LWIP_TCP_OVERSIZE_QUARTER_MSS is not set
|
||||
# CONFIG_LWIP_TCP_OVERSIZE_DISABLE is not set
|
||||
CONFIG_LWIP_TCP_RTO_TIME=1500
|
||||
# end of TCP
|
||||
|
||||
#
|
||||
|
@ -1039,22 +900,11 @@ CONFIG_LWIP_MAX_UDP_PCBS=16
|
|||
CONFIG_LWIP_UDP_RECVMBOX_SIZE=6
|
||||
# end of UDP
|
||||
|
||||
#
|
||||
# Checksums
|
||||
#
|
||||
# CONFIG_LWIP_CHECKSUM_CHECK_IP is not set
|
||||
# CONFIG_LWIP_CHECKSUM_CHECK_UDP is not set
|
||||
CONFIG_LWIP_CHECKSUM_CHECK_ICMP=y
|
||||
# end of Checksums
|
||||
|
||||
CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=2048
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set
|
||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
||||
# CONFIG_LWIP_PPP_SUPPORT is not set
|
||||
CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3
|
||||
CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5
|
||||
# CONFIG_LWIP_SLIP_SUPPORT is not set
|
||||
|
||||
#
|
||||
# ICMP
|
||||
|
@ -1075,24 +925,6 @@ CONFIG_LWIP_MAX_RAW_PCBS=16
|
|||
CONFIG_LWIP_DHCP_MAX_NTP_SERVERS=1
|
||||
CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000
|
||||
# end of SNTP
|
||||
|
||||
CONFIG_LWIP_ESP_LWIP_ASSERT=y
|
||||
|
||||
#
|
||||
# Hooks
|
||||
#
|
||||
# CONFIG_LWIP_HOOK_TCP_ISN_NONE is not set
|
||||
CONFIG_LWIP_HOOK_TCP_ISN_DEFAULT=y
|
||||
# CONFIG_LWIP_HOOK_TCP_ISN_CUSTOM is not set
|
||||
CONFIG_LWIP_HOOK_IP6_ROUTE_NONE=y
|
||||
# CONFIG_LWIP_HOOK_IP6_ROUTE_DEFAULT is not set
|
||||
# CONFIG_LWIP_HOOK_IP6_ROUTE_CUSTOM is not set
|
||||
CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_NONE=y
|
||||
# CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_DEFAULT is not set
|
||||
# CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_CUSTOM is not set
|
||||
# end of Hooks
|
||||
|
||||
# CONFIG_LWIP_DEBUG is not set
|
||||
# end of LWIP
|
||||
|
||||
#
|
||||
|
@ -1103,31 +935,14 @@ CONFIG_MBEDTLS_INTERNAL_MEM_ALLOC=y
|
|||
# CONFIG_MBEDTLS_CUSTOM_MEM_ALLOC is not set
|
||||
CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=16384
|
||||
# CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN is not set
|
||||
# CONFIG_MBEDTLS_DYNAMIC_BUFFER is not set
|
||||
# CONFIG_MBEDTLS_DEBUG is not set
|
||||
|
||||
#
|
||||
# Certificate Bundle
|
||||
#
|
||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE=y
|
||||
CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y
|
||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set
|
||||
# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set
|
||||
# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set
|
||||
# end of Certificate Bundle
|
||||
|
||||
# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set
|
||||
# CONFIG_MBEDTLS_CMAC_C is not set
|
||||
CONFIG_MBEDTLS_HARDWARE_AES=y
|
||||
CONFIG_MBEDTLS_HARDWARE_MPI=y
|
||||
# CONFIG_MBEDTLS_HARDWARE_SHA is not set
|
||||
CONFIG_MBEDTLS_ROM_MD5=y
|
||||
# CONFIG_MBEDTLS_ATCA_HW_ECDSA_SIGN is not set
|
||||
# CONFIG_MBEDTLS_ATCA_HW_ECDSA_VERIFY is not set
|
||||
CONFIG_MBEDTLS_HAVE_TIME=y
|
||||
# CONFIG_MBEDTLS_HAVE_TIME_DATE is not set
|
||||
CONFIG_MBEDTLS_ECDSA_DETERMINISTIC=y
|
||||
CONFIG_MBEDTLS_SHA512_C=y
|
||||
CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y
|
||||
# CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set
|
||||
# CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set
|
||||
|
@ -1192,7 +1007,6 @@ CONFIG_MBEDTLS_X509_CSR_PARSE_C=y
|
|||
CONFIG_MBEDTLS_ECP_C=y
|
||||
CONFIG_MBEDTLS_ECDH_C=y
|
||||
CONFIG_MBEDTLS_ECDSA_C=y
|
||||
# CONFIG_MBEDTLS_ECJPAKE_C is not set
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP192R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y
|
||||
|
@ -1206,11 +1020,6 @@ CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y
|
|||
CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y
|
||||
CONFIG_MBEDTLS_ECP_NIST_OPTIM=y
|
||||
# CONFIG_MBEDTLS_POLY1305_C is not set
|
||||
# CONFIG_MBEDTLS_CHACHA20_C is not set
|
||||
# CONFIG_MBEDTLS_HKDF_C is not set
|
||||
# CONFIG_MBEDTLS_THREADING_C is not set
|
||||
# CONFIG_MBEDTLS_LARGE_KEY_SOFTWARE_MPI is not set
|
||||
# CONFIG_MBEDTLS_SECURITY_RISKS is not set
|
||||
# end of mbedTLS
|
||||
|
||||
|
@ -1219,12 +1028,10 @@ CONFIG_MBEDTLS_ECP_NIST_OPTIM=y
|
|||
#
|
||||
CONFIG_MDNS_MAX_SERVICES=10
|
||||
CONFIG_MDNS_TASK_PRIORITY=1
|
||||
CONFIG_MDNS_TASK_STACK_SIZE=4096
|
||||
# CONFIG_MDNS_TASK_AFFINITY_NO_AFFINITY is not set
|
||||
CONFIG_MDNS_TASK_AFFINITY_CPU0=y
|
||||
CONFIG_MDNS_TASK_AFFINITY=0x0
|
||||
CONFIG_MDNS_SERVICE_ADD_TIMEOUT_MS=2000
|
||||
# CONFIG_MDNS_STRICT_MODE is not set
|
||||
CONFIG_MDNS_TIMER_PERIOD_MS=100
|
||||
# end of mDNS
|
||||
|
||||
|
@ -1235,9 +1042,6 @@ CONFIG_MQTT_PROTOCOL_311=y
|
|||
CONFIG_MQTT_TRANSPORT_SSL=y
|
||||
CONFIG_MQTT_TRANSPORT_WEBSOCKET=y
|
||||
CONFIG_MQTT_TRANSPORT_WEBSOCKET_SECURE=y
|
||||
# CONFIG_MQTT_MSG_ID_INCREMENTAL is not set
|
||||
# CONFIG_MQTT_SKIP_PUBLISH_IF_DISCONNECTED is not set
|
||||
# CONFIG_MQTT_REPORT_DELETED_MESSAGES is not set
|
||||
# CONFIG_MQTT_USE_CUSTOM_CONFIG is not set
|
||||
# CONFIG_MQTT_TASK_CORE_SELECTION_ENABLED is not set
|
||||
# CONFIG_MQTT_CUSTOM_OUTBOX is not set
|
||||
|
@ -1264,7 +1068,6 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y
|
|||
# OpenSSL
|
||||
#
|
||||
# CONFIG_OPENSSL_DEBUG is not set
|
||||
CONFIG_OPENSSL_ERROR_STACK=y
|
||||
CONFIG_OPENSSL_ASSERT_DO_NOTHING=y
|
||||
# CONFIG_OPENSSL_ASSERT_EXIT is not set
|
||||
# end of OpenSSL
|
||||
|
@ -1289,25 +1092,17 @@ CONFIG_SPI_FLASH_DANGEROUS_WRITE_ABORTS=y
|
|||
# CONFIG_SPI_FLASH_DANGEROUS_WRITE_FAILS is not set
|
||||
# CONFIG_SPI_FLASH_DANGEROUS_WRITE_ALLOWED is not set
|
||||
# CONFIG_SPI_FLASH_USE_LEGACY_IMPL is not set
|
||||
# CONFIG_SPI_FLASH_SHARE_SPI1_BUS is not set
|
||||
# CONFIG_SPI_FLASH_BYPASS_BLOCK_ERASE is not set
|
||||
CONFIG_SPI_FLASH_YIELD_DURING_ERASE=y
|
||||
CONFIG_SPI_FLASH_ERASE_YIELD_DURATION_MS=20
|
||||
CONFIG_SPI_FLASH_ERASE_YIELD_TICKS=1
|
||||
CONFIG_SPI_FLASH_WRITE_CHUNK_SIZE=8192
|
||||
# CONFIG_SPI_FLASH_SIZE_OVERRIDE is not set
|
||||
# CONFIG_SPI_FLASH_CHECK_ERASE_TIMEOUT_DISABLED is not set
|
||||
|
||||
#
|
||||
# Auto-detect flash chips
|
||||
#
|
||||
CONFIG_SPI_FLASH_SUPPORT_ISSI_CHIP=y
|
||||
CONFIG_SPI_FLASH_SUPPORT_MXIC_CHIP=y
|
||||
CONFIG_SPI_FLASH_SUPPORT_GD_CHIP=y
|
||||
CONFIG_SPI_FLASH_SUPPORT_WINBOND_CHIP=y
|
||||
# end of Auto-detect flash chips
|
||||
|
||||
CONFIG_SPI_FLASH_ENABLE_ENCRYPTED_READ_WRITE=y
|
||||
# end of SPI Flash driver
|
||||
|
||||
#
|
||||
|
@ -1346,12 +1141,6 @@ CONFIG_SPIFFS_USE_MTIME=y
|
|||
# end of Debug Configuration
|
||||
# end of SPIFFS Configuration
|
||||
|
||||
#
|
||||
# TCP Transport
|
||||
#
|
||||
CONFIG_WS_BUFFER_SIZE=1024
|
||||
# end of TCP Transport
|
||||
|
||||
#
|
||||
# Unity unit testing library
|
||||
#
|
||||
|
@ -1366,17 +1155,14 @@ CONFIG_UNITY_ENABLE_IDF_TEST_RUNNER=y
|
|||
#
|
||||
# Virtual file system
|
||||
#
|
||||
CONFIG_VFS_SUPPORT_IO=y
|
||||
CONFIG_VFS_SUPPORT_DIR=y
|
||||
CONFIG_VFS_SUPPORT_SELECT=y
|
||||
CONFIG_VFS_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
||||
CONFIG_VFS_SUPPORT_TERMIOS=y
|
||||
|
||||
#
|
||||
# Host File System I/O (Semihosting)
|
||||
#
|
||||
CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||
CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||
CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||
# end of Host File System I/O (Semihosting)
|
||||
# end of Virtual file system
|
||||
|
||||
|
@ -1399,11 +1185,7 @@ CONFIG_WIFI_PROV_AUTOSTOP_TIMEOUT=30
|
|||
# Supplicant
|
||||
#
|
||||
CONFIG_WPA_MBEDTLS_CRYPTO=y
|
||||
# CONFIG_WPA_WAPI_PSK is not set
|
||||
# CONFIG_WPA_DEBUG_PRINT is not set
|
||||
# CONFIG_WPA_TESTING_OPTIONS is not set
|
||||
# CONFIG_WPA_WPS_WARS is not set
|
||||
# CONFIG_WPA_11KV_SUPPORT is not set
|
||||
# CONFIG_WPA_TLS_V12 is not set
|
||||
# end of Supplicant
|
||||
# end of Component config
|
||||
|
||||
|
@ -1690,10 +1472,10 @@ CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32
|
|||
CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2048
|
||||
CONFIG_MAIN_TASK_STACK_SIZE=3000
|
||||
CONFIG_IPC_TASK_STACK_SIZE=1024
|
||||
CONFIG_TIMER_TASK_STACK_SIZE=2048
|
||||
CONFIG_CONSOLE_UART_DEFAULT=y
|
||||
# CONFIG_CONSOLE_UART_CUSTOM is not set
|
||||
# CONFIG_ESP_CONSOLE_UART_NONE is not set
|
||||
CONFIG_CONSOLE_UART=y
|
||||
# CONFIG_CONSOLE_UART_NONE is not set
|
||||
CONFIG_CONSOLE_UART_NUM=0
|
||||
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
||||
CONFIG_INT_WDT=y
|
||||
|
@ -1705,20 +1487,11 @@ CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
|||
# CONFIG_EVENT_LOOP_PROFILING is not set
|
||||
CONFIG_POST_EVENTS_FROM_ISR=y
|
||||
CONFIG_POST_EVENTS_FROM_IRAM_ISR=y
|
||||
# CONFIG_ESP32S2_PANIC_PRINT_HALT is not set
|
||||
CONFIG_ESP32S2_PANIC_PRINT_REBOOT=y
|
||||
# CONFIG_ESP32S2_PANIC_SILENT_REBOOT is not set
|
||||
# CONFIG_ESP32S2_PANIC_GDBSTUB is not set
|
||||
CONFIG_ESP32S2_ALLOW_RTC_FAST_MEM_AS_HEAP=y
|
||||
CONFIG_TIMER_TASK_STACK_SIZE=2048
|
||||
CONFIG_SW_COEXIST_ENABLE=y
|
||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set
|
||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set
|
||||
CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y
|
||||
CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150
|
||||
CONFIG_MB_MASTER_DELAY_MS_CONVERT=200
|
||||
CONFIG_MB_QUEUE_LENGTH=20
|
||||
CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096
|
||||
CONFIG_MB_SERIAL_TASK_STACK_SIZE=2048
|
||||
CONFIG_MB_SERIAL_BUF_SIZE=256
|
||||
CONFIG_MB_SERIAL_TASK_PRIO=10
|
||||
# CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT is not set
|
||||
|
@ -1729,6 +1502,7 @@ 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=y
|
||||
# CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set
|
||||
CONFIG_TIMER_TASK_PRIORITY=1
|
||||
CONFIG_TIMER_TASK_STACK_DEPTH=2048
|
||||
|
@ -1766,6 +1540,4 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y
|
|||
# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED is not set
|
||||
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
||||
CONFIG_SUPPORT_TERMIOS=y
|
||||
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||
CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||
# End of deprecated options
|
||||
|
|
Ładowanie…
Reference in New Issue