kopia lustrzana https://github.com/pjalocha/esp32-ogn-tracker
Speed up GPS baudrate switching, print parameters as , cleanup of HTTP interface
rodzic
83a8585224
commit
14039f2f10
|
@ -81,11 +81,11 @@ class AXP192
|
|||
public:
|
||||
uint8_t Error; // error on the I2C bus (0=no error)
|
||||
|
||||
uint8_t checkID(void) // check ID, to make sure the AXP192 is reachable
|
||||
uint8_t checkID(void) // check ID, to make sure the AXP192 is reachable
|
||||
{ ADDR=0;
|
||||
Error=I2C_Read(Bus, AXP192_ADDR, REG_ID, ID);
|
||||
if( (!Error) && (ID==AXP192_ID) ) { ADDR=AXP192_ADDR; return 0; }
|
||||
return 1; } // 0 => no error and correct ID
|
||||
if( (!Error) && (ID==AXP192_ID) ) { ADDR=AXP192_ADDR; return 0; } // 0 => no error and correct ID
|
||||
return 1; } // 1 => error or incorrect chip ID
|
||||
|
||||
uint8_t readStatus(void)
|
||||
{ uint8_t Byte=0; Error=I2C_Read(Bus, ADDR, REG_STATUS, Byte); return Byte; }
|
||||
|
@ -243,15 +243,25 @@ class AXP192
|
|||
}
|
||||
return Error; }
|
||||
|
||||
bool readLongPressIRQ(void)
|
||||
uint8_t readIRQ1(void)
|
||||
{ uint8_t Byte=0;
|
||||
Error=I2C_Read(Bus, ADDR, REG_INTSTS1+2, Byte); if(Error) return 0;
|
||||
return Byte&0x01; }
|
||||
Error=I2C_Read(Bus, ADDR, REG_INTSTS1, Byte); if(Error) return 0;
|
||||
return Byte; }
|
||||
uint8_t readIRQ2(void)
|
||||
{ uint8_t Byte=0;
|
||||
Error=I2C_Read(Bus, ADDR, REG_INTSTS2, Byte); if(Error) return 0;
|
||||
return Byte; }
|
||||
uint8_t readIRQ3(void)
|
||||
{ uint8_t Byte=0;
|
||||
Error=I2C_Read(Bus, ADDR, REG_INTSTS3, Byte); if(Error) return 0;
|
||||
return Byte; }
|
||||
uint8_t readIRQ4(void)
|
||||
{ uint8_t Byte=0;
|
||||
Error=I2C_Read(Bus, ADDR, REG_INTSTS4, Byte); if(Error) return 0;
|
||||
return Byte; }
|
||||
|
||||
bool readShortPressIRQ(void)
|
||||
{ uint8_t Byte=0;
|
||||
Error=I2C_Read(Bus, ADDR, REG_INTSTS1+2, Byte); if(Error) return 0;
|
||||
return Byte&0x02; }
|
||||
bool readLongPressIRQ(void) { return readIRQ3()&0x01; }
|
||||
bool readShortPressIRQ(void) { return readIRQ3()&0x02; }
|
||||
|
||||
uint8_t clearIRQ(void)
|
||||
{ uint8_t Byte=0xFF;
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
|
||||
// #define DEBUG_PRINT
|
||||
|
||||
static char Line[128];
|
||||
static char Line[160];
|
||||
|
||||
// FIFO<uint8_t, 8> KeyBuffer;
|
||||
|
||||
|
@ -87,6 +87,20 @@ static void ReadParameters(void) // read parameters requested by the user in th
|
|||
// Format_String(CONS_UART_Write, "$POGNS[,<Name>=<Value>]\n");
|
||||
Parameters.WritePOGNS(Line);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
Parameters.WritePOGNS_Pilot(Line);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
Parameters.WritePOGNS_Acft(Line);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
Parameters.WritePOGNS_Comp(Line);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
#ifdef WITH_AP
|
||||
Parameters.WritePOGNS_AP(Line);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
#endif
|
||||
#ifdef WITH_STRATUX
|
||||
Parameters.WritePOGNS_Stratux(Line);
|
||||
Format_String(CONS_UART_Write, Line);
|
||||
#endif
|
||||
xSemaphoreGive(CONS_Mutex); //
|
||||
return; }
|
||||
Parameters.ReadPOGNS(NMEA);
|
||||
|
|
|
@ -431,7 +431,7 @@ static void LCD_UpdateRF(bool Redraw=0)
|
|||
Len+=Format_String(Line+Len, "SX1272");
|
||||
#endif
|
||||
Line[Len++]=':'; Line[Len++]=' ';
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)Parameters.getTxPower()); // Tx power
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)Parameters.TxPower); // Tx power
|
||||
Len+=Format_String(Line+Len, "dBm");
|
||||
Line[Len]=0;
|
||||
LCD_DrawString(Line, 4, PosY, RGB565_BLACK, RGB565_WHITE);
|
||||
|
|
|
@ -279,7 +279,7 @@ void OLED_DrawRF(u8g2_t *OLED, GPS_Position *GPS) // RF
|
|||
Len+=Format_String(Line+Len, "SX1272");
|
||||
#endif
|
||||
Line[Len++]=':';
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)Parameters.getTxPower()); // Tx power
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)Parameters.TxPower); // Tx power
|
||||
Len+=Format_String(Line+Len, "dBm");
|
||||
Line[Len++]=' ';
|
||||
Len+=Format_SignDec(Line+Len, (int32_t)Parameters.RFchipFreqCorr, 2, 1); // frequency correction
|
||||
|
|
27
main/gps.cpp
27
main/gps.cpp
|
@ -78,14 +78,23 @@ static union
|
|||
// for the autobaud on the GPS port
|
||||
const int GPS_BurstTimeout = 200; // [ms]
|
||||
|
||||
static const uint8_t BaudRates=7; // number of possible baudrates choices
|
||||
static uint8_t BaudRateIdx=0; // actual choice
|
||||
static const uint32_t BaudRate[BaudRates] = { 4800, 9600, 19200, 38400, 57600, 115200, 230400 } ; // list of baudrate the autobaud scans through
|
||||
// static const uint8_t BaudRates=7; // number of possible baudrates choices
|
||||
// static uint8_t BaudRateIdx=0; // actual choice
|
||||
// static const uint32_t BaudRate[BaudRates] = { 4800, 9600, 19200, 38400, 57600, 115200, 230400 } ; // list of baudrate the autobaud scans through
|
||||
|
||||
uint32_t GPS_getBaudRate (void) { return BaudRate[BaudRateIdx]; }
|
||||
uint32_t GPS_nextBaudRate(void) { BaudRateIdx++; if(BaudRateIdx>=BaudRates) BaudRateIdx=0; return GPS_getBaudRate(); }
|
||||
// uint32_t GPS_getBaudRate (void) { return BaudRate[BaudRateIdx]; }
|
||||
// uint32_t GPS_nextBaudRate(void) { BaudRateIdx++; if(BaudRateIdx>=BaudRates) BaudRateIdx=0; return GPS_getBaudRate(); }
|
||||
|
||||
const uint32_t GPS_TargetBaudRate = 57600; // BaudRate[4]; // [bps] must be one of the baud rates known by the autbaud
|
||||
static uint32_t GPS_BaudRate = 4800; // [bps]
|
||||
static uint32_t GPS_nextBaudRate(void)
|
||||
{ if(GPS_BaudRate>=230400) GPS_BaudRate=4800;
|
||||
else if(GPS_BaudRate==38400) GPS_BaudRate=57600;
|
||||
else GPS_BaudRate<<=1;
|
||||
return GPS_BaudRate; }
|
||||
|
||||
uint32_t GPS_getBaudRate (void) { return GPS_BaudRate; }
|
||||
|
||||
const uint32_t GPS_TargetBaudRate = 57600; // [bps]
|
||||
// const uint8_t GPS_TargetDynModel = 7; // for UBX GPS's: 6 = airborne with >1g, 7 = with >2g
|
||||
|
||||
#ifdef WITH_MAVLINK
|
||||
|
@ -377,6 +386,8 @@ static void GPS_BurstStart(void) // wh
|
|||
GPS_Cmd[Len]=0;
|
||||
Format_String(GPS_UART_Write, GPS_Cmd, Len, 0);
|
||||
#endif // WITH_GPS_SRF
|
||||
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
|
||||
}
|
||||
QueryWait=60;
|
||||
}
|
||||
|
@ -1006,8 +1017,8 @@ void vTaskGPS(void* pvParameters)
|
|||
GPS_Burst.Flags=0; // clear all flags: active and complete
|
||||
}
|
||||
|
||||
if(NoValidData>=2000) // if no valid data from GPS for 1sec
|
||||
{ GPS_Status.Flags=0; GPS_Burst.Flags=0; // assume GPS state is unknown
|
||||
if(NoValidData>=2000) // if no valid data from GPS for 2sec
|
||||
{ GPS_Status.Flags=0; GPS_Burst.Flags=0; // assume GPS state is unknown
|
||||
uint32_t NewBaudRate = GPS_nextBaudRate(); // switch to the next baud rate
|
||||
if(PowerMode>0)
|
||||
{
|
||||
|
|
13
main/hal.cpp
13
main/hal.cpp
|
@ -889,7 +889,8 @@ void AERO_UART_SetBaudrate(int BaudRate) { uart_set_baudrate(AERO_UART,
|
|||
// int GPS_UART_Full (void) { size_t Full=0; uart_get_buffered_data_len(GPS_UART, &Full); return Full; }
|
||||
int GPS_UART_Read (uint8_t &Byte) { return uart_read_bytes (GPS_UART, &Byte, 1, 0); } // should be buffered and non-blocking
|
||||
void GPS_UART_Write (char Byte) { uart_write_bytes (GPS_UART, &Byte, 1); } // should be buffered and blocking
|
||||
void GPS_UART_SetBaudrate(int BaudRate) { uart_set_baudrate(GPS_UART, BaudRate); }
|
||||
void GPS_UART_Flush (int MaxWait ) { uart_wait_tx_done(GPS_UART, MaxWait); }
|
||||
void GPS_UART_SetBaudrate(int BaudRate ) { uart_set_baudrate(GPS_UART, BaudRate); }
|
||||
#endif
|
||||
|
||||
#ifdef WITH_GPS_ENABLE
|
||||
|
@ -1810,6 +1811,16 @@ void IO_Configuration(void)
|
|||
#ifdef WITH_AXP
|
||||
gpio_set_direction(PIN_AXP_IRQ, GPIO_MODE_INPUT);
|
||||
AXP.Bus=(uint8_t)I2C_BUS;
|
||||
#ifdef DEBUG_PRINT
|
||||
xSemaphoreTake(CONS_Mutex, portMAX_DELAY);
|
||||
Format_String(CONS_UART_Write, "AXP192: ");
|
||||
Format_Hex(CONS_UART_Write, AXP.readIRQ1());
|
||||
Format_Hex(CONS_UART_Write, AXP.readIRQ2());
|
||||
Format_Hex(CONS_UART_Write, AXP.readIRQ3());
|
||||
Format_Hex(CONS_UART_Write, AXP.readIRQ4());
|
||||
Format_String(CONS_UART_Write, "\n");
|
||||
xSemaphoreGive(CONS_Mutex);
|
||||
#endif
|
||||
AXP.checkID();
|
||||
AXP.setPOK(0xDC); // power-on = 11 = 1sec, long-press = 01 = 1.5sec, power-off = enable, PWROK delay = 64ms, power-off = 00 = 4sec
|
||||
uint8_t PwrStatus = AXP.readStatus();
|
||||
|
|
|
@ -77,6 +77,7 @@ void CONS_UART_SetBaudrate(int BaudRate);
|
|||
|
||||
int GPS_UART_Read (uint8_t &Byte); // non-blocking
|
||||
void GPS_UART_Write (char Byte); // blocking
|
||||
void GPS_UART_Flush (int MaxWait ); // wait for data to be pushed out
|
||||
void GPS_UART_SetBaudrate(int BaudRate);
|
||||
|
||||
bool GPS_PPS_isOn(void);
|
||||
|
|
|
@ -152,7 +152,7 @@ static void ParmForm_Other(httpd_req_t *Req) // produce HTML form for aircraft
|
|||
httpd_resp_sendstr_chunk(Req, "</td></tr>\n");
|
||||
|
||||
httpd_resp_sendstr_chunk(Req, "<tr><td>Tx power [dBm]</td><td><input type=\"text\" name=\"TxPower\" size=\"10\" value=\"");
|
||||
Len=Format_SignDec(Line, (int16_t)Parameters.getTxPower());
|
||||
Len=Format_SignDec(Line, (int16_t)Parameters.TxPower);
|
||||
httpd_resp_send_chunk(Req, Line, Len);
|
||||
httpd_resp_sendstr_chunk(Req, "\"></td></tr>\n");
|
||||
|
||||
|
@ -402,7 +402,7 @@ static void Table_RF(httpd_req_t *Req)
|
|||
httpd_resp_send_chunk(Req, Line, Len);
|
||||
|
||||
Len =Format_String(Line, "<tr><td>Tx power</td><td align=\"right\">");
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)Parameters.getTxPower());
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)Parameters.TxPower);
|
||||
Len+=Format_String(Line+Len, "dBm</td></tr>\n");
|
||||
httpd_resp_send_chunk(Req, Line, Len);
|
||||
|
||||
|
|
|
@ -9,7 +9,7 @@ inline uint8_t NMEA_AppendCheck(char *NMEA, uint8_t Len) { return NMEA_AppendChe
|
|||
uint8_t NMEA_AppendCheckCRNL(uint8_t *NMEA, uint8_t Len);
|
||||
inline uint8_t NMEA_AppendCheckCRNL(char *NMEA, uint8_t Len) { return NMEA_AppendCheckCRNL((uint8_t*)NMEA, Len); }
|
||||
|
||||
class NMEA_RxMsg // receiver for the NMEA sentences
|
||||
class NMEA_RxMsg // receiver for the NMEA sentences
|
||||
{ public:
|
||||
static const uint8_t MaxLen=104; // maximum length
|
||||
static const uint8_t MaxParms=24; // maximum number of parameters (commas)
|
||||
|
@ -153,13 +153,13 @@ inline uint8_t NMEA_AppendCheckCRNL(char *NMEA, uint8_t Len) { return NMEA_Appen
|
|||
if(Data[4]!='S') return 0;
|
||||
return Data[5]=='A'; }
|
||||
|
||||
uint8_t isGxGSA(void) const //
|
||||
uint8_t isGxGSA(void) const // GP=GPS, GA=Galileo, GL=Glonass, GB=BaiDou, GN=any of the systems combined
|
||||
{ if(!isGx()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='S') return 0;
|
||||
return Data[5]=='A'; }
|
||||
|
||||
uint8_t isGxGSV(void) const // GPS satellite data
|
||||
uint8_t isGxGSV(void) const // Satellite data
|
||||
{ if(!isGx()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='S') return 0;
|
||||
|
@ -171,7 +171,7 @@ inline uint8_t NMEA_AppendCheckCRNL(char *NMEA, uint8_t Len) { return NMEA_Appen
|
|||
if(Data[4]!='S') return 0;
|
||||
return Data[5]=='V'; }
|
||||
|
||||
uint8_t isGNGSV(void) const // GPS satellite data
|
||||
uint8_t isGNGSV(void) const // Combined atellite data
|
||||
{ if(!isGN()) return 0;
|
||||
if(Data[3]!='G') return 0;
|
||||
if(Data[4]!='S') return 0;
|
||||
|
|
|
@ -40,9 +40,20 @@ class FlashParameters
|
|||
} ;
|
||||
} ;
|
||||
|
||||
int16_t RFchipFreqCorr; // [0.1ppm] frequency correction for crystal frequency offset
|
||||
int8_t RFchipTxPower; // [dBm] highest bit set => HW module (up to +20dBm Tx power)
|
||||
int8_t RFchipTempCorr; // [degC] correction to the temperature measured in the RF chip
|
||||
union
|
||||
{ uint32_t RFchip;
|
||||
struct
|
||||
{ int16_t RFchipFreqCorr: 12; // [0.1ppm] frequency correction for crystal frequency offset
|
||||
int8_t RFchipTempCorr: 4; // [degC] correction to the temperature measured in the RF chip
|
||||
int8_t TxPower: 6; // [dBm] highest bit set => HW module (up to +20dBm Tx power)
|
||||
bool RFchipTypeHW: 1; // is this RFM69HW (Tx power up to +20dBm) ?
|
||||
uint8_t FreqPlan: 3; // 0=default or force given frequency hopping plan
|
||||
} ;
|
||||
} ;
|
||||
|
||||
// int16_t RFchipFreqCorr; // [0.1ppm] frequency correction for crystal frequency offset
|
||||
// int8_t RFchipTxPower; // [dBm] highest bit set => HW module (up to +20dBm Tx power)
|
||||
// int8_t RFchipTempCorr; // [degC] correction to the temperature measured in the RF chip
|
||||
|
||||
union
|
||||
{ uint32_t Console;
|
||||
|
@ -61,18 +72,19 @@ class FlashParameters
|
|||
bool hasBT:1; // has BT interface on the console
|
||||
bool BT_ON:1; // BT on after power up
|
||||
bool manGeoidSepar:1; // GeoidSepar is manually configured as the GPS or MAVlink are not able to deliver it
|
||||
bool Encrypt:1; // encrypt the position
|
||||
bool Encrypt:1; // encrypt the position packets
|
||||
uint8_t NavMode:3; // GPS navigation mode/model
|
||||
uint8_t NavRate:2; // [Hz]
|
||||
uint8_t Verbose:2; //
|
||||
int8_t TimeCorr:4; // [sec] it appears for ArduPilot you need to correct time by 3 seconds
|
||||
uint8_t NavRate:3; // [Hz] GPS position report rate
|
||||
int8_t TimeCorr:3; // [sec] it appears for ArduPilot you need to correct time by 3 seconds which is likley the leap-second issue
|
||||
} ;
|
||||
} ; //
|
||||
|
||||
int16_t GeoidSepar; // [0.1m] Geoid-Separation, apparently ArduPilot MAVlink does not give this value (although present in the format)
|
||||
// or it could be a problem of some GPSes
|
||||
uint8_t PPSdelay; // [ms] delay between the PPS and the data burst starts on the GPS UART (used when PPS failed or is not there)
|
||||
uint8_t FreqPlan; // force given frequency hopping plan
|
||||
// uint8_t FreqPlan; // 0=default or force given frequency hopping plan
|
||||
uint8_t Spare;
|
||||
|
||||
static const uint8_t InfoParmLen = 16; // [char] max. size of an infp-parameter
|
||||
static const uint8_t InfoParmNum = 15; // [int] number of info-parameters
|
||||
|
@ -155,12 +167,12 @@ uint16_t StratuxPort;
|
|||
// static const uint32_t Words=sizeof(FlashParameters)/sizeof(uint32_t);
|
||||
|
||||
public:
|
||||
int8_t getTxPower(void) const { int8_t Pwr=RFchipTxPower&0x7F; if(Pwr&0x40) Pwr|=0x80; return Pwr; }
|
||||
void setTxPower(int8_t Pwr) { RFchipTxPower = (RFchipTxPower&0x80) | (Pwr&0x7F); }
|
||||
// int8_t getTxPower(void) const { int8_t Pwr=RFchipTxPower&0x7F; if(Pwr&0x40) Pwr|=0x80; return Pwr; }
|
||||
// void setTxPower(int8_t Pwr) { RFchipTxPower = (RFchipTxPower&0x80) | (Pwr&0x7F); }
|
||||
|
||||
void setTxTypeHW(void) { RFchipTxPower|=0x80; }
|
||||
void clrTxTypeHW(void) { RFchipTxPower&=0x7F; }
|
||||
bool isTxTypeHW(void) const { return RFchipTxPower& 0x80; } // if this RFM69HW (Tx power up to +20dBm) ?
|
||||
// void setTxTypeHW(void) { RFchipTxPower|=0x80; }
|
||||
// void clrTxTypeHW(void) { RFchipTxPower&=0x7F; }
|
||||
// bool isTxTypeHW(void) const { return RFchipTxPower& 0x80; } // if this RFM69HW (Tx power up to +20dBm) ?
|
||||
|
||||
static const uint32_t CheckInit = 0x89ABCDEF;
|
||||
|
||||
|
@ -205,9 +217,11 @@ uint16_t StratuxPort;
|
|||
{ AcftID = ((uint32_t)DEFAULT_AcftType<<26) | 0x03000000 | (UniqueAddr&0x00FFFFFF);
|
||||
RFchipFreqCorr = 0; // [0.1ppm]
|
||||
#ifdef WITH_RFM69W
|
||||
RFchipTxPower = 13; // [dBm] for RFM69W
|
||||
TxPower = 13; // [dBm] for RFM69W
|
||||
RFchipTypeHW = 0;
|
||||
#else
|
||||
RFchipTxPower = 0x80 | 14; // [dBm] for RFM69HW
|
||||
TxPower = 14; // [dBm] for RFM69HW
|
||||
RFchipTypeHW = 1;
|
||||
#endif
|
||||
|
||||
Flags = 0;
|
||||
|
@ -217,7 +231,7 @@ uint16_t StratuxPort;
|
|||
#ifdef WITH_GPS_MTK
|
||||
NavMode = 2; // 2 = Avionic mode for MTK
|
||||
#endif
|
||||
NavRate = 1; // [Hz]
|
||||
NavRate = 0; // [Hz] 0 = do not attempt to change the navigation rate
|
||||
GeoidSepar = 10*DEFAULT_GeoidSepar; // [0.1m]
|
||||
|
||||
Verbose = 1;
|
||||
|
@ -438,7 +452,7 @@ uint16_t StratuxPort;
|
|||
// { Line[Len++]='/'; Len+=Format_Hex(Line+Len, DefaultAddr, 6); }
|
||||
#ifdef WITH_RFM69
|
||||
Len+=Format_String(Line+Len, " RFM69");
|
||||
if(isTxTypeHW()) Line[Len++]='H';
|
||||
if(RFchipTypeHW) Line[Len++]='H';
|
||||
Line[Len++]='W';
|
||||
#endif
|
||||
#ifdef WITH_RFM95
|
||||
|
@ -448,7 +462,7 @@ uint16_t StratuxPort;
|
|||
Len+=Format_String(Line+Len, " SX1272");
|
||||
#endif
|
||||
Line[Len++]='/';
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)getTxPower());
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)TxPower);
|
||||
Len+=Format_String(Line+Len, "dBm");
|
||||
Line[Len++]=' '; Len+=Format_SignDec(Line+Len, (int32_t)RFchipFreqCorr, 2, 1); Len+=Format_String(Line+Len, "ppm");
|
||||
Len+=Format_String(Line+Len, " CON:");
|
||||
|
@ -471,13 +485,81 @@ uint16_t StratuxPort;
|
|||
Line[Len++]=HexDigit(AcftType);
|
||||
Len+=Format_String(Line+Len, ",FreqPlan=");
|
||||
Line[Len++]='0'+FreqPlan;
|
||||
Len+=Format_String(Line+Len, ",Pilot=");
|
||||
Len+=NMEA_AppendCheckCRNL(Line, Len);
|
||||
Line[Len]=0; return Len; }
|
||||
|
||||
uint8_t WritePOGNS_Pilot(char *Line)
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_String(Line+Len, "$POGNS,Pilot=");
|
||||
Len+=Format_String(Line+Len, Pilot);
|
||||
Len+=Format_String(Line+Len, ",Crew=");
|
||||
Len+=Format_String(Line+Len, Crew);
|
||||
Len+=Format_String(Line+Len, ",Reg=");
|
||||
Len+=Format_String(Line+Len, Reg);
|
||||
Len+=Format_String(Line+Len, ",Base=");
|
||||
Len+=Format_String(Line+Len, Base);
|
||||
Len+=NMEA_AppendCheckCRNL(Line, Len);
|
||||
Line[Len]=0;
|
||||
return Len; }
|
||||
Line[Len]=0; return Len; }
|
||||
|
||||
uint8_t WritePOGNS_Acft(char *Line)
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_String(Line+Len, "$POGNS,Manuf=");
|
||||
Len+=Format_String(Line+Len, Manuf);
|
||||
Len+=Format_String(Line+Len, ",Model=");
|
||||
Len+=Format_String(Line+Len, Model);
|
||||
Len+=Format_String(Line+Len, ",Type=");
|
||||
Len+=Format_String(Line+Len, Type);
|
||||
Len+=Format_String(Line+Len, ",SN=");
|
||||
Len+=Format_String(Line+Len, SN);
|
||||
Len+=NMEA_AppendCheckCRNL(Line, Len);
|
||||
Line[Len]=0; return Len; }
|
||||
|
||||
uint8_t WritePOGNS_Comp(char *Line)
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_String(Line+Len, "$POGNS,Class=");
|
||||
Len+=Format_String(Line+Len, Class);
|
||||
Len+=Format_String(Line+Len, ",ID=");
|
||||
Len+=Format_String(Line+Len, ID);
|
||||
Len+=Format_String(Line+Len, ",Task=");
|
||||
Len+=Format_String(Line+Len, Task);
|
||||
Len+=NMEA_AppendCheckCRNL(Line, Len);
|
||||
Line[Len]=0; return Len; }
|
||||
|
||||
#ifdef WITH_AP
|
||||
uint8_t WritePOGNS_AP(char *Line)
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_String(Line+Len, "$POGNS,APname=");
|
||||
Len+=Format_String(Line+Len, APname);
|
||||
Len+=Format_String(Line+Len, ",APass=");
|
||||
Len+=Format_String(Line+Len, APpass);
|
||||
Len+=Format_String(Line+Len, ",APport=");
|
||||
Len+=Format_UnsDec(Line+Len, APport);
|
||||
Len+=Format_String(Line+Len, ",APtxPwr=");
|
||||
Len+=Format_SignDec(Line+Len, ((int16_t)10*APtxPwr+2)>>2, 2, 1);
|
||||
Len+=Format_String(Line+Len, ",APminSig=");
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)APminSig);
|
||||
Len+=NMEA_AppendCheckCRNL(Line, Len);
|
||||
Line[Len]=0; return Len; }
|
||||
#endif
|
||||
|
||||
#ifdef WITH_STRATUX
|
||||
uint8_t WritePOGNS_Stratux(char *Line)
|
||||
{ uint8_t Len=0;
|
||||
Len+=Format_String(Line+Len, "$POGNS,StratuxWIFI=");
|
||||
Len+=Format_String(Line+Len, StratuxWIFI);
|
||||
Len+=Format_String(Line+Len, ",StratuxPass=");
|
||||
Len+=Format_String(Line+Len, StratuxPass);
|
||||
Len+=Format_String(Line+Len, ",StratuxHost=");
|
||||
Len+=Format_String(Line+Len, StratuxHost);
|
||||
Len+=Format_String(Line+Len, ",StratuxPort=");
|
||||
Len+=Format_UnsDec(Line+Len, StratuxPort);
|
||||
Len+=Format_String(Line+Len, ",StratuxTxPwr=");
|
||||
Len+=Format_SignDec(Line+Len, ((int16_t)10*StratuxTxPwr+2)>>2, 2, 1);
|
||||
Len+=Format_String(Line+Len, ",StratuxMinSig=");
|
||||
Len+=Format_SignDec(Line+Len, (int16_t)StratuxMinSig);
|
||||
Len+=NMEA_AppendCheckCRNL(Line, Len);
|
||||
Line[Len]=0; return Len; }
|
||||
#endif
|
||||
|
||||
int ReadPOGNS(NMEA_RxMsg &NMEA)
|
||||
{ int Count=0;
|
||||
|
@ -530,10 +612,10 @@ uint16_t StratuxPort;
|
|||
CONprot=Prot; return 1; }
|
||||
if(strcmp(Name, "TxHW")==0)
|
||||
{ int32_t HW=1; if(Read_Int(HW, Value)<=0) return 0;
|
||||
if(HW) setTxTypeHW(); else clrTxTypeHW(); }
|
||||
RFchipTypeHW=HW; }
|
||||
if(strcmp(Name, "TxPower")==0)
|
||||
{ int32_t TxPower=0; if(Read_Int(TxPower, Value)<=0) return 0;
|
||||
setTxPower(TxPower); return 1; }
|
||||
{ int32_t Power=0; if(Read_Int(Power, Value)<=0) return 0;
|
||||
TxPower=Power; return 1; }
|
||||
if(strcmp(Name, "PPSdelay")==0)
|
||||
{ uint32_t Delay=0; if(Read_Int(Delay, Value)<=0) return 0;
|
||||
if(Delay>0xFF) Delay=0xFF; PPSdelay=Delay; return 1; }
|
||||
|
@ -559,7 +641,7 @@ uint16_t StratuxPort;
|
|||
NavMode=Mode; return 1; }
|
||||
if(strcmp(Name, "NavRate")==0)
|
||||
{ int32_t Mode=0; if(Read_Int(Mode, Value)<=0) return 0;
|
||||
if(Mode<1) Mode=1; NavRate=Mode; return 1; }
|
||||
if(Mode<0) Mode=0; NavRate=Mode; return 1; }
|
||||
if(strcmp(Name, "PageMask")==0)
|
||||
{ int32_t Mode=0; if(Read_Int(Mode, Value)<=0) return 0;
|
||||
PageMask=Mode; return 1; }
|
||||
|
@ -724,8 +806,8 @@ uint16_t StratuxPort;
|
|||
Write_Hex (Line, "AcftType" , AcftType, 1); strcat(Line, " # [4-bit]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_UnsDec (Line, "CONbaud" , CONbaud ); strcat(Line, " # [ bps]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_Hex (Line, "CONprot" , CONprot, 1); strcat(Line, " # [ mask]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_SignDec(Line, "TxPower" , getTxPower() ); strcat(Line, " # [ dBm]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_UnsDec (Line, "TxHW" ,(uint32_t)isTxTypeHW() ); strcat(Line, " # [ bool]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_SignDec(Line, "TxPower" , TxPower ); strcat(Line, " # [ dBm]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_UnsDec (Line, "TxHW" ,(uint32_t)RFchipTypeHW ); strcat(Line, " # [ bool]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_UnsDec (Line, "FreqPlan" ,(uint32_t)FreqPlan ); strcat(Line, " # [ 0..5]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_Float1 (Line, "FreqCorr" , (int32_t)RFchipFreqCorr ); strcat(Line, " # [ ppm]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
Write_SignDec(Line, "TempCorr" , (int32_t)RFchipTempCorr ); strcat(Line, " # [ degC]\n"); if(fputs(Line, File)==EOF) return EOF;
|
||||
|
@ -789,8 +871,8 @@ uint16_t StratuxPort;
|
|||
Write_Hex (Line, "AcftType" , AcftType, 1); strcat(Line, " # [4-bit]\n"); Format_String(Output, Line);
|
||||
Write_UnsDec (Line, "CONbaud" , CONbaud ); strcat(Line, " # [ bps]\n"); Format_String(Output, Line);
|
||||
Write_Hex (Line, "CONprot" , CONprot, 1); strcat(Line, " # [ mask]\n"); Format_String(Output, Line);
|
||||
Write_SignDec(Line, "TxPower" , getTxPower() ); strcat(Line, " # [ dBm]\n"); Format_String(Output, Line);
|
||||
Write_UnsDec (Line, "TxHW" ,(uint32_t)isTxTypeHW() ); strcat(Line, " # [ bool]\n"); Format_String(Output, Line);
|
||||
Write_SignDec(Line, "TxPower" , TxPower ); strcat(Line, " # [ dBm]\n"); Format_String(Output, Line);
|
||||
Write_UnsDec (Line, "TxHW" ,(uint32_t)RFchipTypeHW ); strcat(Line, " # [ bool]\n"); Format_String(Output, Line);
|
||||
Write_UnsDec (Line, "FreqPlan" ,(uint32_t)FreqPlan ); strcat(Line, " # [ 0..5]\n"); Format_String(Output, Line);
|
||||
Write_Float1 (Line, "FreqCorr" , (int32_t)RFchipFreqCorr ); strcat(Line, " # [ ppm]\n"); Format_String(Output, Line);
|
||||
Write_SignDec(Line, "TempCorr" , (int32_t)RFchipTempCorr ); strcat(Line, " # [ degC]\n"); Format_String(Output, Line);
|
||||
|
|
|
@ -253,7 +253,7 @@ static void ReadStatus(OGN_Packet &Packet)
|
|||
if(Packet.Status.Pressure==0) Packet.EncodeTemperature(TRX.chipTemp*10); // [0.1degC]
|
||||
Packet.Status.RadioNoise = TRX.averRSSI; // [-0.5dBm] write radio noise to the status packet
|
||||
|
||||
uint8_t TxPower = Parameters.getTxPower()-4;
|
||||
uint8_t TxPower = Parameters.TxPower-4;
|
||||
if(TxPower>15) TxPower=15;
|
||||
Packet.Status.TxPower = TxPower;
|
||||
|
||||
|
|
10
main/rf.cpp
10
main/rf.cpp
|
@ -61,10 +61,10 @@ static uint8_t RX_Channel=0; // (hopping) channel currently being
|
|||
static void SetTxChannel(uint8_t TxChan=RX_Channel) // default channel to transmit is same as the receive channel
|
||||
{
|
||||
#ifdef WITH_RFM69
|
||||
TRX.WriteTxPower(Parameters.getTxPower(), Parameters.isTxTypeHW()); // set TX for transmission
|
||||
TRX.WriteTxPower(Parameters.TxPower, Parameters.isTxTypeHW()); // set TX for transmission
|
||||
#endif
|
||||
#if defined(WITH_RFM95) || defined(WITH_SX1272)
|
||||
TRX.WriteTxPower(Parameters.getTxPower()); // set TX for transmission
|
||||
TRX.WriteTxPower(Parameters.TxPower); // set TX for transmission
|
||||
#endif
|
||||
TRX.setChannel(TxChan&0x7F);
|
||||
TRX.FSK_WriteSYNC(8, 7, OGN_SYNC); } // Full SYNC for TX
|
||||
|
@ -432,7 +432,7 @@ extern "C"
|
|||
Packet.setCRC();
|
||||
TRX.WriteMode(RF_OPMODE_STANDBY);
|
||||
TRX.PAW_Configure(PAW_SYNC);
|
||||
TRX.WriteTxPower(Parameters.getTxPower());
|
||||
TRX.WriteTxPower(Parameters.TxPower);
|
||||
TRX.WritePacketPAW(Packet.Byte, 24);
|
||||
TRX.WriteMode(RF_OPMODE_TRANSMITTER);
|
||||
vTaskDelay(10);
|
||||
|
@ -446,7 +446,7 @@ extern "C"
|
|||
{ TRX.setLoRa(); // switch TRX to LoRa
|
||||
TRX.FNT_Configure(); // configure for FANET
|
||||
// TRX.setChannel(0); // configure for FANET
|
||||
TRX.WriteTxPower(Parameters.getTxPower()); // transmission power
|
||||
TRX.WriteTxPower(Parameters.TxPower); // transmission power
|
||||
TRX.WriteMode(RF_OPMODE_LORA_RX_CONT); // continous receiver mode
|
||||
vTaskDelay(2);
|
||||
for(uint8_t Wait=50; Wait; Wait--) //
|
||||
|
@ -512,7 +512,7 @@ extern "C"
|
|||
WANdev.Chan = RX_Random&7; // choose random channel
|
||||
TRX.setChannel(WANdev.Chan); // set the channel
|
||||
TRX.LoRa_InvertIQ(0); TRX.LoRa_setCRC(1); // setup for WAN TX
|
||||
TRX.WriteTxPower(Parameters.getTxPower()); // transmit power
|
||||
TRX.WriteTxPower(Parameters.TxPower); // transmit power
|
||||
int RespDelay=0;
|
||||
int TxPktLen=0;
|
||||
if(WANdev.State==0)
|
||||
|
|
Ładowanie…
Reference in New Issue