kopia lustrzana https://github.com/pjalocha/esp32-ogn-tracker
Porównaj commity
7 Commity
7a3ea1a2e0
...
aac6866609
Autor | SHA1 | Data |
---|---|---|
Pawel Jalocha | aac6866609 | |
Pawel Jalocha | a44c5bc617 | |
Pawel Jalocha | 44cce4a19a | |
Pawel Jalocha | ff20127a6a | |
Pawel Jalocha | 670043d468 | |
Pawel Jalocha | 9bcccbc1ca | |
Pawel Jalocha | 060dcb077e |
|
@ -42,7 +42,7 @@ Start with:
|
||||||
|
|
||||||
```
|
```
|
||||||
cd
|
cd
|
||||||
git clone -b v4.1 --recursive https://github.com/espressif/esp-idf.git
|
git clone -b v4.3 --recursive https://github.com/espressif/esp-idf.git
|
||||||
cd esp-idf
|
cd esp-idf
|
||||||
./install.sh
|
./install.sh
|
||||||
```
|
```
|
||||||
|
|
|
@ -111,6 +111,7 @@ static void ReadParameters(void) // read parameters requested by the user in th
|
||||||
Parameters.ReadPOGNS(NMEA);
|
Parameters.ReadPOGNS(NMEA);
|
||||||
PrintParameters();
|
PrintParameters();
|
||||||
esp_err_t Err = Parameters.WriteToNVS(); // erase and write the parameters into the Flash
|
esp_err_t Err = Parameters.WriteToNVS(); // erase and write the parameters into the Flash
|
||||||
|
// Parameters.ReadFromNVS(); // for debug only
|
||||||
// if(Parameters.ReadFromNVS()!=ESP_OK) Parameters.setDefault();
|
// if(Parameters.ReadFromNVS()!=ESP_OK) Parameters.setDefault();
|
||||||
// Parameters.WriteToFlash(); // erase and write the parameters into the Flash
|
// Parameters.WriteToFlash(); // erase and write the parameters into the Flash
|
||||||
// if(Parameters.ReadFromFlash()<0) Parameters.setDefault(); // read the parameters back: if invalid, set defaults
|
// if(Parameters.ReadFromFlash()<0) Parameters.setDefault(); // read the parameters back: if invalid, set defaults
|
||||||
|
|
|
@ -76,6 +76,10 @@ void Format_Hex( void (*Output)(char), uint32_t Word )
|
||||||
{ Format_Hex(Output, (uint8_t)(Word>>24)); Format_Hex(Output, (uint8_t)(Word>>16));
|
{ Format_Hex(Output, (uint8_t)(Word>>24)); Format_Hex(Output, (uint8_t)(Word>>16));
|
||||||
Format_Hex(Output, (uint8_t)(Word>>8)); Format_Hex(Output, (uint8_t)Word); }
|
Format_Hex(Output, (uint8_t)(Word>>8)); Format_Hex(Output, (uint8_t)Word); }
|
||||||
|
|
||||||
|
void Format_Hex( void (*Output)(char), uint64_t Word )
|
||||||
|
{ Format_Hex(Output, (uint32_t)(Word>>32));
|
||||||
|
Format_Hex(Output, (uint32_t)(Word )); }
|
||||||
|
|
||||||
void Format_MAC( void (*Output)(char), uint8_t *MAC, uint8_t Len)
|
void Format_MAC( void (*Output)(char), uint8_t *MAC, uint8_t Len)
|
||||||
{ for(uint8_t Idx=0; Idx<Len; Idx++)
|
{ for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||||
{ if(Idx) (*Output)(':');
|
{ if(Idx) (*Output)(':');
|
||||||
|
@ -284,11 +288,16 @@ int16_t Read_Dec3(const char *Inp) // convert three digit decimal nu
|
||||||
int8_t Low=Read_Dec1(Inp[2]); if(Low<0) return -1;
|
int8_t Low=Read_Dec1(Inp[2]); if(Low<0) return -1;
|
||||||
return (int16_t)Low + (int16_t)10*(int16_t)Mid + (int16_t)100*(int16_t)High; }
|
return (int16_t)Low + (int16_t)10*(int16_t)Mid + (int16_t)100*(int16_t)High; }
|
||||||
|
|
||||||
int16_t Read_Dec4(const char *Inp) // convert three digit decimal number into an integer
|
int16_t Read_Dec4(const char *Inp) // convert four digit decimal number into an integer
|
||||||
{ int16_t High=Read_Dec2(Inp ); if(High<0) return -1;
|
{ int16_t High=Read_Dec2(Inp ); if(High<0) return -1;
|
||||||
int16_t Low =Read_Dec2(Inp+2); if(Low<0) return -1;
|
int16_t Low =Read_Dec2(Inp+2); if(Low<0) return -1;
|
||||||
return Low + (int16_t)100*(int16_t)High; }
|
return Low + (int16_t)100*(int16_t)High; }
|
||||||
|
|
||||||
|
int32_t Read_Dec5(const char *Inp) // convert four digit decimal number into an integer
|
||||||
|
{ int16_t High=Read_Dec2(Inp ); if(High<0) return -1;
|
||||||
|
int16_t Low =Read_Dec3(Inp+2); if(Low<0) return -1;
|
||||||
|
return (int32_t)Low + (int32_t)1000*(int32_t)High; }
|
||||||
|
|
||||||
// ------------------------------------------------------------------------------------------
|
// ------------------------------------------------------------------------------------------
|
||||||
|
|
||||||
int8_t Read_Coord(int32_t &Lat, const char *Inp)
|
int8_t Read_Coord(int32_t &Lat, const char *Inp)
|
||||||
|
|
|
@ -16,6 +16,7 @@ void Format_String( void (*Output)(char), const char *String, uint8_t MinLen,
|
||||||
void Format_Hex( void (*Output)(char), uint8_t Byte );
|
void Format_Hex( void (*Output)(char), uint8_t Byte );
|
||||||
void Format_Hex( void (*Output)(char), uint16_t Word );
|
void Format_Hex( void (*Output)(char), uint16_t Word );
|
||||||
void Format_Hex( void (*Output)(char), uint32_t Word );
|
void Format_Hex( void (*Output)(char), uint32_t Word );
|
||||||
|
void Format_Hex( void (*Output)(char), uint64_t Word );
|
||||||
// void Format_Hex( void (*Output)(char), uint32_t Word, uint8_t Digits);
|
// void Format_Hex( void (*Output)(char), uint32_t Word, uint8_t Digits);
|
||||||
void Format_MAC( void (*Output)(char), const uint8_t *MAC, uint8_t Len=6);
|
void Format_MAC( void (*Output)(char), const uint8_t *MAC, uint8_t Len=6);
|
||||||
|
|
||||||
|
@ -78,7 +79,8 @@ int8_t Read_Dec1(char Digit); // convert single digit into an
|
||||||
inline int8_t Read_Dec1(const char *Inp) { return Read_Dec1(Inp[0]); }
|
inline int8_t Read_Dec1(const char *Inp) { return Read_Dec1(Inp[0]); }
|
||||||
int8_t Read_Dec2(const char *Inp); // convert two digit decimal number into an integer
|
int8_t Read_Dec2(const char *Inp); // convert two digit decimal number into an integer
|
||||||
int16_t Read_Dec3(const char *Inp); // convert three digit decimal number into an integer
|
int16_t Read_Dec3(const char *Inp); // convert three digit decimal number into an integer
|
||||||
int16_t Read_Dec4(const char *Inp); // convert three digit decimal number into an integer
|
int16_t Read_Dec4(const char *Inp); // convert four digit decimal number into an integer
|
||||||
|
int32_t Read_Dec5(const char *Inp); // convert five digit decimal number into an integer
|
||||||
|
|
||||||
template <class Type>
|
template <class Type>
|
||||||
int8_t Read_Hex(Type &Int, const char *Inp, uint8_t MaxDig=0) // convert variable number of digits hexadecimal number into an integer
|
int8_t Read_Hex(Type &Int, const char *Inp, uint8_t MaxDig=0) // convert variable number of digits hexadecimal number into an integer
|
||||||
|
@ -120,7 +122,8 @@ template <class Type>
|
||||||
{ Dig=Read_UnsDec(Value, Inp+Len); }
|
{ Dig=Read_UnsDec(Value, Inp+Len); }
|
||||||
if(Dig<=0) return Dig;
|
if(Dig<=0) return Dig;
|
||||||
Len+=Dig;
|
Len+=Dig;
|
||||||
if(Sign=='-') Value=(-Value); return Len; }
|
if(Sign=='-') Value=(-Value);
|
||||||
|
return Len; }
|
||||||
|
|
||||||
template <class Type>
|
template <class Type>
|
||||||
int8_t Read_Float1(Type &Value, const char *Inp) // read floating point, take just one digit after decimal point
|
int8_t Read_Float1(Type &Value, const char *Inp) // read floating point, take just one digit after decimal point
|
||||||
|
|
21
main/gps.cpp
21
main/gps.cpp
|
@ -100,7 +100,7 @@ static uint32_t GPS_nextBaudRate(void) // produce next (possible) GPS baudrate
|
||||||
|
|
||||||
uint32_t GPS_getBaudRate (void) { return GPS_BaudRate; }
|
uint32_t GPS_getBaudRate (void) { return GPS_BaudRate; }
|
||||||
|
|
||||||
const uint32_t GPS_TargetBaudRate = 57600; // [bps]
|
const uint32_t GPS_TargetBaudRate = 115200; // [bps]
|
||||||
// const uint8_t GPS_TargetDynModel = 7; // for UBX GPS's: 6 = airborne with >1g, 7 = with >2g
|
// const uint8_t GPS_TargetDynModel = 7; // for UBX GPS's: 6 = airborne with >1g, 7 = with >2g
|
||||||
|
|
||||||
#ifdef WITH_MAVLINK
|
#ifdef WITH_MAVLINK
|
||||||
|
@ -119,7 +119,7 @@ static uint32_t RndID_TimeToChange = 0;
|
||||||
void FlightProcess(void)
|
void FlightProcess(void)
|
||||||
{ bool PrevInFlight=Flight.inFlight();
|
{ bool PrevInFlight=Flight.inFlight();
|
||||||
GPS_Position &GPS = GPS_Pos[GPS_PosIdx];
|
GPS_Position &GPS = GPS_Pos[GPS_PosIdx];
|
||||||
Flight.Process(GPS_Pos[GPS_PosIdx]);
|
Flight.Process(GPS);
|
||||||
GPS.InFlight=Flight.inFlight();
|
GPS.InFlight=Flight.inFlight();
|
||||||
if(Parameters.AddrType!=0) return;
|
if(Parameters.AddrType!=0) return;
|
||||||
uint32_t Random = GPS_Random^RX_Random;
|
uint32_t Random = GPS_Random^RX_Random;
|
||||||
|
@ -320,9 +320,9 @@ static void GPS_BurstStart(int CharDelay=0) // when GPS starts sending the data
|
||||||
#ifdef WITH_GPS_UBX
|
#ifdef WITH_GPS_UBX
|
||||||
if(Parameters.NavRate)
|
if(Parameters.NavRate)
|
||||||
{ UBX_CFG_RATE CFG_RATE;
|
{ UBX_CFG_RATE CFG_RATE;
|
||||||
CFG_RATE.measRate = 1000/Parameters.NavRate;
|
CFG_RATE.measRate = 1000/Parameters.NavRate; // set the requested measuring period
|
||||||
CFG_RATE.navRate = 1;
|
CFG_RATE.navRate = 1;
|
||||||
CFG_RATE.timeRef = 0;
|
CFG_RATE.timeRef = 0; //
|
||||||
UBX_RxMsg::Send(0x06, 0x08, GPS_UART_Write, (uint8_t*)(&CFG_RATE), sizeof(CFG_RATE));
|
UBX_RxMsg::Send(0x06, 0x08, GPS_UART_Write, (uint8_t*)(&CFG_RATE), sizeof(CFG_RATE));
|
||||||
#ifdef DEBUG_PRINT
|
#ifdef DEBUG_PRINT
|
||||||
Format_String(CONS_UART_Write, "GPS <- CFG-RATE: ");
|
Format_String(CONS_UART_Write, "GPS <- CFG-RATE: ");
|
||||||
|
@ -331,7 +331,7 @@ static void GPS_BurstStart(int CharDelay=0) // when GPS starts sending the data
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
{ UBX_CFG_NAV5 CFG_NAV5;
|
{ UBX_CFG_NAV5 CFG_NAV5;
|
||||||
CFG_NAV5.setDynModel(Parameters.NavMode);
|
CFG_NAV5.setDynModel(Parameters.NavMode); // set the navigation/dynamic model
|
||||||
UBX_RxMsg::Send(0x06, 0x24, GPS_UART_Write, (uint8_t*)(&CFG_NAV5), sizeof(CFG_NAV5));
|
UBX_RxMsg::Send(0x06, 0x24, GPS_UART_Write, (uint8_t*)(&CFG_NAV5), sizeof(CFG_NAV5));
|
||||||
#ifdef DEBUG_PRINT
|
#ifdef DEBUG_PRINT
|
||||||
Format_String(CONS_UART_Write, "GPS <- CFG-NAV5: ");
|
Format_String(CONS_UART_Write, "GPS <- CFG-NAV5: ");
|
||||||
|
@ -461,7 +461,8 @@ static void GPS_BurstStart(int CharDelay=0) // when GPS starts sending the data
|
||||||
// GPS_UART_Flush(500); // wait for all data to be sent to the GPS
|
// GPS_UART_Flush(500); // wait for all data to be sent to the GPS
|
||||||
// GPS_UART_SetBaudrate(GPS_TargetBaudRate); GPS_BaudRate=GPS_TargetBaudRate; // switch serial port to the new baudrate
|
// GPS_UART_SetBaudrate(GPS_TargetBaudRate); GPS_BaudRate=GPS_TargetBaudRate; // switch serial port to the new baudrate
|
||||||
}
|
}
|
||||||
QueryWait=60;
|
|
||||||
|
QueryWait=60; if(Parameters.NavRate) QueryWait+=Parameters.NavRate;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else { QueryWait=0; }
|
else { QueryWait=0; }
|
||||||
|
@ -1089,12 +1090,12 @@ void vTaskGPS(void* pvParameters)
|
||||||
#endif
|
#endif
|
||||||
LineIdle+=Delta; // count idle time
|
LineIdle+=Delta; // count idle time
|
||||||
NoValidData+=Delta; // count time without any valid NMEA nor UBX packet
|
NoValidData+=Delta; // count time without any valid NMEA nor UBX packet
|
||||||
uint16_t Bytes=0;
|
// uint16_t Bytes=0;
|
||||||
uint16_t MaxBytesPerTick = 1+(GPS_getBaudRate()+2500)/5000;
|
// uint16_t MaxBytesPerTick = 1+(GPS_getBaudRate()+2500)/5000;
|
||||||
for( ; ; ) // loop over bytes in the GPS UART buffer
|
for( ; ; ) // loop over bytes in the GPS UART buffer
|
||||||
{ uint8_t Byte; int Err=GPS_UART_Read(Byte); if(Err<=0) break; // get Byte from serial port, if no bytes then break this loop
|
{ uint8_t Byte; int Err=GPS_UART_Read(Byte); if(Err<=0) break; // get Byte from serial port, if no bytes then break this loop
|
||||||
// CONS_UART_Write(Byte); // copy the GPS output to console (for debug only)
|
// CONS_UART_Write(Byte); // copy the GPS output to console (for debug only)
|
||||||
Bytes++;
|
// Bytes++;
|
||||||
LineIdle=0; // if there was a byte: restart idle counting
|
LineIdle=0; // if there was a byte: restart idle counting
|
||||||
NMEA.ProcessByte(Byte); // process through the NMEA interpreter
|
NMEA.ProcessByte(Byte); // process through the NMEA interpreter
|
||||||
#ifdef WITH_GPS_UBX
|
#ifdef WITH_GPS_UBX
|
||||||
|
@ -1112,7 +1113,7 @@ void vTaskGPS(void* pvParameters)
|
||||||
#ifdef WITH_MAVLINK
|
#ifdef WITH_MAVLINK
|
||||||
if(MAV.isComplete()) { GPS_MAV(); NoValidData=0; MAV.Clear(); break; }
|
if(MAV.isComplete()) { GPS_MAV(); NoValidData=0; MAV.Clear(); break; }
|
||||||
#endif
|
#endif
|
||||||
if(Bytes>=MaxBytesPerTick) break;
|
// if(Bytes>=MaxBytesPerTick) break;
|
||||||
}
|
}
|
||||||
/*
|
/*
|
||||||
#ifdef DEBUG_PRINT
|
#ifdef DEBUG_PRINT
|
||||||
|
|
|
@ -1607,6 +1607,7 @@ void IO_Configuration(void)
|
||||||
uart_param_config (GPS_UART, &GPS_UART_Config);
|
uart_param_config (GPS_UART, &GPS_UART_Config);
|
||||||
uart_set_pin (GPS_UART, PIN_GPS_TXD, PIN_GPS_RXD, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
|
uart_set_pin (GPS_UART, PIN_GPS_TXD, PIN_GPS_RXD, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
|
||||||
uart_driver_install(GPS_UART, 512, 512, 0, 0, 0);
|
uart_driver_install(GPS_UART, 512, 512, 0, 0, 0);
|
||||||
|
uart_set_rx_full_threshold(GPS_UART, 24);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef AERO_UART
|
#ifdef AERO_UART
|
||||||
|
|
|
@ -64,21 +64,25 @@ class LoRaWANnode
|
||||||
|
|
||||||
// uint8_t TxMAC[16];
|
// uint8_t TxMAC[16];
|
||||||
// uint8_t TxMACs;
|
// uint8_t TxMACs;
|
||||||
static const size_t MaxPacketSize = 64; // [bytes]
|
static const size_t MaxPacketSize = 63; // [bytes]
|
||||||
uint8_t Packet[MaxPacketSize]; // generic packet for storage/processing
|
uint8_t Packet[MaxPacketSize]; // generic packet for storage/processing
|
||||||
|
|
||||||
|
uint8_t TxBattLevel; // battery level to be transmitted in the DevStatusAns
|
||||||
|
uint8_t TxOptLen;
|
||||||
|
uint8_t TxOpt[15]; // MAC commands/options to be transmitted
|
||||||
|
|
||||||
public:
|
public:
|
||||||
LoRaWANnode() { Reset(); }
|
LoRaWANnode() { Reset(); TxOptLen=0; TxBattLevel=0xFF; }
|
||||||
|
|
||||||
void Reset(void)
|
void Reset(void)
|
||||||
{ State=0; DevNonce=0; JoinNonce=0;
|
{ State=0; DevNonce=0; JoinNonce=0;
|
||||||
LastTx=0; TxCount=0; LastRx=0; RxCount=0; RxSilent=0; Flags=0; LastSaved=0;
|
LastTx=0; TxCount=0; LastRx=0; RxCount=0; RxSilent=0; Flags=0; LastSaved=0;
|
||||||
setCRC(); }
|
setCRC(); }
|
||||||
|
|
||||||
void Reset(uint64_t MAC, uint8_t *AppKey=0)
|
void Reset(uint64_t MAC, uint8_t *NewKey=0)
|
||||||
{ AppEUI=0x70B3D57ED0035895; // set OGN application
|
{ AppEUI=0x70B3D57ED0035895; // set OGN application
|
||||||
DevEUI=MAC; // set DevEUI from MAC
|
DevEUI=MAC; // set DevEUI from MAC
|
||||||
if(AppKey) memcpy(this->AppKey, AppKey, 16); // set the AppKey
|
if(NewKey) memcpy(AppKey, NewKey, 16); // set the AppKey
|
||||||
Reset(); } // reset to not-joined state
|
Reset(); } // reset to not-joined state
|
||||||
|
|
||||||
void Disconnect(void)
|
void Disconnect(void)
|
||||||
|
@ -155,8 +159,8 @@ class LoRaWANnode
|
||||||
|
|
||||||
int procJoinAccept(const RFM_LoRa_RxPacket &RxPacket)
|
int procJoinAccept(const RFM_LoRa_RxPacket &RxPacket)
|
||||||
{ int Ret=procJoinAccept(RxPacket.Byte, RxPacket.Len); if(Ret<0) return Ret;
|
{ int Ret=procJoinAccept(RxPacket.Byte, RxPacket.Len); if(Ret<0) return Ret;
|
||||||
RxSNR = RxPacket.SNR;
|
RxSNR = RxPacket.SNR; // store the SNR of the join-accept
|
||||||
RxRSSI = RxPacket.RSSI;
|
RxRSSI = RxPacket.RSSI; // store the RSSI
|
||||||
return Ret; }
|
return Ret; }
|
||||||
|
|
||||||
int procJoinAccept(const uint8_t *PktData, int PktLen) // process Join-Accept packet (5sec after Join-Request)
|
int procJoinAccept(const uint8_t *PktData, int PktLen) // process Join-Accept packet (5sec after Join-Request)
|
||||||
|
@ -175,7 +179,8 @@ class LoRaWANnode
|
||||||
RxDelay = Packet[12];
|
RxDelay = Packet[12];
|
||||||
State = 2; // State = accepted on network
|
State = 2; // State = accepted on network
|
||||||
UpCount = 0;
|
UpCount = 0;
|
||||||
DnCount = 0;
|
DnCount = 0xFFFFFFFF;
|
||||||
|
TxOptLen = 0;
|
||||||
#ifdef WITH_PRINTF
|
#ifdef WITH_PRINTF
|
||||||
printf("Accept[%d] ", PktLen-4);
|
printf("Accept[%d] ", PktLen-4);
|
||||||
for(int Idx=0; Idx<PktLen-4; Idx++)
|
for(int Idx=0; Idx<PktLen-4; Idx++)
|
||||||
|
@ -192,10 +197,13 @@ class LoRaWANnode
|
||||||
int PktLen=0;
|
int PktLen=0;
|
||||||
Packet[PktLen++] = Type<<5; // packet-type
|
Packet[PktLen++] = Type<<5; // packet-type
|
||||||
PktLen+=writeInt(Packet+PktLen, DevAddr, 4); // Device Address
|
PktLen+=writeInt(Packet+PktLen, DevAddr, 4); // Device Address
|
||||||
uint8_t Ctrl=0; // Frame Control
|
uint8_t Ctrl=0x00; // Frame Control
|
||||||
if(TxACK) { Ctrl|=0x20; TxACK=0; } // if there is ACK to be transmitted
|
if(TxACK) { Ctrl|=0x20; TxACK=0; } // if there is ACK to be transmitted
|
||||||
Packet[PktLen++] = Ctrl; // Frame Control: ADR | ADR-ACK-Req | ACK | ClassB | FOptsLen[4]
|
Packet[PktLen++] = Ctrl | TxOptLen; // Frame Control: ADR | ADR-ACK-Req | ACK | ClassB | FOptsLen[4]
|
||||||
PktLen+=writeInt(Packet+PktLen, UpCount, 2); // uplink frame counter
|
PktLen+=writeInt(Packet+PktLen, UpCount, 2); // uplink frame counter
|
||||||
|
for(int Idx=0; Idx<TxOptLen; Idx++) // add options, MAC replies
|
||||||
|
Packet[PktLen++]=TxOpt[Idx];
|
||||||
|
TxOptLen=0;
|
||||||
Packet[PktLen++] = Port; // port
|
Packet[PktLen++] = Port; // port
|
||||||
LoRaMacPayloadEncrypt(Data, DataLen, AppSesKey, DevAddr, 0, UpCount, Packet+PktLen); PktLen+=DataLen; // copy+encrypt user data
|
LoRaMacPayloadEncrypt(Data, DataLen, AppSesKey, DevAddr, 0, UpCount, Packet+PktLen); PktLen+=DataLen; // copy+encrypt user data
|
||||||
uint32_t MIC=0;
|
uint32_t MIC=0;
|
||||||
|
@ -211,13 +219,14 @@ class LoRaWANnode
|
||||||
|
|
||||||
int procRxData(const RFM_LoRa_RxPacket &RxPacket)
|
int procRxData(const RFM_LoRa_RxPacket &RxPacket)
|
||||||
{ int Ret=procRxData(RxPacket.Byte, RxPacket.Len); if(Ret<0) return Ret;
|
{ int Ret=procRxData(RxPacket.Byte, RxPacket.Len); if(Ret<0) return Ret;
|
||||||
RxSNR += (RxPacket.SNR-RxSNR+1)/2;
|
RxSNR += (RxPacket.SNR-RxSNR+1)/2; // average the SNR
|
||||||
RxRSSI += (RxPacket.RSSI-RxRSSI+1)/2;
|
RxRSSI += (RxPacket.RSSI-RxRSSI+1)/2; // average the RSSI
|
||||||
return Ret; }
|
return Ret; }
|
||||||
|
|
||||||
int procRxData(const uint8_t *PktData, int PktLen)
|
int procRxData(const uint8_t *PktData, int PktLen)
|
||||||
{ if(PktLen<12) return -1;
|
{ if(PktLen<12) return -1;
|
||||||
uint8_t Type = PktData[0]>>5; if(Type!=3 && Type!=5) return -1; // Frame Type: 3=unconfirmed data downlink, 5=confirmed data downlink
|
uint8_t Type = PktData[0]>>5; // Frame Type
|
||||||
|
if(Type!=3 && Type!=5) return -1; // Frame Type: 3=unconfirmed data downlink, 5=confirmed data downlink
|
||||||
uint32_t Addr=readInt<uint32_t>(PktData+1, 4); // device address
|
uint32_t Addr=readInt<uint32_t>(PktData+1, 4); // device address
|
||||||
if(Addr!=DevAddr) return 0; // check if packet is for us (it could be for somebody else)
|
if(Addr!=DevAddr) return 0; // check if packet is for us (it could be for somebody else)
|
||||||
uint8_t Ctrl = PktData[5]; // Frame Control: ADR | RFU | ACK | FPending | FOptLen[4]
|
uint8_t Ctrl = PktData[5]; // Frame Control: ADR | RFU | ACK | FPending | FOptLen[4]
|
||||||
|
@ -253,8 +262,30 @@ class LoRaWANnode
|
||||||
// }
|
// }
|
||||||
return DataLen; }
|
return DataLen; }
|
||||||
|
|
||||||
void procRxOpt(const uint8_t *Opt, uint8_t Len) // process the options
|
void procRxOpt(const uint8_t *Opt, uint8_t OptLen) // process the options
|
||||||
{ }
|
{ if(OptLen==0) return;
|
||||||
|
for(uint8_t Idx=0; Idx<OptLen; Idx++)
|
||||||
|
{ uint8_t Cmd=Opt[Idx];
|
||||||
|
if(Cmd==0x03) // LinkADRReq
|
||||||
|
{ TxOpt[TxOptLen++]=0x03; // LinkADRAns
|
||||||
|
TxOpt[TxOptLen++]=0x00; // negative 0x00 or positive 0x07 on all requested changes ?
|
||||||
|
Idx+=4; continue; } // skip the actual data for this command
|
||||||
|
if(Cmd==0x06) // DevStatusReq
|
||||||
|
{ TxOpt[TxOptLen++]=0x06; // DevStatusAns
|
||||||
|
TxOpt[TxOptLen++]=TxBattLevel; // battery level: 0=ext. power, 1..254=level, 255=not available
|
||||||
|
TxOpt[TxOptLen++]=(RxSNR>>2)&0x3F; // Rx SNR
|
||||||
|
continue; }
|
||||||
|
break; }
|
||||||
|
// #ifdef WITH_PRINTF
|
||||||
|
printf("RxOpt: [%d] ", OptLen);
|
||||||
|
for(int Idx=0; Idx<OptLen; Idx++)
|
||||||
|
printf("%02X", Opt[Idx]);
|
||||||
|
printf(" => [%d] ", TxOptLen);
|
||||||
|
for(int Idx=0; Idx<TxOptLen; Idx++)
|
||||||
|
printf("%02X", TxOpt[Idx]);
|
||||||
|
printf("\n");
|
||||||
|
// #endif
|
||||||
|
}
|
||||||
// { Format_String(CONS_UART_Write, "LoRaWAN Opt: ");
|
// { Format_String(CONS_UART_Write, "LoRaWAN Opt: ");
|
||||||
// for(uint8_t Idx=0; Idx<Len; Idx++)
|
// for(uint8_t Idx=0; Idx<Len; Idx++)
|
||||||
// Format_Hex(CONS_UART_Write, Opt[Idx]);
|
// Format_Hex(CONS_UART_Write, Opt[Idx]);
|
||||||
|
|
|
@ -73,19 +73,55 @@ void app_main(void)
|
||||||
// #endif
|
// #endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
CONS_UART_SetBaudrate(Parameters.CONbaud);
|
||||||
|
|
||||||
#ifdef WITH_LORAWAN
|
#ifdef WITH_LORAWAN
|
||||||
|
#ifdef DEBUG_PRINT
|
||||||
|
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||||
|
Format_String(CONS_UART_Write, "Parameters.AppKey:");
|
||||||
|
Format_HexBytes(CONS_UART_Write, Parameters.AppKey, 16);
|
||||||
|
Format_String(CONS_UART_Write, "\n");
|
||||||
|
xSemaphoreGive(CONS_Mutex);
|
||||||
|
#endif
|
||||||
WANdev.Reset(getUniqueID(), Parameters.AppKey); // set default LoRaWAN config.
|
WANdev.Reset(getUniqueID(), Parameters.AppKey); // set default LoRaWAN config.
|
||||||
if(WANdev.ReadFromNVS()!=ESP_OK) // if can't read the LoRaWAN setup from NVS
|
if(WANdev.ReadFromNVS()!=ESP_OK) // if can't read the LoRaWAN setup from NVS
|
||||||
{ WANdev.WriteToNVS(); } // then store the default
|
{ WANdev.WriteToNVS(); } // then store the default
|
||||||
if(Parameters.hasAppKey())
|
if(Parameters.hasAppKey())
|
||||||
{ if(!Parameters.sameAppKey(WANdev.AppKey)) // if LoRaWAN key different from the one in Parameters
|
{ if(!Parameters.sameAppKey(WANdev.AppKey)) // if LoRaWAN key different from the one in Parameters
|
||||||
{ WANdev.Reset(getUniqueID(), Parameters.AppKey); // then reset LoRaWAN to this key
|
{ WANdev.Reset(getUniqueID(), Parameters.AppKey); // then reset LoRaWAN to this key
|
||||||
WANdev.WriteToNVS(); } // and save LoRaWAN config. to NVS
|
WANdev.WriteToNVS(); // and save LoRaWAN config. to NVS
|
||||||
Parameters.clrAppKey(); }
|
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||||
|
Format_String(CONS_UART_Write, "LoRaWAN: AppKey <- ");
|
||||||
|
Format_HexBytes(CONS_UART_Write, Parameters.AppKey, 16);
|
||||||
|
// Format_String(CONS_UART_Write, " => ");
|
||||||
|
// Format_SignDec(CONS_UART_Write, Err);
|
||||||
|
Format_String(CONS_UART_Write, "\n");
|
||||||
|
xSemaphoreGive(CONS_Mutex);
|
||||||
|
}
|
||||||
|
Parameters.clrAppKey(); // clear the AppKey in the Parameters and save it to Flash
|
||||||
|
Parameters.WriteToNVS(); }
|
||||||
// WANdev.Disconnect(); // restart with network join-request/accept at each restart
|
// WANdev.Disconnect(); // restart with network join-request/accept at each restart
|
||||||
#endif
|
|
||||||
|
|
||||||
CONS_UART_SetBaudrate(Parameters.CONbaud);
|
#ifdef DEBUG_PRINT
|
||||||
|
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||||
|
Format_String(CONS_UART_Write, "LoRaWAN: AppEUI:");
|
||||||
|
Format_Hex(CONS_UART_Write, WANdev.AppEUI);
|
||||||
|
Format_String(CONS_UART_Write, " DevEUI:");
|
||||||
|
Format_Hex(CONS_UART_Write, WANdev.DevEUI);
|
||||||
|
Format_String(CONS_UART_Write, " DevNonce:");
|
||||||
|
Format_Hex(CONS_UART_Write, WANdev.DevNonce);
|
||||||
|
Format_String(CONS_UART_Write, " State:");
|
||||||
|
Format_Hex(CONS_UART_Write, WANdev.State);
|
||||||
|
Format_String(CONS_UART_Write, " AppKey:");
|
||||||
|
Format_HexBytes(CONS_UART_Write, WANdev.AppKey, 16);
|
||||||
|
Format_String(CONS_UART_Write, "\n");
|
||||||
|
Format_String(CONS_UART_Write, "Parameters.AppKey:");
|
||||||
|
Format_HexBytes(CONS_UART_Write, Parameters.AppKey, 16);
|
||||||
|
Format_String(CONS_UART_Write, "\n");
|
||||||
|
xSemaphoreGive(CONS_Mutex);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(WITH_BT_SPP) || defined(WITH_BLE_SPP)
|
#if defined(WITH_BT_SPP) || defined(WITH_BLE_SPP)
|
||||||
{ int32_t Err=BT_SPP_Init(); // start BT SPP
|
{ int32_t Err=BT_SPP_Init(); // start BT SPP
|
||||||
|
|
|
@ -199,15 +199,13 @@ uint16_t StratuxPort;
|
||||||
|
|
||||||
#ifdef WITH_LORAWAN
|
#ifdef WITH_LORAWAN
|
||||||
bool hasAppKey(void) const
|
bool hasAppKey(void) const
|
||||||
{ uint8_t Sum=AppKey[0];
|
{ for(int Idx=0; Idx<16; Idx++)
|
||||||
for(int Idx=1; Idx<16; Idx++)
|
{ if(AppKey[Idx]) return 1; }
|
||||||
{ if(Sum!=0) break;
|
return 0; }
|
||||||
Sum|=AppKey[Idx]; }
|
|
||||||
return Sum!=0; }
|
|
||||||
|
|
||||||
void clrAppKey(void) { for(int Idx=0; Idx<16; Idx++) AppKey[Idx]=0; }
|
void clrAppKey(void) { for(int Idx=0; Idx<16; Idx++) AppKey[Idx]=0x00; } // set AppKey to all-zero
|
||||||
void cpyAppKey(uint8_t *Key) { memcpy(Key, AppKey, 16); }
|
void cpyAppKey(uint8_t *Key) { memcpy(Key, AppKey, 16); } // copy AppKey from given pointer
|
||||||
bool sameAppKey(const uint8_t *RefKey) const { return memcmp(AppKey, RefKey, 16)==0; }
|
bool sameAppKey(const uint8_t *RefKey) const { return memcmp(AppKey, RefKey, 16)==0; } // is AppKey same as given ?
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
uint32_t static calcCheckSum(volatile uint32_t *Word, uint32_t Words) // calculate check-sum of pointed data
|
uint32_t static calcCheckSum(volatile uint32_t *Word, uint32_t Words) // calculate check-sum of pointed data
|
||||||
|
@ -236,7 +234,9 @@ uint16_t StratuxPort;
|
||||||
|
|
||||||
void setDefault(uint32_t UniqueAddr)
|
void setDefault(uint32_t UniqueAddr)
|
||||||
{ AcftID = ((uint32_t)DEFAULT_AcftType<<26) | 0x03000000 | (UniqueAddr&0x00FFFFFF);
|
{ AcftID = ((uint32_t)DEFAULT_AcftType<<26) | 0x03000000 | (UniqueAddr&0x00FFFFFF);
|
||||||
RFchipFreqCorr = 0; // [0.1ppm]
|
RFchip = 0; // this clears FreqCorr and other
|
||||||
|
// RFchipFreqCorr = 0; // [0.1ppm]
|
||||||
|
// RFchipTempCorr = 0; // [degC]
|
||||||
#ifdef WITH_RFM69W
|
#ifdef WITH_RFM69W
|
||||||
TxPower = 13; // [dBm] for RFM69W
|
TxPower = 13; // [dBm] for RFM69W
|
||||||
RFchipTypeHW = 0;
|
RFchipTypeHW = 0;
|
||||||
|
@ -681,8 +681,8 @@ uint16_t StratuxPort;
|
||||||
{ int32_t Mode=0; if(Read_Int(Mode, Value)<=0) return 0;
|
{ int32_t Mode=0; if(Read_Int(Mode, Value)<=0) return 0;
|
||||||
NavMode=Mode; return 1; }
|
NavMode=Mode; return 1; }
|
||||||
if(strcmp(Name, "NavRate")==0)
|
if(strcmp(Name, "NavRate")==0)
|
||||||
{ int32_t Mode=0; if(Read_Int(Mode, Value)<=0) return 0;
|
{ int32_t Rate=0; if(Read_Int(Rate, Value)<=0) return 0;
|
||||||
if(Mode<0) Mode=0; NavRate=Mode; return 1; }
|
if(Rate<0) Rate=0; NavRate=Rate; return 1; }
|
||||||
if(strcmp(Name, "GNSS")==0)
|
if(strcmp(Name, "GNSS")==0)
|
||||||
{ int32_t Mode=0; if(Read_Int(Mode, Value)<=0) return 0;
|
{ int32_t Mode=0; if(Read_Int(Mode, Value)<=0) return 0;
|
||||||
GNSS=Mode; return 1; }
|
GNSS=Mode; return 1; }
|
||||||
|
@ -706,8 +706,8 @@ uint16_t StratuxPort;
|
||||||
Verbose=Mode; return 1; }
|
Verbose=Mode; return 1; }
|
||||||
#ifdef WITH_LORAWAN
|
#ifdef WITH_LORAWAN
|
||||||
if(strcmp(Name, "AppKey")==0)
|
if(strcmp(Name, "AppKey")==0)
|
||||||
{ if(Value[0]=='0' && Value[1]=='x') Value+=2;
|
{ if(Value[0]=='0' && Value[1]=='x') Value+=2; // skip initial 0x if present
|
||||||
for(uint8_t Idx=0; Idx<16; Idx++)
|
for(uint8_t Idx=0; Idx<16; Idx++) // read 16 hex bytes
|
||||||
{ uint8_t Byte;
|
{ uint8_t Byte;
|
||||||
uint8_t Len=Read_Hex(Byte, Value);
|
uint8_t Len=Read_Hex(Byte, Value);
|
||||||
if(Len!=2) break;
|
if(Len!=2) break;
|
||||||
|
@ -991,6 +991,11 @@ uint16_t StratuxPort;
|
||||||
// Write_String (Line, "WIFIname", WIFIname[0]); strcat(Line, " # [char]\n"); Format_String(Output, Line);
|
// Write_String (Line, "WIFIname", WIFIname[0]); strcat(Line, " # [char]\n"); Format_String(Output, Line);
|
||||||
// Write_String (Line, "WIFIpass", WIFIpass[0]); strcat(Line, " # [char]\n"); Format_String(Output, Line);
|
// Write_String (Line, "WIFIpass", WIFIpass[0]); strcat(Line, " # [char]\n"); Format_String(Output, Line);
|
||||||
#endif
|
#endif
|
||||||
|
// #ifdef WITH_LORAWAN
|
||||||
|
// Format_String(Output, "AppKey = ");
|
||||||
|
// Format_HexBytes(Output, AppKey, 16);
|
||||||
|
// Format_String(Output, "\n");
|
||||||
|
// #endif
|
||||||
}
|
}
|
||||||
|
|
||||||
} ;
|
} ;
|
||||||
|
|
|
@ -125,7 +125,8 @@ static void IGC_Close(void)
|
||||||
Format_String(CONS_UART_Write, IGC_FileName);
|
Format_String(CONS_UART_Write, IGC_FileName);
|
||||||
Format_String(CONS_UART_Write, "\n");
|
Format_String(CONS_UART_Write, "\n");
|
||||||
xSemaphoreGive(CONS_Mutex);
|
xSemaphoreGive(CONS_Mutex);
|
||||||
fclose(IGC_File); IGC_File=0; IGC_FlightNum++; }
|
fclose(IGC_File); IGC_File=0;
|
||||||
|
IGC_FlightNum++; }
|
||||||
}
|
}
|
||||||
/*
|
/*
|
||||||
IGC_SaveTime = TimeSync_Time();
|
IGC_SaveTime = TimeSync_Time();
|
||||||
|
@ -146,11 +147,14 @@ static int IGC_Open(const GPS_Position &GPS)
|
||||||
IGC_FileName[IGC_PathLen]='/'; // slash after the path
|
IGC_FileName[IGC_PathLen]='/'; // slash after the path
|
||||||
Flight.ShortName(IGC_FileName+IGC_PathLen+1, GPS, IGC_FlightNum, IGC_Serial); // full name
|
Flight.ShortName(IGC_FileName+IGC_PathLen+1, GPS, IGC_FlightNum, IGC_Serial); // full name
|
||||||
IGC_File=fopen(IGC_FileName, "rt"); // attempt to open for read, just to try if the file is already there
|
IGC_File=fopen(IGC_FileName, "rt"); // attempt to open for read, just to try if the file is already there
|
||||||
if(IGC_File) { IGC_Close(); return -2; } // -2 => file already exists
|
// Format_String(CONS_UART_Write, "IGC_Open() (1)\n");
|
||||||
|
if(IGC_File) { fclose(IGC_File); IGC_File=0; IGC_FlightNum++; return -2; } // -2 => file already exists
|
||||||
IGC_File=fopen(IGC_FileName, "wt"); // open for write
|
IGC_File=fopen(IGC_FileName, "wt"); // open for write
|
||||||
|
// Format_String(CONS_UART_Write, "IGC_Open() (2)\n");
|
||||||
if(IGC_File==0) // failed: maybe sub-dir does not exist ?
|
if(IGC_File==0) // failed: maybe sub-dir does not exist ?
|
||||||
{ if(mkdir(IGC_Path, 0777)<0) return -3; // -3 => can't create sub-dir
|
{ if(mkdir(IGC_Path, 0777)<0) return -3; // -3 => can't create sub-dir
|
||||||
IGC_File=fopen(IGC_FileName, "wt"); } // retry to open for write
|
IGC_File=fopen(IGC_FileName, "wt"); } // retry to open for write
|
||||||
|
// Format_String(CONS_UART_Write, "IGC_Open() (3)\n");
|
||||||
if(IGC_File)
|
if(IGC_File)
|
||||||
{ IGC_SaveTime = TimeSync_Time();
|
{ IGC_SaveTime = TimeSync_Time();
|
||||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||||
|
@ -373,8 +377,8 @@ static void IGC_CheckGPS(void) // check if new
|
||||||
static bool PrevInFlight=0;
|
static bool PrevInFlight=0;
|
||||||
const GPS_Position &GPS = GPS_Pos[PosIdx];
|
const GPS_Position &GPS = GPS_Pos[PosIdx];
|
||||||
bool inFlight = GPS.InFlight; // in-flight or on-the-ground ?
|
bool inFlight = GPS.InFlight; // in-flight or on-the-ground ?
|
||||||
bool StopFile = PrevInFlight && !inFlight;
|
bool StopFile = PrevInFlight && !inFlight; // decide to stop the file when InFlight switches from 1 to 0
|
||||||
PrevInFlight = inFlight;;
|
PrevInFlight = inFlight;
|
||||||
#ifdef DEBUG_PRINT
|
#ifdef DEBUG_PRINT
|
||||||
GPS.PrintLine(Line);
|
GPS.PrintLine(Line);
|
||||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||||
|
|
294
sdkconfig
294
sdkconfig
|
@ -2,6 +2,7 @@
|
||||||
# Automatically generated file. DO NOT EDIT.
|
# Automatically generated file. DO NOT EDIT.
|
||||||
# Espressif IoT Development Framework (ESP-IDF) Project Configuration
|
# Espressif IoT Development Framework (ESP-IDF) Project Configuration
|
||||||
#
|
#
|
||||||
|
CONFIG_IDF_TARGET_ARCH_XTENSA=y
|
||||||
CONFIG_IDF_TARGET="esp32"
|
CONFIG_IDF_TARGET="esp32"
|
||||||
CONFIG_IDF_TARGET_ESP32=y
|
CONFIG_IDF_TARGET_ESP32=y
|
||||||
CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000
|
CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000
|
||||||
|
@ -31,12 +32,14 @@ CONFIG_APP_BUILD_USE_FLASH_SECTIONS=y
|
||||||
CONFIG_APP_COMPILE_TIME_DATE=y
|
CONFIG_APP_COMPILE_TIME_DATE=y
|
||||||
# CONFIG_APP_EXCLUDE_PROJECT_VER_VAR is not set
|
# CONFIG_APP_EXCLUDE_PROJECT_VER_VAR is not set
|
||||||
# CONFIG_APP_EXCLUDE_PROJECT_NAME_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
|
CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16
|
||||||
# end of Application manager
|
# end of Application manager
|
||||||
|
|
||||||
#
|
#
|
||||||
# Bootloader config
|
# Bootloader config
|
||||||
#
|
#
|
||||||
|
CONFIG_BOOTLOADER_OFFSET_IN_FLASH=0x1000
|
||||||
CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y
|
CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y
|
||||||
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_DEBUG is not set
|
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_DEBUG is not set
|
||||||
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_PERF is not set
|
# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_PERF is not set
|
||||||
|
@ -57,6 +60,8 @@ CONFIG_BOOTLOADER_WDT_ENABLE=y
|
||||||
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
CONFIG_BOOTLOADER_WDT_TIME_MS=9000
|
||||||
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
# CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE is not set
|
||||||
# CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP 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_RESERVE_RTC_SIZE=0
|
||||||
# CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC is not set
|
# CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC is not set
|
||||||
# end of Bootloader config
|
# end of Bootloader config
|
||||||
|
@ -81,6 +86,7 @@ CONFIG_ESPTOOLPY_BAUD_921600B=y
|
||||||
CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200
|
CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200
|
||||||
CONFIG_ESPTOOLPY_BAUD=921600
|
CONFIG_ESPTOOLPY_BAUD=921600
|
||||||
CONFIG_ESPTOOLPY_COMPRESSED=y
|
CONFIG_ESPTOOLPY_COMPRESSED=y
|
||||||
|
# CONFIG_ESPTOOLPY_NO_STUB is not set
|
||||||
# CONFIG_ESPTOOLPY_FLASHMODE_QIO is not set
|
# CONFIG_ESPTOOLPY_FLASHMODE_QIO is not set
|
||||||
# CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set
|
# CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set
|
||||||
CONFIG_ESPTOOLPY_FLASHMODE_DIO=y
|
CONFIG_ESPTOOLPY_FLASHMODE_DIO=y
|
||||||
|
@ -104,6 +110,7 @@ CONFIG_ESPTOOLPY_BEFORE="default_reset"
|
||||||
CONFIG_ESPTOOLPY_AFTER_RESET=y
|
CONFIG_ESPTOOLPY_AFTER_RESET=y
|
||||||
# CONFIG_ESPTOOLPY_AFTER_NORESET is not set
|
# CONFIG_ESPTOOLPY_AFTER_NORESET is not set
|
||||||
CONFIG_ESPTOOLPY_AFTER="hard_reset"
|
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_9600B is not set
|
||||||
# CONFIG_ESPTOOLPY_MONITOR_BAUD_57600B is not set
|
# CONFIG_ESPTOOLPY_MONITOR_BAUD_57600B is not set
|
||||||
CONFIG_ESPTOOLPY_MONITOR_BAUD_115200B=y
|
CONFIG_ESPTOOLPY_MONITOR_BAUD_115200B=y
|
||||||
|
@ -146,6 +153,7 @@ CONFIG_COMPILER_STACK_CHECK_MODE_NORM=y
|
||||||
CONFIG_COMPILER_STACK_CHECK=y
|
CONFIG_COMPILER_STACK_CHECK=y
|
||||||
# CONFIG_COMPILER_WARN_WRITE_STRINGS is not set
|
# CONFIG_COMPILER_WARN_WRITE_STRINGS is not set
|
||||||
CONFIG_COMPILER_DISABLE_GCC8_WARNINGS=y
|
CONFIG_COMPILER_DISABLE_GCC8_WARNINGS=y
|
||||||
|
# CONFIG_COMPILER_DUMP_RTL_FILES is not set
|
||||||
# end of Compiler options
|
# end of Compiler options
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -160,13 +168,20 @@ CONFIG_APPTRACE_DEST_NONE=y
|
||||||
CONFIG_APPTRACE_LOCK_ENABLE=y
|
CONFIG_APPTRACE_LOCK_ENABLE=y
|
||||||
# end of Application Level Tracing
|
# end of Application Level Tracing
|
||||||
|
|
||||||
|
#
|
||||||
|
# ESP-ASIO
|
||||||
|
#
|
||||||
|
# CONFIG_ASIO_SSL_SUPPORT is not set
|
||||||
|
# end of ESP-ASIO
|
||||||
|
|
||||||
#
|
#
|
||||||
# Bluetooth
|
# Bluetooth
|
||||||
#
|
#
|
||||||
CONFIG_BT_ENABLED=y
|
CONFIG_BT_ENABLED=y
|
||||||
|
CONFIG_BT_CTRL_ESP32=y
|
||||||
|
|
||||||
#
|
#
|
||||||
# Bluetooth controller
|
# Bluetooth controller(ESP32 Dual Mode Bluetooth)
|
||||||
#
|
#
|
||||||
# CONFIG_BTDM_CTRL_MODE_BLE_ONLY is not set
|
# CONFIG_BTDM_CTRL_MODE_BLE_ONLY is not set
|
||||||
# CONFIG_BTDM_CTRL_MODE_BR_EDR_ONLY is not set
|
# CONFIG_BTDM_CTRL_MODE_BR_EDR_ONLY is not set
|
||||||
|
@ -177,7 +192,16 @@ 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_HCI is not set
|
||||||
CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_PCM=y
|
CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_PCM=y
|
||||||
CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_EFF=1
|
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_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_BLE_MAX_CONN_EFF=2
|
||||||
CONFIG_BTDM_CTRL_BR_EDR_MAX_ACL_CONN_EFF=2
|
CONFIG_BTDM_CTRL_BR_EDR_MAX_ACL_CONN_EFF=2
|
||||||
CONFIG_BTDM_CTRL_BR_EDR_MAX_SYNC_CONN_EFF=0
|
CONFIG_BTDM_CTRL_BR_EDR_MAX_SYNC_CONN_EFF=0
|
||||||
|
@ -188,10 +212,10 @@ CONFIG_BTDM_CTRL_HCI_MODE_VHCI=y
|
||||||
#
|
#
|
||||||
# MODEM SLEEP Options
|
# MODEM SLEEP Options
|
||||||
#
|
#
|
||||||
CONFIG_BTDM_MODEM_SLEEP=y
|
CONFIG_BTDM_CTRL_MODEM_SLEEP=y
|
||||||
CONFIG_BTDM_MODEM_SLEEP_MODE_ORIG=y
|
CONFIG_BTDM_CTRL_MODEM_SLEEP_MODE_ORIG=y
|
||||||
# CONFIG_BTDM_MODEM_SLEEP_MODE_EVED is not set
|
# CONFIG_BTDM_CTRL_MODEM_SLEEP_MODE_EVED is not set
|
||||||
CONFIG_BTDM_LPCLK_SEL_MAIN_XTAL=y
|
CONFIG_BTDM_CTRL_LPCLK_SEL_MAIN_XTAL=y
|
||||||
# end of MODEM SLEEP Options
|
# end of MODEM SLEEP Options
|
||||||
|
|
||||||
CONFIG_BTDM_BLE_DEFAULT_SCA_250PPM=y
|
CONFIG_BTDM_BLE_DEFAULT_SCA_250PPM=y
|
||||||
|
@ -209,7 +233,37 @@ CONFIG_BTDM_BLE_ADV_REPORT_FLOW_CTRL_NUM=100
|
||||||
CONFIG_BTDM_BLE_ADV_REPORT_DISCARD_THRSHOLD=20
|
CONFIG_BTDM_BLE_ADV_REPORT_DISCARD_THRSHOLD=20
|
||||||
CONFIG_BTDM_COEX_BT_OPTIONS=y
|
CONFIG_BTDM_COEX_BT_OPTIONS=y
|
||||||
CONFIG_BTDM_COEX_BLE_ADV_HIGH_PRIORITY=y
|
CONFIG_BTDM_COEX_BLE_ADV_HIGH_PRIORITY=y
|
||||||
# end of Bluetooth controller
|
# 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
|
||||||
|
|
||||||
CONFIG_BT_BLUEDROID_ENABLED=y
|
CONFIG_BT_BLUEDROID_ENABLED=y
|
||||||
# CONFIG_BT_NIMBLE_ENABLED is not set
|
# CONFIG_BT_NIMBLE_ENABLED is not set
|
||||||
|
@ -226,15 +280,19 @@ CONFIG_BT_CLASSIC_ENABLED=y
|
||||||
# CONFIG_BT_A2DP_ENABLE is not set
|
# CONFIG_BT_A2DP_ENABLE is not set
|
||||||
CONFIG_BT_SPP_ENABLED=y
|
CONFIG_BT_SPP_ENABLED=y
|
||||||
# CONFIG_BT_HFP_ENABLE is not set
|
# CONFIG_BT_HFP_ENABLE is not set
|
||||||
|
# CONFIG_BT_HID_HOST_ENABLED is not set
|
||||||
CONFIG_BT_SSP_ENABLED=y
|
CONFIG_BT_SSP_ENABLED=y
|
||||||
CONFIG_BT_BLE_ENABLED=y
|
CONFIG_BT_BLE_ENABLED=y
|
||||||
CONFIG_BT_GATTS_ENABLE=y
|
CONFIG_BT_GATTS_ENABLE=y
|
||||||
# CONFIG_BT_GATTS_PPCP_CHAR_GAP is not set
|
# 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_MANUAL is not set
|
||||||
CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_AUTO=y
|
CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_AUTO=y
|
||||||
CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_MODE=0
|
CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_MODE=0
|
||||||
CONFIG_BT_GATTC_ENABLE=y
|
CONFIG_BT_GATTC_ENABLE=y
|
||||||
# CONFIG_BT_GATTC_CACHE_NVS_FLASH is not set
|
# CONFIG_BT_GATTC_CACHE_NVS_FLASH is not set
|
||||||
|
CONFIG_BT_GATTC_CONNECT_RETRY_COUNT=3
|
||||||
CONFIG_BT_BLE_SMP_ENABLE=y
|
CONFIG_BT_BLE_SMP_ENABLE=y
|
||||||
# CONFIG_BT_SMP_SLAVE_CON_PARAMS_UPD_ENABLE is not set
|
# CONFIG_BT_SMP_SLAVE_CON_PARAMS_UPD_ENABLE is not set
|
||||||
# CONFIG_BT_STACK_NO_LOG is not set
|
# CONFIG_BT_STACK_NO_LOG is not set
|
||||||
|
@ -413,12 +471,14 @@ CONFIG_BT_LOG_BLUFI_TRACE_LEVEL=2
|
||||||
# end of BT DEBUG LOG LEVEL
|
# end of BT DEBUG LOG LEVEL
|
||||||
|
|
||||||
CONFIG_BT_ACL_CONNECTIONS=4
|
CONFIG_BT_ACL_CONNECTIONS=4
|
||||||
|
CONFIG_BT_MULTI_CONNECTION_ENBALE=y
|
||||||
# CONFIG_BT_ALLOCATION_FROM_SPIRAM_FIRST is not set
|
# CONFIG_BT_ALLOCATION_FROM_SPIRAM_FIRST is not set
|
||||||
# CONFIG_BT_BLE_DYNAMIC_ENV_MEMORY is not set
|
# CONFIG_BT_BLE_DYNAMIC_ENV_MEMORY is not set
|
||||||
# CONFIG_BT_BLE_HOST_QUEUE_CONG_CHECK is not set
|
# CONFIG_BT_BLE_HOST_QUEUE_CONG_CHECK is not set
|
||||||
CONFIG_BT_SMP_ENABLE=y
|
CONFIG_BT_SMP_ENABLE=y
|
||||||
# CONFIG_BT_BLE_ACT_SCAN_REP_ADV_SCAN is not set
|
# CONFIG_BT_BLE_ACT_SCAN_REP_ADV_SCAN is not set
|
||||||
CONFIG_BT_BLE_ESTAB_LINK_CONN_TOUT=30
|
CONFIG_BT_BLE_ESTAB_LINK_CONN_TOUT=30
|
||||||
|
# CONFIG_BT_BLE_RPA_SUPPORTED is not set
|
||||||
CONFIG_BT_RESERVE_DRAM=0xdb5c
|
CONFIG_BT_RESERVE_DRAM=0xdb5c
|
||||||
# end of Bluedroid Options
|
# end of Bluedroid Options
|
||||||
# end of Bluetooth
|
# end of Bluetooth
|
||||||
|
@ -454,6 +514,16 @@ CONFIG_SPI_MASTER_ISR_IN_IRAM=y
|
||||||
CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
||||||
# end of SPI configuration
|
# 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
|
# UART configuration
|
||||||
#
|
#
|
||||||
|
@ -465,6 +535,12 @@ CONFIG_SPI_SLAVE_ISR_IN_IRAM=y
|
||||||
#
|
#
|
||||||
# CONFIG_RTCIO_SUPPORT_RTC_GPIO_DESC is not set
|
# CONFIG_RTCIO_SUPPORT_RTC_GPIO_DESC is not set
|
||||||
# end of RTCIO configuration
|
# end of RTCIO configuration
|
||||||
|
|
||||||
|
#
|
||||||
|
# GPIO Configuration
|
||||||
|
#
|
||||||
|
# CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set
|
||||||
|
# end of GPIO Configuration
|
||||||
# end of Driver configurations
|
# end of Driver configurations
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -482,8 +558,10 @@ CONFIG_EFUSE_MAX_BLK_LEN=192
|
||||||
# ESP-TLS
|
# ESP-TLS
|
||||||
#
|
#
|
||||||
CONFIG_ESP_TLS_USING_MBEDTLS=y
|
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_SERVER is not set
|
||||||
# CONFIG_ESP_TLS_PSK_VERIFICATION is not set
|
# CONFIG_ESP_TLS_PSK_VERIFICATION is not set
|
||||||
|
# CONFIG_ESP_TLS_INSECURE is not set
|
||||||
# end of ESP-TLS
|
# end of ESP-TLS
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -506,10 +584,6 @@ CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR=y
|
||||||
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4
|
CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4
|
||||||
# CONFIG_ESP32_ULP_COPROC_ENABLED is not set
|
# CONFIG_ESP32_ULP_COPROC_ENABLED is not set
|
||||||
CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=0
|
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_DEBUG_OCDAWARE=y
|
||||||
CONFIG_ESP32_BROWNOUT_DET=y
|
CONFIG_ESP32_BROWNOUT_DET=y
|
||||||
CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_0=y
|
CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_0=y
|
||||||
|
@ -541,13 +615,12 @@ CONFIG_ESP32_XTAL_FREQ=0
|
||||||
# CONFIG_ESP32_RTCDATA_IN_FAST_MEM is not set
|
# CONFIG_ESP32_RTCDATA_IN_FAST_MEM is not set
|
||||||
# CONFIG_ESP32_USE_FIXED_STATIC_RAM_SIZE is not set
|
# CONFIG_ESP32_USE_FIXED_STATIC_RAM_SIZE is not set
|
||||||
CONFIG_ESP32_DPORT_DIS_INTERRUPT_LVL=5
|
CONFIG_ESP32_DPORT_DIS_INTERRUPT_LVL=5
|
||||||
|
# CONFIG_ESP32_IRAM_AS_8BIT_ACCESSIBLE_MEMORY is not set
|
||||||
# end of ESP32-specific
|
# end of ESP32-specific
|
||||||
|
|
||||||
#
|
CONFIG_ESP32C3_DEBUG_OCDAWARE=y
|
||||||
# Power Management
|
CONFIG_ESP32C3_BROWNOUT_DET=y
|
||||||
#
|
CONFIG_ESP32C3_LIGHTSLEEP_GPIO_RESET_WORKAROUND=y
|
||||||
# CONFIG_PM_ENABLE is not set
|
|
||||||
# end of Power Management
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Cache config
|
# Cache config
|
||||||
|
@ -559,6 +632,16 @@ CONFIG_ESP32S2_ULP_COPROC_RESERVE_MEM=0
|
||||||
CONFIG_ESP32S2_DEBUG_OCDAWARE=y
|
CONFIG_ESP32S2_DEBUG_OCDAWARE=y
|
||||||
CONFIG_ESP32S2_BROWNOUT_DET=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
|
# ADC-Calibration
|
||||||
#
|
#
|
||||||
|
@ -570,17 +653,17 @@ CONFIG_ADC_CAL_LUT_ENABLE=y
|
||||||
#
|
#
|
||||||
# Common ESP-related
|
# Common ESP-related
|
||||||
#
|
#
|
||||||
# CONFIG_ESP_TIMER_PROFILING is not set
|
|
||||||
CONFIG_ESP_ERR_TO_NAME_LOOKUP=y
|
CONFIG_ESP_ERR_TO_NAME_LOOKUP=y
|
||||||
CONFIG_ESP_SYSTEM_EVENT_QUEUE_SIZE=32
|
CONFIG_ESP_SYSTEM_EVENT_QUEUE_SIZE=32
|
||||||
CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=2048
|
CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=2048
|
||||||
CONFIG_ESP_MAIN_TASK_STACK_SIZE=3000
|
CONFIG_ESP_MAIN_TASK_STACK_SIZE=3000
|
||||||
CONFIG_ESP_IPC_TASK_STACK_SIZE=1024
|
CONFIG_ESP_IPC_TASK_STACK_SIZE=1024
|
||||||
CONFIG_ESP_TIMER_TASK_STACK_SIZE=2048
|
|
||||||
CONFIG_ESP_MINIMAL_SHARED_STACK_SIZE=2048
|
CONFIG_ESP_MINIMAL_SHARED_STACK_SIZE=2048
|
||||||
CONFIG_ESP_CONSOLE_UART_DEFAULT=y
|
CONFIG_ESP_CONSOLE_UART_DEFAULT=y
|
||||||
# CONFIG_ESP_CONSOLE_UART_CUSTOM is not set
|
# CONFIG_ESP_CONSOLE_UART_CUSTOM is not set
|
||||||
# CONFIG_ESP_CONSOLE_UART_NONE 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_NUM=0
|
CONFIG_ESP_CONSOLE_UART_NUM=0
|
||||||
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
|
||||||
CONFIG_ESP_INT_WDT=y
|
CONFIG_ESP_INT_WDT=y
|
||||||
|
@ -590,6 +673,10 @@ CONFIG_ESP_TASK_WDT=y
|
||||||
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
|
||||||
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||||
# CONFIG_ESP_PANIC_HANDLER_IRAM is not set
|
# 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
|
# end of Common ESP-related
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -637,6 +724,7 @@ CONFIG_HTTPD_MAX_URI_LEN=512
|
||||||
CONFIG_HTTPD_ERR_RESP_NO_DELAY=y
|
CONFIG_HTTPD_ERR_RESP_NO_DELAY=y
|
||||||
CONFIG_HTTPD_PURGE_BUF_LEN=32
|
CONFIG_HTTPD_PURGE_BUF_LEN=32
|
||||||
# CONFIG_HTTPD_LOG_PURGE_DATA is not set
|
# CONFIG_HTTPD_LOG_PURGE_DATA is not set
|
||||||
|
# CONFIG_HTTPD_WS_SUPPORT is not set
|
||||||
# end of HTTP Server
|
# end of HTTP Server
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -660,6 +748,41 @@ CONFIG_ESP_NETIF_TCPIP_LWIP=y
|
||||||
CONFIG_ESP_NETIF_TCPIP_ADAPTER_COMPATIBLE_LAYER=y
|
CONFIG_ESP_NETIF_TCPIP_ADAPTER_COMPATIBLE_LAYER=y
|
||||||
# end of ESP NETIF Adapter
|
# 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
|
# Wi-Fi
|
||||||
#
|
#
|
||||||
|
@ -682,6 +805,8 @@ CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32
|
||||||
CONFIG_ESP32_WIFI_IRAM_OPT=y
|
CONFIG_ESP32_WIFI_IRAM_OPT=y
|
||||||
CONFIG_ESP32_WIFI_RX_IRAM_OPT=y
|
CONFIG_ESP32_WIFI_RX_IRAM_OPT=y
|
||||||
CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=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
|
# end of Wi-Fi
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -696,9 +821,9 @@ CONFIG_ESP32_PHY_MAX_TX_POWER=20
|
||||||
#
|
#
|
||||||
# Core dump
|
# Core dump
|
||||||
#
|
#
|
||||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set
|
# CONFIG_ESP_COREDUMP_ENABLE_TO_FLASH is not set
|
||||||
# CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set
|
# CONFIG_ESP_COREDUMP_ENABLE_TO_UART is not set
|
||||||
CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y
|
CONFIG_ESP_COREDUMP_ENABLE_TO_NONE=y
|
||||||
# end of Core dump
|
# end of Core dump
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -733,21 +858,26 @@ CONFIG_FATFS_LFN_NONE=y
|
||||||
CONFIG_FATFS_FS_LOCK=0
|
CONFIG_FATFS_FS_LOCK=0
|
||||||
CONFIG_FATFS_TIMEOUT_MS=10000
|
CONFIG_FATFS_TIMEOUT_MS=10000
|
||||||
CONFIG_FATFS_PER_FILE_CACHE=y
|
CONFIG_FATFS_PER_FILE_CACHE=y
|
||||||
|
# CONFIG_FATFS_USE_FASTSEEK is not set
|
||||||
# end of FAT Filesystem support
|
# end of FAT Filesystem support
|
||||||
|
|
||||||
#
|
#
|
||||||
# Modbus configuration
|
# 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_RTU_EN=y
|
||||||
CONFIG_FMB_COMM_MODE_ASCII_EN=y
|
CONFIG_FMB_COMM_MODE_ASCII_EN=y
|
||||||
CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150
|
CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150
|
||||||
CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200
|
CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200
|
||||||
CONFIG_FMB_QUEUE_LENGTH=20
|
CONFIG_FMB_QUEUE_LENGTH=20
|
||||||
CONFIG_FMB_SERIAL_TASK_STACK_SIZE=2048
|
CONFIG_FMB_PORT_TASK_STACK_SIZE=4096
|
||||||
CONFIG_FMB_SERIAL_BUF_SIZE=256
|
CONFIG_FMB_SERIAL_BUF_SIZE=256
|
||||||
CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8
|
CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8
|
||||||
CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000
|
CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000
|
||||||
CONFIG_FMB_SERIAL_TASK_PRIO=10
|
CONFIG_FMB_PORT_TASK_PRIO=10
|
||||||
# CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT is not set
|
# CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT is not set
|
||||||
CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20
|
CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20
|
||||||
CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20
|
CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20
|
||||||
|
@ -766,6 +896,7 @@ CONFIG_FREERTOS_UNICORE=y
|
||||||
CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF
|
CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF
|
||||||
CONFIG_FREERTOS_CORETIMER_0=y
|
CONFIG_FREERTOS_CORETIMER_0=y
|
||||||
# CONFIG_FREERTOS_CORETIMER_1 is not set
|
# CONFIG_FREERTOS_CORETIMER_1 is not set
|
||||||
|
CONFIG_FREERTOS_OPTIMIZED_SCHEDULER=y
|
||||||
CONFIG_FREERTOS_HZ=1000
|
CONFIG_FREERTOS_HZ=1000
|
||||||
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y
|
||||||
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set
|
# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set
|
||||||
|
@ -791,10 +922,11 @@ CONFIG_FREERTOS_USE_TRACE_FACILITY=y
|
||||||
CONFIG_FREERTOS_USE_STATS_FORMATTING_FUNCTIONS=y
|
CONFIG_FREERTOS_USE_STATS_FORMATTING_FUNCTIONS=y
|
||||||
# CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID is not set
|
# CONFIG_FREERTOS_VTASKLIST_INCLUDE_COREID is not set
|
||||||
# CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS 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_MUTEX_GIVEN_BY_OWNER=y
|
||||||
# CONFIG_FREERTOS_CHECK_PORT_CRITICAL_COMPLIANCE is not set
|
# 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_DEBUG_OCDAWARE=y
|
||||||
|
# CONFIG_FREERTOS_FPU_IN_ISR is not set
|
||||||
# end of FreeRTOS
|
# end of FreeRTOS
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -806,6 +938,7 @@ CONFIG_HEAP_POISONING_DISABLED=y
|
||||||
CONFIG_HEAP_TRACING_OFF=y
|
CONFIG_HEAP_TRACING_OFF=y
|
||||||
# CONFIG_HEAP_TRACING_STANDALONE is not set
|
# CONFIG_HEAP_TRACING_STANDALONE is not set
|
||||||
# CONFIG_HEAP_TRACING_TOHOST is not set
|
# CONFIG_HEAP_TRACING_TOHOST is not set
|
||||||
|
# CONFIG_HEAP_ABORT_WHEN_ALLOCATION_FAILS is not set
|
||||||
# end of Heap memory debugging
|
# end of Heap memory debugging
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -850,8 +983,11 @@ CONFIG_LWIP_MAX_SOCKETS=8
|
||||||
# CONFIG_LWIP_SO_REUSE is not set
|
# CONFIG_LWIP_SO_REUSE is not set
|
||||||
# CONFIG_LWIP_SO_RCVBUF is not set
|
# CONFIG_LWIP_SO_RCVBUF is not set
|
||||||
# CONFIG_LWIP_NETBUF_RECVINFO is not set
|
# CONFIG_LWIP_NETBUF_RECVINFO is not set
|
||||||
CONFIG_LWIP_IP_FRAG=y
|
CONFIG_LWIP_IP4_FRAG=y
|
||||||
# CONFIG_LWIP_IP_REASSEMBLY is not set
|
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_STATS is not set
|
# CONFIG_LWIP_STATS is not set
|
||||||
CONFIG_LWIP_ETHARP_TRUST_IP_MAC=y
|
CONFIG_LWIP_ETHARP_TRUST_IP_MAC=y
|
||||||
CONFIG_LWIP_ESP_GRATUITOUS_ARP=y
|
CONFIG_LWIP_ESP_GRATUITOUS_ARP=y
|
||||||
|
@ -868,6 +1004,7 @@ CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8
|
||||||
# end of DHCP server
|
# end of DHCP server
|
||||||
|
|
||||||
# CONFIG_LWIP_AUTOIP is not set
|
# CONFIG_LWIP_AUTOIP is not set
|
||||||
|
CONFIG_LWIP_IPV6=y
|
||||||
# CONFIG_LWIP_IPV6_AUTOCONFIG is not set
|
# CONFIG_LWIP_IPV6_AUTOCONFIG is not set
|
||||||
CONFIG_LWIP_NETIF_LOOPBACK=y
|
CONFIG_LWIP_NETIF_LOOPBACK=y
|
||||||
CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8
|
CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8
|
||||||
|
@ -877,6 +1014,7 @@ CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8
|
||||||
#
|
#
|
||||||
CONFIG_LWIP_MAX_ACTIVE_TCP=16
|
CONFIG_LWIP_MAX_ACTIVE_TCP=16
|
||||||
CONFIG_LWIP_MAX_LISTENING_TCP=16
|
CONFIG_LWIP_MAX_LISTENING_TCP=16
|
||||||
|
CONFIG_LWIP_TCP_HIGH_SPEED_RETRANSMISSION=y
|
||||||
CONFIG_LWIP_TCP_MAXRTX=12
|
CONFIG_LWIP_TCP_MAXRTX=12
|
||||||
CONFIG_LWIP_TCP_SYNMAXRTX=6
|
CONFIG_LWIP_TCP_SYNMAXRTX=6
|
||||||
CONFIG_LWIP_TCP_MSS=1436
|
CONFIG_LWIP_TCP_MSS=1436
|
||||||
|
@ -891,6 +1029,7 @@ CONFIG_LWIP_TCP_QUEUE_OOSEQ=y
|
||||||
CONFIG_LWIP_TCP_OVERSIZE_MSS=y
|
CONFIG_LWIP_TCP_OVERSIZE_MSS=y
|
||||||
# CONFIG_LWIP_TCP_OVERSIZE_QUARTER_MSS is not set
|
# CONFIG_LWIP_TCP_OVERSIZE_QUARTER_MSS is not set
|
||||||
# CONFIG_LWIP_TCP_OVERSIZE_DISABLE is not set
|
# CONFIG_LWIP_TCP_OVERSIZE_DISABLE is not set
|
||||||
|
CONFIG_LWIP_TCP_RTO_TIME=1500
|
||||||
# end of TCP
|
# end of TCP
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -900,11 +1039,22 @@ CONFIG_LWIP_MAX_UDP_PCBS=16
|
||||||
CONFIG_LWIP_UDP_RECVMBOX_SIZE=6
|
CONFIG_LWIP_UDP_RECVMBOX_SIZE=6
|
||||||
# end of UDP
|
# 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_STACK_SIZE=2048
|
||||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY=y
|
||||||
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set
|
# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0 is not set
|
||||||
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x7FFFFFFF
|
||||||
# CONFIG_LWIP_PPP_SUPPORT is not set
|
# 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
|
# ICMP
|
||||||
|
@ -925,6 +1075,24 @@ CONFIG_LWIP_MAX_RAW_PCBS=16
|
||||||
CONFIG_LWIP_DHCP_MAX_NTP_SERVERS=1
|
CONFIG_LWIP_DHCP_MAX_NTP_SERVERS=1
|
||||||
CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000
|
CONFIG_LWIP_SNTP_UPDATE_DELAY=3600000
|
||||||
# end of SNTP
|
# 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
|
# end of LWIP
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -935,14 +1103,31 @@ CONFIG_MBEDTLS_INTERNAL_MEM_ALLOC=y
|
||||||
# CONFIG_MBEDTLS_CUSTOM_MEM_ALLOC is not set
|
# CONFIG_MBEDTLS_CUSTOM_MEM_ALLOC is not set
|
||||||
CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=16384
|
CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=16384
|
||||||
# CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN is not set
|
# CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN is not set
|
||||||
|
# CONFIG_MBEDTLS_DYNAMIC_BUFFER is not set
|
||||||
# CONFIG_MBEDTLS_DEBUG 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_ECP_RESTARTABLE is not set
|
||||||
# CONFIG_MBEDTLS_CMAC_C is not set
|
# CONFIG_MBEDTLS_CMAC_C is not set
|
||||||
CONFIG_MBEDTLS_HARDWARE_AES=y
|
CONFIG_MBEDTLS_HARDWARE_AES=y
|
||||||
CONFIG_MBEDTLS_HARDWARE_MPI=y
|
CONFIG_MBEDTLS_HARDWARE_MPI=y
|
||||||
# CONFIG_MBEDTLS_HARDWARE_SHA is not set
|
# 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=y
|
||||||
# CONFIG_MBEDTLS_HAVE_TIME_DATE is not set
|
# 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_AND_CLIENT=y
|
||||||
# CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set
|
# CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set
|
||||||
# CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set
|
# CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set
|
||||||
|
@ -1007,6 +1192,7 @@ CONFIG_MBEDTLS_X509_CSR_PARSE_C=y
|
||||||
CONFIG_MBEDTLS_ECP_C=y
|
CONFIG_MBEDTLS_ECP_C=y
|
||||||
CONFIG_MBEDTLS_ECDH_C=y
|
CONFIG_MBEDTLS_ECDH_C=y
|
||||||
CONFIG_MBEDTLS_ECDSA_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_SECP192R1_ENABLED=y
|
||||||
CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y
|
CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y
|
||||||
CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y
|
CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y
|
||||||
|
@ -1020,6 +1206,11 @@ CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y
|
||||||
CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y
|
CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y
|
||||||
CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y
|
CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y
|
||||||
CONFIG_MBEDTLS_ECP_NIST_OPTIM=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
|
# CONFIG_MBEDTLS_SECURITY_RISKS is not set
|
||||||
# end of mbedTLS
|
# end of mbedTLS
|
||||||
|
|
||||||
|
@ -1028,10 +1219,12 @@ CONFIG_MBEDTLS_ECP_NIST_OPTIM=y
|
||||||
#
|
#
|
||||||
CONFIG_MDNS_MAX_SERVICES=10
|
CONFIG_MDNS_MAX_SERVICES=10
|
||||||
CONFIG_MDNS_TASK_PRIORITY=1
|
CONFIG_MDNS_TASK_PRIORITY=1
|
||||||
|
CONFIG_MDNS_TASK_STACK_SIZE=4096
|
||||||
# CONFIG_MDNS_TASK_AFFINITY_NO_AFFINITY is not set
|
# CONFIG_MDNS_TASK_AFFINITY_NO_AFFINITY is not set
|
||||||
CONFIG_MDNS_TASK_AFFINITY_CPU0=y
|
CONFIG_MDNS_TASK_AFFINITY_CPU0=y
|
||||||
CONFIG_MDNS_TASK_AFFINITY=0x0
|
CONFIG_MDNS_TASK_AFFINITY=0x0
|
||||||
CONFIG_MDNS_SERVICE_ADD_TIMEOUT_MS=2000
|
CONFIG_MDNS_SERVICE_ADD_TIMEOUT_MS=2000
|
||||||
|
# CONFIG_MDNS_STRICT_MODE is not set
|
||||||
CONFIG_MDNS_TIMER_PERIOD_MS=100
|
CONFIG_MDNS_TIMER_PERIOD_MS=100
|
||||||
# end of mDNS
|
# end of mDNS
|
||||||
|
|
||||||
|
@ -1042,6 +1235,9 @@ CONFIG_MQTT_PROTOCOL_311=y
|
||||||
CONFIG_MQTT_TRANSPORT_SSL=y
|
CONFIG_MQTT_TRANSPORT_SSL=y
|
||||||
CONFIG_MQTT_TRANSPORT_WEBSOCKET=y
|
CONFIG_MQTT_TRANSPORT_WEBSOCKET=y
|
||||||
CONFIG_MQTT_TRANSPORT_WEBSOCKET_SECURE=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_USE_CUSTOM_CONFIG is not set
|
||||||
# CONFIG_MQTT_TASK_CORE_SELECTION_ENABLED is not set
|
# CONFIG_MQTT_TASK_CORE_SELECTION_ENABLED is not set
|
||||||
# CONFIG_MQTT_CUSTOM_OUTBOX is not set
|
# CONFIG_MQTT_CUSTOM_OUTBOX is not set
|
||||||
|
@ -1068,6 +1264,7 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y
|
||||||
# OpenSSL
|
# OpenSSL
|
||||||
#
|
#
|
||||||
# CONFIG_OPENSSL_DEBUG is not set
|
# CONFIG_OPENSSL_DEBUG is not set
|
||||||
|
CONFIG_OPENSSL_ERROR_STACK=y
|
||||||
CONFIG_OPENSSL_ASSERT_DO_NOTHING=y
|
CONFIG_OPENSSL_ASSERT_DO_NOTHING=y
|
||||||
# CONFIG_OPENSSL_ASSERT_EXIT is not set
|
# CONFIG_OPENSSL_ASSERT_EXIT is not set
|
||||||
# end of OpenSSL
|
# end of OpenSSL
|
||||||
|
@ -1092,17 +1289,25 @@ CONFIG_SPI_FLASH_DANGEROUS_WRITE_ABORTS=y
|
||||||
# CONFIG_SPI_FLASH_DANGEROUS_WRITE_FAILS is not set
|
# CONFIG_SPI_FLASH_DANGEROUS_WRITE_FAILS is not set
|
||||||
# CONFIG_SPI_FLASH_DANGEROUS_WRITE_ALLOWED is not set
|
# CONFIG_SPI_FLASH_DANGEROUS_WRITE_ALLOWED is not set
|
||||||
# CONFIG_SPI_FLASH_USE_LEGACY_IMPL 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_BYPASS_BLOCK_ERASE is not set
|
||||||
CONFIG_SPI_FLASH_YIELD_DURING_ERASE=y
|
CONFIG_SPI_FLASH_YIELD_DURING_ERASE=y
|
||||||
CONFIG_SPI_FLASH_ERASE_YIELD_DURATION_MS=20
|
CONFIG_SPI_FLASH_ERASE_YIELD_DURATION_MS=20
|
||||||
CONFIG_SPI_FLASH_ERASE_YIELD_TICKS=1
|
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
|
# Auto-detect flash chips
|
||||||
#
|
#
|
||||||
CONFIG_SPI_FLASH_SUPPORT_ISSI_CHIP=y
|
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_GD_CHIP=y
|
||||||
|
CONFIG_SPI_FLASH_SUPPORT_WINBOND_CHIP=y
|
||||||
# end of Auto-detect flash chips
|
# end of Auto-detect flash chips
|
||||||
|
|
||||||
|
CONFIG_SPI_FLASH_ENABLE_ENCRYPTED_READ_WRITE=y
|
||||||
# end of SPI Flash driver
|
# end of SPI Flash driver
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -1141,6 +1346,12 @@ CONFIG_SPIFFS_USE_MTIME=y
|
||||||
# end of Debug Configuration
|
# end of Debug Configuration
|
||||||
# end of SPIFFS Configuration
|
# end of SPIFFS Configuration
|
||||||
|
|
||||||
|
#
|
||||||
|
# TCP Transport
|
||||||
|
#
|
||||||
|
CONFIG_WS_BUFFER_SIZE=1024
|
||||||
|
# end of TCP Transport
|
||||||
|
|
||||||
#
|
#
|
||||||
# Unity unit testing library
|
# Unity unit testing library
|
||||||
#
|
#
|
||||||
|
@ -1155,14 +1366,17 @@ CONFIG_UNITY_ENABLE_IDF_TEST_RUNNER=y
|
||||||
#
|
#
|
||||||
# Virtual file system
|
# 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_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
||||||
CONFIG_VFS_SUPPORT_TERMIOS=y
|
CONFIG_VFS_SUPPORT_TERMIOS=y
|
||||||
|
|
||||||
#
|
#
|
||||||
# Host File System I/O (Semihosting)
|
# Host File System I/O (Semihosting)
|
||||||
#
|
#
|
||||||
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||||
CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||||
# end of Host File System I/O (Semihosting)
|
# end of Host File System I/O (Semihosting)
|
||||||
# end of Virtual file system
|
# end of Virtual file system
|
||||||
|
|
||||||
|
@ -1185,7 +1399,11 @@ CONFIG_WIFI_PROV_AUTOSTOP_TIMEOUT=30
|
||||||
# Supplicant
|
# Supplicant
|
||||||
#
|
#
|
||||||
CONFIG_WPA_MBEDTLS_CRYPTO=y
|
CONFIG_WPA_MBEDTLS_CRYPTO=y
|
||||||
# CONFIG_WPA_TLS_V12 is not set
|
# 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
|
||||||
# end of Supplicant
|
# end of Supplicant
|
||||||
# end of Component config
|
# end of Component config
|
||||||
|
|
||||||
|
@ -1472,10 +1690,10 @@ CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32
|
||||||
CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2048
|
CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2048
|
||||||
CONFIG_MAIN_TASK_STACK_SIZE=3000
|
CONFIG_MAIN_TASK_STACK_SIZE=3000
|
||||||
CONFIG_IPC_TASK_STACK_SIZE=1024
|
CONFIG_IPC_TASK_STACK_SIZE=1024
|
||||||
CONFIG_TIMER_TASK_STACK_SIZE=2048
|
|
||||||
CONFIG_CONSOLE_UART_DEFAULT=y
|
CONFIG_CONSOLE_UART_DEFAULT=y
|
||||||
# CONFIG_CONSOLE_UART_CUSTOM is not set
|
# CONFIG_CONSOLE_UART_CUSTOM is not set
|
||||||
# CONFIG_CONSOLE_UART_NONE is not set
|
# CONFIG_ESP_CONSOLE_UART_NONE is not set
|
||||||
|
CONFIG_CONSOLE_UART=y
|
||||||
CONFIG_CONSOLE_UART_NUM=0
|
CONFIG_CONSOLE_UART_NUM=0
|
||||||
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
CONFIG_CONSOLE_UART_BAUDRATE=115200
|
||||||
CONFIG_INT_WDT=y
|
CONFIG_INT_WDT=y
|
||||||
|
@ -1487,11 +1705,20 @@ CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
|
||||||
# CONFIG_EVENT_LOOP_PROFILING is not set
|
# CONFIG_EVENT_LOOP_PROFILING is not set
|
||||||
CONFIG_POST_EVENTS_FROM_ISR=y
|
CONFIG_POST_EVENTS_FROM_ISR=y
|
||||||
CONFIG_POST_EVENTS_FROM_IRAM_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_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_TIMEOUT_MS_RESPOND=150
|
||||||
CONFIG_MB_MASTER_DELAY_MS_CONVERT=200
|
CONFIG_MB_MASTER_DELAY_MS_CONVERT=200
|
||||||
CONFIG_MB_QUEUE_LENGTH=20
|
CONFIG_MB_QUEUE_LENGTH=20
|
||||||
CONFIG_MB_SERIAL_TASK_STACK_SIZE=2048
|
CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096
|
||||||
CONFIG_MB_SERIAL_BUF_SIZE=256
|
CONFIG_MB_SERIAL_BUF_SIZE=256
|
||||||
CONFIG_MB_SERIAL_TASK_PRIO=10
|
CONFIG_MB_SERIAL_TASK_PRIO=10
|
||||||
# CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT is not set
|
# CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT is not set
|
||||||
|
@ -1502,7 +1729,6 @@ CONFIG_MB_EVENT_QUEUE_TIMEOUT=20
|
||||||
CONFIG_MB_TIMER_PORT_ENABLED=y
|
CONFIG_MB_TIMER_PORT_ENABLED=y
|
||||||
CONFIG_MB_TIMER_GROUP=0
|
CONFIG_MB_TIMER_GROUP=0
|
||||||
CONFIG_MB_TIMER_INDEX=0
|
CONFIG_MB_TIMER_INDEX=0
|
||||||
CONFIG_SUPPORT_STATIC_ALLOCATION=y
|
|
||||||
# CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set
|
# CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set
|
||||||
CONFIG_TIMER_TASK_PRIORITY=1
|
CONFIG_TIMER_TASK_PRIORITY=1
|
||||||
CONFIG_TIMER_TASK_STACK_DEPTH=2048
|
CONFIG_TIMER_TASK_STACK_DEPTH=2048
|
||||||
|
@ -1540,4 +1766,6 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y
|
||||||
# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED is not set
|
# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED is not set
|
||||||
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y
|
||||||
CONFIG_SUPPORT_TERMIOS=y
|
CONFIG_SUPPORT_TERMIOS=y
|
||||||
|
CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1
|
||||||
|
CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128
|
||||||
# End of deprecated options
|
# End of deprecated options
|
||||||
|
|
Ładowanie…
Reference in New Issue