Pawel Jalocha 2019-05-02 00:54:18 +00:00
commit 38173f17a8
5 zmienionych plików z 160 dodań i 42 usunięć

Wyświetl plik

@ -9,6 +9,7 @@
#include "hal.h"
#include "rf.h"
#include "ctrl.h"
#include "log.h"
@ -19,6 +20,8 @@
// #define DEBUG_PRINT
static char Line[128];
// ========================================================================================================================
void PrintTasks(void (*CONS_UART_Write)(char))
@ -51,8 +54,7 @@ void PrintTasks(void (*CONS_UART_Write)(char))
#ifdef WITH_OLED
int OLED_DisplayStatus(uint32_t Time, uint8_t LineIdx=0)
{ char Line[20];
Format_String(Line , "OGN Tx/Rx ");
{ Format_String(Line , "OGN Tx/Rx ");
Format_HHMMSS(Line+10, Time);
OLED_PutLine(LineIdx++, Line);
Parameters.Print(Line);
@ -60,8 +62,7 @@ int OLED_DisplayStatus(uint32_t Time, uint8_t LineIdx=0)
return 0; }
int OLED_DisplayPosition(GPS_Position *GPS=0, uint8_t LineIdx=2)
{ char Line[20];
if(GPS && GPS->isValid())
{ if(GPS && GPS->isValid())
{ Line[0]=' ';
Format_SignDec(Line+1, GPS->Latitude /60, 6, 4); Line[9]=' ';
Format_UnsDec (Line+10, GPS->Altitude /10, 5, 0); Line[15]='m';
@ -117,16 +118,14 @@ void OLED_PutLine(u8g2_t *OLED, uint8_t LineIdx, const char *Line)
}
void OLED_DrawStatus(u8g2_t *OLED, uint32_t Time, uint8_t LineIdx=0)
{ char Line[32];
Format_String(Line , "OGN Tx/Rx ");
{ Format_String(Line , "OGN Tx/Rx ");
Format_HHMMSS(Line+10, Time); Line[16]=0;
OLED_PutLine(OLED, LineIdx++, Line);
Parameters.Print(Line); Line[16]=0;
OLED_PutLine(OLED, LineIdx++, Line); }
void OLED_DrawPosition(u8g2_t *OLED, GPS_Position *GPS=0, uint8_t LineIdx=2)
{ char Line[20];
if(GPS && GPS->isValid())
{ if(GPS && GPS->isValid())
{ Line[0]=' ';
Format_SignDec(Line+1, GPS->Latitude /60, 6, 4); Line[9]=' ';
Format_UnsDec (Line+10, GPS->Altitude /10, 5, 0); Line[15]='m';
@ -162,24 +161,122 @@ void OLED_DrawPosition(u8g2_t *OLED, GPS_Position *GPS=0, uint8_t LineIdx=2)
OLED_PutLine(OLED, LineIdx+5, Line);
}
void OLED_DrawGPS(u8g2_t *OLED)
{ u8g2_SetFont(OLED, u8g2_font_ncenB14_tr);
u8g2_DrawStr(OLED, 0, 16, "GPS");
void OLED_DrawGPS(u8g2_t *OLED, GPS_Position *GPS=0)
{ // u8g2_SetFont(OLED, u8g2_font_ncenB14_tr);
u8g2_SetFont(OLED, u8g2_font_7x13_tf);
uint8_t Len=0;
Len+=Format_String(Line+Len, "GPS ");
#ifdef WITH_GPS_UBX
Len+=Format_String(Line+Len, "UBX ");
#endif
#ifdef WITH_GPS_MTK
Len+=Format_String(Line+Len, "MTK ");
#endif
#ifdef WITH_GPS_SRF
Len+=Format_String(Line+Len, "SRF ");
#endif
Len+=Format_UnsDec(Line+Len, GPS_getBaudRate(), 1);
Len+=Format_String(Line+Len, "bps");
Line[Len]=0;
u8g2_DrawStr(OLED, 0, 12, Line);
if(GPS && GPS->isDateValid())
{ Format_UnsDec (Line , (uint16_t)GPS->Day, 2, 0); Line[2]='.';
Format_UnsDec (Line+ 3, (uint16_t)GPS->Month, 2, 0); Line[5]='.';
Format_UnsDec (Line+ 6, (uint16_t)GPS->Year , 2, 0); Line[8]=' ';
} else Format_String(Line, " . . ");
if(GPS && GPS->isTimeValid())
{ Format_UnsDec (Line+ 9, (uint16_t)GPS->Hour, 2, 0); Line[11]=':';
Format_UnsDec (Line+12, (uint16_t)GPS->Min, 2, 0); Line[14]=':';
Format_UnsDec (Line+15, (uint16_t)GPS->Sec, 2, 0);
} else Format_String(Line+9, " : : ");
Line[17]=0;
u8g2_DrawStr(OLED, 0, 24, Line);
Len=0;
Len+=Format_String(Line+Len, "Lat: ");
if(GPS && GPS->isValid())
{ Len+=Format_SignDec(Line+Len, GPS->Latitude /6, 7, 5);
Line[Len++]=0xB0; }
Line[Len]=0;
u8g2_DrawStr(OLED, 0, 36, Line);
Len=0;
Len+=Format_String(Line+Len, "Lon: ");
if(GPS && GPS->isValid())
{ Len+=Format_SignDec(Line+Len, GPS->Longitude /6, 8, 5);
Line[Len++]=0xB0; }
Line[Len]=0;
u8g2_DrawStr(OLED, 0, 48, Line);
Len=0;
Len+=Format_String(Line+Len, "Alt: ");
if(GPS && GPS->isValid())
{ Len+=Format_SignDec(Line+Len, GPS->Altitude, 4, 1);
Line[Len++]='m'; }
Line[Len]=0;
u8g2_DrawStr(OLED, 0, 60, Line);
}
void OLED_DrawRF(u8g2_t *OLED)
{ u8g2_SetFont(OLED, u8g2_font_ncenB14_tr);
u8g2_DrawStr(OLED, 0, 16, "RF");
{ u8g2_SetFont(OLED, u8g2_font_7x13_tf);
uint8_t Len=0;
#ifdef WITH_RFM69
Len+=Format_String(Line+Len, "RFM69");
if(isTxTypeHW()) Line[Len++]='H';
Line[Len++]='W';
#endif
#ifdef WITH_RFM95
Len+=Format_String(Line+Len, "RFM95");
#endif
#ifdef WITH_SX1272
Len+=Format_String(Line+Len, "SX1272");
#endif
Line[Len++]=':';
Len+=Format_SignDec(Line+Len, (int16_t)Parameters.getTxPower());
Len+=Format_String(Line+Len, "dBm");
Line[Len++]=' ';
Len+=Format_SignDec(Line+Len, (int32_t)Parameters.RFchipFreqCorr, 2, 1);
Len+=Format_String(Line+Len, "ppm");
Line[Len]=0;
u8g2_DrawStr(OLED, 0, 12, Line);
Len=0;
Len+=Format_String(Line+Len, "Rx:");
Len+=Format_SignDec(Line+Len, -5*RX_AverRSSI, 2, 1);
Len+=Format_String(Line+Len, "dBm ");
Len+=Format_UnsDec(Line+Len, RX_OGN_Count64);
Len+=Format_String(Line+Len, "/min");
Line[Len]=0;
u8g2_DrawStr(OLED, 0, 24, Line);
Len=0;
Len+=Format_SignDec(Line+Len, (int16_t)RF_Temp);
Line[Len++]=0xB0;
Line[Len++]='C';
Line[Len]=0;
u8g2_DrawStr(OLED, 0, 36, Line);
// u8g2_DrawStr(OLED, 0, 48, RF_FreqPlan.getPlanName());
Len=0;
Len+=Format_String(Line+Len, RF_FreqPlan.getPlanName());
Line[Len++]=' ';
Len+=Format_UnsDec(Line+Len, (uint16_t)(RF_FreqPlan.getCenterFreq()/100000), 3, 1);
Len+=Format_String(Line+Len, "MHz");
Line[Len]=0;
u8g2_DrawStr(OLED, 0, 48, Line);
}
void OLED_DrawBARO(u8g2_t *OLED)
void OLED_DrawBaro(u8g2_t *OLED)
{ u8g2_SetFont(OLED, u8g2_font_ncenB14_tr);
u8g2_DrawStr(OLED, 0, 16, "Baro");
// #ifdef WITH_BMP180
u8g2_DrawStr(OLED, 0, 16, "Baro");
// #endif
}
void OLED_DrawSYS(u8g2_t *OLED)
void OLED_DrawSystem(u8g2_t *OLED)
{ u8g2_SetFont(OLED, u8g2_font_ncenB14_tr);
u8g2_DrawStr(OLED, 0, 16, "SYS");
u8g2_DrawStr(OLED, 0, 16, "System");
}
void OLED_DrawConfig(u8g2_t *OLED)
{ u8g2_SetFont(OLED, u8g2_font_timR18_tr);
Parameters.Print(Line); Line[10]=0;
u8g2_DrawStr(OLED, 0, 20, Line);
}
#endif
@ -191,8 +288,6 @@ static NMEA_RxMsg NMEA;
static UBX_RxMsg UBX;
#endif
static char Line[128];
static void PrintParameters(void) // print parameters stored in Flash
{ Parameters.Print(Line);
xSemaphoreTake(CONS_Mutex, portMAX_DELAY); // ask exclusivity on UART1
@ -360,8 +455,8 @@ static void ProcessInput(void)
// ========================================================================================================================
const uint8_t OLED_Pages = 5;
static uint8_t OLED_Page=0;
const uint8_t OLED_Pages = 6;
static uint8_t OLED_Page = 1;
extern "C"
void vTaskCTRL(void* pvParameters)
@ -430,10 +525,11 @@ void vTaskCTRL(void* pvParameters)
else if(TimeChange || PageChange)
{ u8g2_ClearBuffer(&U8G2_OLED);
switch(OLED_Page)
{ case 1: OLED_DrawGPS(&U8G2_OLED); break;
{ case 1: OLED_DrawGPS(&U8G2_OLED, GPS); break;
case 2: OLED_DrawRF(&U8G2_OLED); break;
case 3: OLED_DrawBARO(&U8G2_OLED); break;
case 4: OLED_DrawSYS(&U8G2_OLED); break;
case 3: OLED_DrawBaro(&U8G2_OLED); break;
case 4: OLED_DrawConfig(&U8G2_OLED); break;
case 5: OLED_DrawSystem(&U8G2_OLED); break;
default:
{ OLED_DrawStatus(&U8G2_OLED, Time, 0);
OLED_DrawPosition(&U8G2_OLED, GPS, 2); }

Wyświetl plik

@ -26,9 +26,10 @@ class FreqPlan
{ setPlan(calcPlan(Latitude, Longitude)); }
const char *getPlanName(void) { return getPlanName(Plan); }
uint32_t getCenterFreq(void) { return BaseFreq + ChanSepar/2*(Channels-1); }
static const char *getPlanName(uint8_t Plan)
{ static const char *Name[6] = { "Default", "Europe/Africa", "USA/Canada", "Australia/South America", "New Zeeland", "Europe/Africa 434MHz" } ;
{ static const char *Name[6] = { "Default", "EU/Africa", "USA/Canada", "Australia/Chile", "New Zeeland", "EU/Africa 434MHz" } ;
if(Plan>=6) return 0;
return Name[Plan]; }

Wyświetl plik

@ -219,10 +219,10 @@ GPIO HELTEC TTGO JACEK T-Beam FollowMe Restrictions
#define RFM_SPI_SPEED 4000000 // [Hz] 4MHz SPI clock rate for RF chip
#if defined(WITH_HELTEC) || defined(WITH_TTGO)
// VK2828U GN-801 MAVlink
#define PIN_GPS_TXD GPIO_NUM_12 // green green green
#define PIN_GPS_RXD GPIO_NUM_35 // blue yellow yellow
#define PIN_GPS_PPS GPIO_NUM_34 // white blue
// VK2828U GN-801 GG-1802 MAVlink
#define PIN_GPS_TXD GPIO_NUM_12 // green green blue green
#define PIN_GPS_RXD GPIO_NUM_35 // blue yellow green yellow
#define PIN_GPS_PPS GPIO_NUM_34 // white blue yellow
#define PIN_GPS_ENA GPIO_NUM_13 // yellow white
#endif // HELTEC || TTGO

Wyświetl plik

@ -261,7 +261,8 @@ class FlashParameters
Line[Len++]='/';
Len+=Format_SignDec(Line+Len, (int16_t)getTxPower());
Len+=Format_String(Line+Len, "dBm");
Line[Len++]=' '; Len+=Format_SignDec(Line+Len, (int32_t)RFchipFreqCorr, 2, 1); Len+=Format_String(Line+Len, "ppm");
Line[Len++]=' '; Len+=Format_SignDec(Line+Len, (int32_t)RFchipFreqCorr, 2, 1);
Len+=Format_String(Line+Len, "ppm");
Len+=Format_String(Line+Len, " CON:");
Len+=Format_UnsDec(Line+Len, CONbaud);
Len+=Format_String(Line+Len, "bps\n");

Wyświetl plik

@ -73,19 +73,19 @@ static void PrintRelayQueue(uint8_t Idx) // for debug
#endif
static bool GetRelayPacket(OGN_TxPacket<OGN_Packet> *Packet) // prepare a packet to be relayed
{ if(RelayQueue.Sum==0) return 0;
XorShift32(RX_Random);
uint8_t Idx=RelayQueue.getRand(RX_Random);
if(RelayQueue.Packet[Idx].Rank==0) return 0;
memcpy(Packet->Packet.Byte(), RelayQueue[Idx]->Byte(), OGN_Packet::Bytes);
Packet->Packet.Header.Relay=1;
Packet->Packet.Whiten(); Packet->calcFEC();
{ if(RelayQueue.Sum==0) return 0; // if no packets in the relay queue
XorShift32(RX_Random); // produce a new random number
uint8_t Idx=RelayQueue.getRand(RX_Random); // get weight-random packet from the relay queue
if(RelayQueue.Packet[Idx].Rank==0) return 0; // should not happen ...
memcpy(Packet->Packet.Byte(), RelayQueue[Idx]->Byte(), OGN_Packet::Bytes); // copy the packet
Packet->Packet.Header.Relay=1; // increment the relay count (in fact we only do single relay)
Packet->Packet.Whiten(); Packet->calcFEC(); // whiten and calc. the FEC code => packet ready for transmission
// PrintRelayQueue(Idx); // for debug
RelayQueue.decrRank(Idx);
RelayQueue.decrRank(Idx); // reduce the rank of the packet selected for relay
return 1; }
static void CleanRelayQueue(uint32_t Time, uint32_t Delay=20)
{ RelayQueue.cleanTime((Time-Delay)%60); }
static void CleanRelayQueue(uint32_t Time, uint32_t Delay=20) // remove "old" packets from the relay queue
{ RelayQueue.cleanTime((Time-Delay)%60); } // remove packets 20(default) seconds into the past
// ---------------------------------------------------------------------------------------------------------------------------------------
@ -211,12 +211,32 @@ static void ReadStatus(OGN_Packet &Packet)
// static void ReadStatus(OGN_TxPacket<OGN_Packet> &StatPacket)
// { ReadStatus(StatPacket.Packet); }
// ---------------------------------------------------------------------------------------------------------------------------------------
static uint8_t WritePFLAU(char *NMEA, uint8_t GPS=1) // produce the (mostly dummy) PFLAU to satisfy XCsoar and LK8000
{ uint8_t Len=0;
Len+=Format_String(NMEA+Len, "$PFLAU,");
NMEA[Len++]='0';
NMEA[Len++]=',';
NMEA[Len++]='0'+GPS; // TX status
NMEA[Len++]=',';
NMEA[Len++]='0'+GPS; // GPS status
NMEA[Len++]=',';
NMEA[Len++]='1'; // power status: one could monitor the supply
NMEA[Len++]=',';
NMEA[Len++]='0';
NMEA[Len++]=',';
NMEA[Len++]=',';
NMEA[Len++]='0';
NMEA[Len++]=',';
NMEA[Len++]=',';
Len+=NMEA_AppendCheckCRNL(NMEA, Len);
NMEA[Len]=0;
return Len; }
// ---------------------------------------------------------------------------------------------------------------------------------------
static void ProcessRxPacket(OGN_RxPacket<OGN_Packet> *RxPacket, uint8_t RxPacketIdx, uint32_t RxTime) // process every (correctly) received packet
{ int32_t LatDist=0, LonDist=0; uint8_t Warn=0;
if( RxPacket->Packet.Header.NonPos /* || RxPacket->Packet.Header.Encrypted */ ) return ; // status packet or encrypted: ignore
if( RxPacket->Packet.Header.NonPos || RxPacket->Packet.Header.Encrypted ) return ; // status packet or encrypted: ignore
uint8_t MyOwnPacket = ( RxPacket->Packet.Header.Address == Parameters.Address )
&& ( RxPacket->Packet.Header.AddrType == Parameters.AddrType );
if(MyOwnPacket) return; // don't process my own (relayed) packets