read config from config.txt, configurable display ports
This commit is contained in:
parent
63abbe9a2c
commit
500679bdc5
14
README.md
14
README.md
|
|
@ -46,17 +46,5 @@ spectrum diagram (each line == 50 kHz)
|
|||
|
||||
## Setup
|
||||
|
||||
Download https://github.com/me-no-dev/ESPAsyncWebServer/archive/master.zip
|
||||
and move to your Arduino IDE's libraries directory
|
||||
Rename to (name without "-master")
|
||||
|
||||
Download https://github.com/me-no-dev/AsyncTCP/archive/master.zip
|
||||
and move to your Arduino IDE's libraries directory
|
||||
Rename to (name without "-master")
|
||||
|
||||
Install Arduino ESP32 file system uploader
|
||||
https://randomnerdtutorials.com/install-esp32-filesystem-uploader-arduino-ide/
|
||||
Download https://github.com/me-no-dev/arduino-esp32fs-plugin/releases/download/1.0/ESP32FS-1.0.zip
|
||||
Move to your Arduino IDE's tools directory
|
||||
|
||||
see Setup.md
|
||||
|
||||
|
|
|
|||
|
|
@ -18,7 +18,8 @@
|
|||
#define OLED_RST 16
|
||||
|
||||
// UNCOMMENT one of the constructor lines below
|
||||
U8X8_SSD1306_128X64_NONAME_SW_I2C u8x8(/* clock=*/ OLED_SCL, /* data=*/ OLED_SDA, /* reset=*/ OLED_RST); // Unbuffered, basic graphics, software I2C
|
||||
U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8=NULL; // initialize later after reading config file
|
||||
//U8X8_SSD1306_128X64_NONAME_SW_I2C u8x8(/* clock=*/ OLED_SCL, /* data=*/ OLED_SDA, /* reset=*/ OLED_RST); // Unbuffered, basic graphics, software I2C
|
||||
//U8G2_SSD1306_128X64_NONAME_1_SW_I2C Display(U8G2_R0, /* clock=*/ OLED_SCL, /* data=*/ OLED_SDA, /* reset=*/ OLED_RST); // Page buffer, SW I2C
|
||||
//U8G2_SSD1306_128X64_NONAME_F_SW_I2C Display(U8G2_R0, /* clock=*/ OLED_SCL, /* data=*/ OLED_SDA, /* reset=*/ OLED_RST); // Full framebuffer, SW I2C
|
||||
|
||||
|
|
@ -271,6 +272,20 @@ const char *createStatusForm() {
|
|||
|
||||
///////////////////// Config form
|
||||
|
||||
|
||||
void setupConfigData() {
|
||||
File file = SPIFFS.open("/config.txt", "r");
|
||||
if(!file) {
|
||||
Serial.println("There was an error opening the file '/config.txt' for reading");
|
||||
return;
|
||||
}
|
||||
while(file.available()) {
|
||||
String line = file.readStringUntil('\n');
|
||||
sonde.setConfig(line.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
struct st_configitems {
|
||||
const char *label;
|
||||
int type; // 0: numeric; i>0 string of length i; -1: separator; -2: type selector
|
||||
|
|
@ -459,7 +474,6 @@ void setup()
|
|||
// Open serial communications and wait for port to open:
|
||||
Serial.begin(115200);
|
||||
|
||||
u8x8.begin();
|
||||
aprs_gencrctab();
|
||||
|
||||
pinMode(LORA_LED, OUTPUT);
|
||||
|
|
@ -471,6 +485,11 @@ void setup()
|
|||
}
|
||||
|
||||
setupWifiList();
|
||||
setupConfigData();
|
||||
|
||||
u8x8 = new U8X8_SSD1306_128X64_NONAME_SW_I2C(/* clock=*/ OLED_SCL, /* data=*/ OLED_SDA, /* reset=*/ OLED_RST); // Unbuffered, basic graphics, software I2C
|
||||
u8x8->begin();
|
||||
|
||||
|
||||
#if 0
|
||||
if(rs41.setFrequency(402700000)==0) {
|
||||
|
|
@ -551,7 +570,8 @@ void loopDecoder() {
|
|||
Serial.println("Sending position via UDP");
|
||||
SondeInfo *s = sonde.si();
|
||||
char raw[201];
|
||||
const char *str = aprs_senddata(s->lat, s->lon, s->hei, s->hs, s->dir, s->vs, sondeTypeStr[s->type], s->id, "TE0ST", "EO");
|
||||
const char *str = aprs_senddata(s->lat, s->lon, s->hei, s->hs, s->dir, s->vs, sondeTypeStr[s->type], s->id, "TE0ST",
|
||||
sonde.config.udpfeed.symbol);
|
||||
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
|
||||
Serial.print("Sending: "); Serial.println(raw);
|
||||
udp.beginPacket(sonde.config.udpfeed.host,sonde.config.udpfeed.port);
|
||||
|
|
@ -648,19 +668,20 @@ void WiFiEvent(WiFiEvent_t event){
|
|||
|
||||
static char* _scan[2]={"/","\\"};
|
||||
void loopWifiScan() {
|
||||
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
||||
u8x8.drawString(0,0,"WiFi Scan...");
|
||||
u8x8->setFont(u8x8_font_chroma48medium8_r);
|
||||
u8x8->drawString(0,0,"WiFi Scan...");
|
||||
int line=0;
|
||||
int cnt=0;
|
||||
|
||||
WiFi.disconnect(true);
|
||||
WiFi.mode(WIFI_STA);
|
||||
const char *id, *pw;
|
||||
char idstr[64]="test";
|
||||
int n = WiFi.scanNetworks();
|
||||
for (int i = 0; i < n; i++) {
|
||||
Serial.print("Network name: ");
|
||||
Serial.println(WiFi.SSID(i));
|
||||
u8x8.drawString(0,1+line,WiFi.SSID(i).c_str());
|
||||
u8x8->drawString(0,1+line,WiFi.SSID(i).c_str());
|
||||
line = (line+1)%5;
|
||||
Serial.print("Signal strength: ");
|
||||
Serial.println(WiFi.RSSI(i));
|
||||
|
|
@ -672,26 +693,26 @@ void loopWifiScan() {
|
|||
Serial.println("-----------------------");
|
||||
id=WiFi.SSID(i).c_str();
|
||||
pw=fetchWifiPw(id);
|
||||
if(pw) break;
|
||||
if(pw) { strncpy(idstr, id, 63); }
|
||||
}
|
||||
if(!pw) { id="test"; pw="test"; }
|
||||
Serial.print("Connecting to: "); Serial.println(id);
|
||||
u8x8.drawString(0,6, "Conn:");
|
||||
u8x8.drawString(6,6, id);
|
||||
if(!pw) { pw="test"; }
|
||||
Serial.print("Connecting to: "); Serial.println(idstr);
|
||||
u8x8->drawString(0,6, "Conn:");
|
||||
u8x8->drawString(6,6, idstr);
|
||||
//register event handler
|
||||
WiFi.onEvent(WiFiEvent);
|
||||
|
||||
WiFi.begin(id, pw);
|
||||
WiFi.begin(idstr, pw);
|
||||
while(WiFi.status() != WL_CONNECTED) {
|
||||
delay(500);
|
||||
Serial.print(".");
|
||||
u8x8.drawString(15,7,_scan[cnt&1]);
|
||||
u8x8->drawString(15,7,_scan[cnt&1]);
|
||||
cnt++;
|
||||
#if 0
|
||||
if(cnt==4) {
|
||||
WiFi.disconnect(true); // retry, for my buggy FritzBox
|
||||
WiFi.onEvent(WiFiEvent);
|
||||
WiFi.begin(id, pw);
|
||||
WiFi.begin(idstr, pw);
|
||||
}
|
||||
#endif
|
||||
if(cnt==15) {
|
||||
|
|
@ -701,12 +722,12 @@ void loopWifiScan() {
|
|||
IPAddress myIP = WiFi.softAPIP();
|
||||
Serial.print("AP IP address: ");
|
||||
Serial.println(myIP);
|
||||
u8x8.drawString(0,6, "AP: ");
|
||||
u8x8.drawString(6,6, networks[0].id.c_str());
|
||||
u8x8->drawString(0,6, "AP: ");
|
||||
u8x8->drawString(6,6, networks[0].id.c_str());
|
||||
sonde.setIP(myIP.toString().c_str(), true);
|
||||
sonde.updateDisplayIP();
|
||||
SetupAsyncServer();
|
||||
delay(5000);
|
||||
delay(3000);
|
||||
enterMode(ST_DECODER);
|
||||
return;
|
||||
}
|
||||
|
|
@ -719,7 +740,7 @@ void loopWifiScan() {
|
|||
sonde.setIP(WiFi.localIP().toString().c_str(), false);
|
||||
sonde.updateDisplayIP();
|
||||
SetupAsyncServer();
|
||||
delay(5000);
|
||||
delay(2000);
|
||||
enterMode(ST_DECODER);
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -0,0 +1,25 @@
|
|||
# oled: SDA, SCL, RST (4,15,16 für TTGO v1)
|
||||
oled_sda=4
|
||||
oled_scl=15
|
||||
oled_rst=16
|
||||
noisefloor=-130
|
||||
call=NOCALL
|
||||
passcode=12345
|
||||
# axudp for sending to aprsmap
|
||||
# local use only, do not feed to public services
|
||||
# data not sanities / quality checked, outliers not filtered out
|
||||
axudp.active=1
|
||||
axudp.host=192.168.42.20
|
||||
axudp.port=9002
|
||||
axudp.symbol=/O
|
||||
axudp.highrate=1
|
||||
axudp.idformat=0
|
||||
# maybe some time in the future
|
||||
# currently simply not implemented, no need to put anything here anyway
|
||||
tcp.active=0
|
||||
tcp.host=radiosondy.info
|
||||
tcp.port=14590
|
||||
tcp.symbol=/O
|
||||
tcp.highrate=20
|
||||
tcp.idformat=0
|
||||
|
||||
3
Setup.md
3
Setup.md
|
|
@ -53,6 +53,9 @@ ln -s <whereyouclonedthegit>/rdz_ttgo_sonde/libraries/SX1278FSK/ .
|
|||
|
||||
Restart the Arduino IDE
|
||||
|
||||
(symbolic links are the preferred way, otherwise you have to copy the the libraries again after
|
||||
each update)
|
||||
|
||||
## Final steps
|
||||
|
||||
In the IDE Tools -> Board: ->
|
||||
|
|
|
|||
|
|
@ -2,7 +2,7 @@
|
|||
#include <SX1278FSK.h>
|
||||
#include <U8x8lib.h>
|
||||
|
||||
extern U8X8_SSD1306_128X64_NONAME_SW_I2C u8x8;
|
||||
extern U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8;
|
||||
|
||||
#define CHANBW 10
|
||||
#define PIXSAMPL (50/CHANBW)
|
||||
|
|
@ -44,7 +44,7 @@ void Scanner::plotResult()
|
|||
if( ((i+j)%TICK2)==0) { row[j] |= 0x01; }
|
||||
}
|
||||
for(int y=0; y<8; y++) {
|
||||
u8x8.drawTile(i/8, y, 1, row+8*y);
|
||||
u8x8->drawTile(i/8, y, 1, row+8*y);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -5,7 +5,7 @@
|
|||
#include "RS41.h"
|
||||
#include "DFM.h"
|
||||
|
||||
extern U8X8_SSD1306_128X64_NONAME_SW_I2C u8x8;
|
||||
extern U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8;
|
||||
|
||||
//SondeInfo si = { STYPE_RS41, 403.450, "P1234567", true, 48.1234, 14.9876, 543, 3.97, -0.5, true, 120 };
|
||||
const char *sondeTypeStr[5] = { "DFM6", "DFM9", "RS41" };
|
||||
|
|
@ -67,6 +67,57 @@ Sonde::Sonde() {
|
|||
config.tcpfeed.idformat = ID_DFMDXL;
|
||||
}
|
||||
|
||||
void Sonde::setConfig(const char *cfg) {
|
||||
while(*cfg==' '||*cfg=='\t') cfg++;
|
||||
if(*cfg=='#') return;
|
||||
char *s = strchr(cfg,'=');
|
||||
if(!s) return;
|
||||
char *val = s+1;
|
||||
*s=0; s--;
|
||||
while(s>cfg && (*s==' '||*s=='\t')) { *s=0; s--; }
|
||||
Serial.printf("handling option '%s'='%s'\n", cfg, val);
|
||||
if(strcmp(cfg,"noisefloor")==0) {
|
||||
config.noisefloor = atoi(val);
|
||||
if(config.noisefloor==0) config.noisefloor=-130;
|
||||
} else if(strcmp(cfg,"call")==0) {
|
||||
strncpy(config.call, val, 9);
|
||||
} else if(strcmp(cfg,"passcode")==0) {
|
||||
strncpy(config.passcode, val, 9);
|
||||
} else if(strcmp(cfg,"oled_sda")==0) {
|
||||
config.oled_sda = atoi(val);
|
||||
} else if(strcmp(cfg,"oled_scl")==0) {
|
||||
config.oled_scl = atoi(val);
|
||||
} else if(strcmp(cfg,"oled_rst")==0) {
|
||||
config.oled_rst = atoi(val);
|
||||
} else if(strcmp(cfg,"axudp.active")==0) {
|
||||
config.udpfeed.active = atoi(val)>0;
|
||||
} else if(strcmp(cfg,"axudp.host")==0) {
|
||||
strncpy(config.udpfeed.host, val, 63);
|
||||
} else if(strcmp(cfg,"axudp.port")==0) {
|
||||
config.udpfeed.port = atoi(val);
|
||||
} else if(strcmp(cfg,"axudp.symbol")==0) {
|
||||
strncpy(config.udpfeed.symbol, val, 3);
|
||||
} else if(strcmp(cfg,"axudp.highrate")==0) {
|
||||
config.udpfeed.highrate = atoi(val);
|
||||
} else if(strcmp(cfg,"axudp.idformat")==0) {
|
||||
config.udpfeed.idformat = atoi(val);
|
||||
} else if(strcmp(cfg,"tcp.active")==0) {
|
||||
config.tcpfeed.active = atoi(val)>0;
|
||||
} else if(strcmp(cfg,"tcp.host")==0) {
|
||||
strncpy(config.tcpfeed.host, val, 63);
|
||||
} else if(strcmp(cfg,"tcp.port")==0) {
|
||||
config.tcpfeed.port = atoi(val);
|
||||
} else if(strcmp(cfg,"tcp.symbol")==0) {
|
||||
strncpy(config.tcpfeed.symbol, val, 3);
|
||||
} else if(strcmp(cfg,"tcp.highrate")==0) {
|
||||
config.tcpfeed.highrate = atoi(val);
|
||||
} else if(strcmp(cfg,"tcp.idformat")==0) {
|
||||
config.tcpfeed.idformat = atoi(val);
|
||||
} else {
|
||||
Serial.printf("Invalid config option '%s'='%s'\n", cfg, val);
|
||||
}
|
||||
}
|
||||
|
||||
void Sonde::setIP(const char *ip, bool AP) {
|
||||
memset(myIP_tiles, 0, 11*8);
|
||||
int len = strlen(ip);
|
||||
|
|
@ -151,55 +202,55 @@ int Sonde::receiveFrame() {
|
|||
|
||||
void Sonde::updateDisplayPos() {
|
||||
char buf[16];
|
||||
u8x8.setFont(u8x8_font_7x14_1x2_r);
|
||||
u8x8->setFont(u8x8_font_7x14_1x2_r);
|
||||
if(si()->validPos) {
|
||||
snprintf(buf, 16, "%2.5f", si()->lat);
|
||||
u8x8.drawString(0,2,buf);
|
||||
u8x8->drawString(0,2,buf);
|
||||
snprintf(buf, 16, "%2.5f", si()->lon);
|
||||
u8x8.drawString(0,4,buf);
|
||||
u8x8->drawString(0,4,buf);
|
||||
} else {
|
||||
u8x8.drawString(0,2,"<??> ");
|
||||
u8x8.drawString(0,4,"<??> ");
|
||||
u8x8->drawString(0,2,"<??> ");
|
||||
u8x8->drawString(0,4,"<??> ");
|
||||
}
|
||||
}
|
||||
|
||||
void Sonde::updateDisplayPos2() {
|
||||
char buf[16];
|
||||
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
||||
u8x8->setFont(u8x8_font_chroma48medium8_r);
|
||||
if(!si()->validPos) {
|
||||
u8x8.drawString(10,2," ");
|
||||
u8x8.drawString(10,3," ");
|
||||
u8x8.drawString(10,4," ");
|
||||
u8x8->drawString(10,2," ");
|
||||
u8x8->drawString(10,3," ");
|
||||
u8x8->drawString(10,4," ");
|
||||
return;
|
||||
}
|
||||
snprintf(buf, 16, si()->hei>999?" %5.0fm":" %3.1fm", si()->hei);
|
||||
u8x8.drawString((10+6-strlen(buf)),2,buf);
|
||||
u8x8->drawString((10+6-strlen(buf)),2,buf);
|
||||
snprintf(buf, 16, si()->hs>99?" %3.0f":" %2.1f", si()->hs);
|
||||
u8x8.drawString((10+4-strlen(buf)),3,buf);
|
||||
u8x8->drawString((10+4-strlen(buf)),3,buf);
|
||||
snprintf(buf, 16, " %+2.1f", si()->vs);
|
||||
u8x8.drawString((10+4-strlen(buf)),4,buf);
|
||||
u8x8.drawTile(14,3,2,kmh_tiles);
|
||||
u8x8.drawTile(14,4,2,ms_tiles);
|
||||
u8x8->drawString((10+4-strlen(buf)),4,buf);
|
||||
u8x8->drawTile(14,3,2,kmh_tiles);
|
||||
u8x8->drawTile(14,4,2,ms_tiles);
|
||||
}
|
||||
|
||||
void Sonde::updateDisplayID() {
|
||||
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
||||
u8x8->setFont(u8x8_font_chroma48medium8_r);
|
||||
if(si()->validID) {
|
||||
u8x8.drawString(0,1, si()->id);
|
||||
u8x8->drawString(0,1, si()->id);
|
||||
} else {
|
||||
u8x8.drawString(0,1, "nnnnnnnn ");
|
||||
u8x8->drawString(0,1, "nnnnnnnn ");
|
||||
}
|
||||
}
|
||||
|
||||
void Sonde::updateDisplayRSSI() {
|
||||
char buf[16];
|
||||
u8x8.setFont(u8x8_font_7x14_1x2_r);
|
||||
u8x8->setFont(u8x8_font_7x14_1x2_r);
|
||||
snprintf(buf, 16, "-%d ", sonde.si()->rssi/2);
|
||||
int len=strlen(buf)-3;
|
||||
buf[5]=0;
|
||||
u8x8.drawString(0,6,buf);
|
||||
u8x8.drawTile(len,6,1,(sonde.si()->rssi&1)?halfdb_tile1:empty_tile1);
|
||||
u8x8.drawTile(len,7,1,(sonde.si()->rssi&1)?halfdb_tile2:empty_tile2);
|
||||
u8x8->drawString(0,6,buf);
|
||||
u8x8->drawTile(len,6,1,(sonde.si()->rssi&1)?halfdb_tile1:empty_tile1);
|
||||
u8x8->drawTile(len,7,1,(sonde.si()->rssi&1)?halfdb_tile2:empty_tile2);
|
||||
}
|
||||
|
||||
void Sonde::updateStat() {
|
||||
|
|
@ -208,32 +259,32 @@ void Sonde::updateStat() {
|
|||
uint8_t tile[8];
|
||||
*(uint32_t *)(&tile[0]) = *(uint32_t *)(&(stattiles[stat[i]]));
|
||||
*(uint32_t *)(&tile[4]) = *(uint32_t *)(&(stattiles[stat[i+1]]));
|
||||
u8x8.drawTile(7+i/2, 6, 1, tile);
|
||||
u8x8->drawTile(7+i/2, 6, 1, tile);
|
||||
}
|
||||
}
|
||||
|
||||
void Sonde::updateDisplayRXConfig() {
|
||||
char buf[16];
|
||||
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
||||
u8x8.drawString(0,0, sondeTypeStr[si()->type]);
|
||||
u8x8->setFont(u8x8_font_chroma48medium8_r);
|
||||
u8x8->drawString(0,0, sondeTypeStr[si()->type]);
|
||||
snprintf(buf, 16, "%3.3f MHz", si()->freq);
|
||||
u8x8.drawString(5,0, buf);
|
||||
u8x8->drawString(5,0, buf);
|
||||
|
||||
}
|
||||
|
||||
void Sonde::updateDisplayIP() {
|
||||
u8x8.drawTile(5, 7, 11, myIP_tiles);
|
||||
u8x8->drawTile(5, 7, 11, myIP_tiles);
|
||||
}
|
||||
|
||||
// Probing RS41
|
||||
// 40x.xxx MHz
|
||||
void Sonde::updateDisplayScanner() {
|
||||
char buf[16];
|
||||
u8x8.setFont(u8x8_font_7x14_1x2_r);
|
||||
u8x8.drawString(0, 0, "Probing");
|
||||
u8x8.drawString(8, 0, sondeTypeStr[si()->type]);
|
||||
u8x8->setFont(u8x8_font_7x14_1x2_r);
|
||||
u8x8->drawString(0, 0, "Probing");
|
||||
u8x8->drawString(8, 0, sondeTypeStr[si()->type]);
|
||||
snprintf(buf, 16, "%3.3f MHz", si()->freq);
|
||||
u8x8.drawString(0,3, buf);
|
||||
u8x8->drawString(0,3, buf);
|
||||
updateDisplayIP();
|
||||
}
|
||||
|
||||
|
|
@ -250,7 +301,7 @@ void Sonde::updateDisplay()
|
|||
}
|
||||
|
||||
void Sonde::clearDisplay() {
|
||||
u8x8.clearDisplay();
|
||||
u8x8->clearDisplay();
|
||||
}
|
||||
|
||||
Sonde sonde = Sonde();
|
||||
|
|
|
|||
|
|
@ -13,6 +13,9 @@ enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41 };
|
|||
extern const char *sondeTypeStr[5];
|
||||
|
||||
typedef struct st_rdzconfig {
|
||||
int oled_sda;
|
||||
int oled_scl;
|
||||
int oled_rst;
|
||||
int noisefloor; // for spectrum display
|
||||
char call[9];
|
||||
char passcode[9];
|
||||
|
|
@ -56,6 +59,7 @@ public:
|
|||
SondeInfo sondeList[MAXSONDE+1];
|
||||
|
||||
Sonde();
|
||||
void setConfig(const char *str);
|
||||
|
||||
void clearSonde();
|
||||
void addSonde(float frequency, SondeType type, int active);
|
||||
|
|
|
|||
Loading…
Reference in New Issue