kopia lustrzana https://github.com/dl9rdz/rdz_ttgo_sonde
v0.4: merging pull request by DL2MF and some minor modifications
rodzic
791a6bdb75
commit
0518f070a2
34
README.md
34
README.md
|
@ -4,14 +4,20 @@ RDZ_TTGO_SONDE
|
|||
This a simple, experimental, not (well) tested, and incomplete decoder for
|
||||
radiosonde RS41 and DFM06/09 on a TTGO LoRa ESP32 with OLED display board.
|
||||
|
||||
There have been made some additions for TTGO LoRa ESP32 with only RST button.
|
||||
Please check also your OLED port settings, both versions use different ports.
|
||||
You can setup the depending ports in config.txt, OLED Setup is depending on hardware of LoRa board
|
||||
- TTGO v1: SDA=4 SCL=15, RST=16
|
||||
- TTGO v2: SDA=21 SCL=22, RST=16
|
||||
|
||||
## Button commands
|
||||
You can use the button on the board (not the reset button, the second one) to
|
||||
issue some commands. The software distinguishes between several inputs:
|
||||
|
||||
SHORT Short button press (<1.5 seconds)
|
||||
DOUBLE Short button press, followed by another button press within 0.5 seconds
|
||||
MID Medium-length button press (2-4 seconds)
|
||||
LONG Long button press (>5 seconds)
|
||||
- SHORT Short button press (<1.5 seconds)
|
||||
- DOUBLE Short button press, followed by another button press within 0.5 seconds
|
||||
- MID Medium-length button press (2-4 seconds)
|
||||
- LONG Long button press (>5 seconds)
|
||||
|
||||
## Wireless configuration
|
||||
|
||||
|
@ -39,24 +45,16 @@ for the last 18 frames, if reception was successfull (|) or failed (.)
|
|||
A DOUBLE press will switch to scanning mode.
|
||||
A SHORT press will switch to the next channel in channels.txt
|
||||
|
||||
# Spectrum mode
|
||||
## Spectrum mode
|
||||
|
||||
A medium press will active scan the whole band (400..406 MHz) and display a
|
||||
spectrum diagram (each line == 50 kHz)
|
||||
For TTGO boards without configurable button there are some new parameter in config.txt:
|
||||
- spectrum=10 // 0=off / 1-99 number of seconds to show spectrum after restart
|
||||
- timer=1 // 0=off / 1= show spectrum countdown timer in spectrum display
|
||||
- marker=1 // 0=off / 1= show channel edge freq in spectrum display
|
||||
|
||||
## 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
|
||||
|
||||
|
|
|
@ -3,6 +3,7 @@
|
|||
#include <ESPAsyncWebServer.h>
|
||||
#include <SPIFFS.h>
|
||||
#include <U8x8lib.h>
|
||||
#include <U8g2lib.h>
|
||||
#include <SPI.h>
|
||||
|
||||
#include <SX1278FSK.h>
|
||||
|
@ -12,13 +13,9 @@
|
|||
|
||||
#define LORA_LED 9
|
||||
|
||||
// I2C OLED Display works with SSD1306 driver
|
||||
#define OLED_SDA 4
|
||||
#define OLED_SCL 15
|
||||
#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
|
||||
|
||||
|
@ -28,20 +25,14 @@ AsyncWebServer server(80);
|
|||
|
||||
#define LOCALUDPPORT 9002
|
||||
|
||||
// moved to sonde.config
|
||||
//const char * udpAddress = "192.168.42.20";
|
||||
//const int udpPort = 9002;
|
||||
|
||||
boolean connected = false;
|
||||
WiFiUDP udp;
|
||||
|
||||
|
||||
// Set LED GPIO
|
||||
const int ledPin = 2;
|
||||
int ledPin = 1;
|
||||
// Stores LED state
|
||||
String ledState;
|
||||
|
||||
|
||||
// Replaces placeholder with LED state value
|
||||
String processor(const String& var){
|
||||
Serial.println(var);
|
||||
|
@ -90,6 +81,7 @@ void setupChannelList() {
|
|||
}
|
||||
int i=0;
|
||||
sonde.clearSonde();
|
||||
Serial.println("Reading channel config:");
|
||||
while(file.available()) {
|
||||
String line = file.readStringUntil('\n');
|
||||
if(!file.available()) break;
|
||||
|
@ -104,8 +96,9 @@ void setupChannelList() {
|
|||
else if (space[1]=='6') { type=STYPE_DFM06; }
|
||||
else continue;
|
||||
int active = space[3]=='+'?1:0;
|
||||
Serial.printf("Adding %f with type %d (active: %d)\n",freq,type,active);
|
||||
sonde.addSonde(freq, type, active);
|
||||
char *launchsite = strchr(line.c_str(), ' ');
|
||||
Serial.printf("Add %f - type %d (on/off: %d)- Site: \n",freq,type,active,launchsite);
|
||||
sonde.addSonde(freq, type, active, launchsite);
|
||||
i++;
|
||||
}
|
||||
}
|
||||
|
@ -113,7 +106,7 @@ void setupChannelList() {
|
|||
const char *createQRGForm() {
|
||||
char *ptr = message;
|
||||
strcpy(ptr,"<html><head><link rel=\"stylesheet\" type=\"text/css\" href=\"style.css\"></head><body><form action=\"qrg.html\" method=\"post\"><table><tr><th>ID</th><th>Active</th><th>Freq</th><th>Mode</th></tr>");
|
||||
for(int i=0; i<10; i++) {
|
||||
for(int i=0; i<sonde.config.maxsonde; i++) {
|
||||
String s = sondeTypeSelect(i>=sonde.nSonde?2:sonde.sondeList[i].type);
|
||||
sprintf(ptr+strlen(ptr), "<tr><td>%d</td><td><input name=\"A%d\" type=\"checkbox\" %s/></td>"
|
||||
"<td><input name=\"F%d\" type=\"text\" value=\"%3.3f\"></td>"
|
||||
|
@ -160,6 +153,9 @@ const char *handleQRGPost(AsyncWebServerRequest *request) {
|
|||
f.printf("%3.3f %c %c\n", atof(fstr), typech, active?'+':'-');
|
||||
}
|
||||
f.close();
|
||||
Serial.println("Channel setup finished");
|
||||
Serial.println();
|
||||
|
||||
setupChannelList();
|
||||
}
|
||||
|
||||
|
@ -251,9 +247,9 @@ void addSondeStatus(char *ptr, int i)
|
|||
sprintf(ptr+strlen(ptr),"<tr><td id=\"sfreq\">%3.3f MHz, Type: %s</td><tr><td>ID: %s</td></tr><tr><td>QTH: %.6f,%.6f h=%.0fm</td></tr>\n",
|
||||
s->freq, sondeTypeStr[s->type],
|
||||
s->validID?s->id:"<??>",
|
||||
s->lat, s->lon, s->hei);
|
||||
sprintf(ptr+strlen(ptr), "<tr><td><a target=\"_empty\" href=\"geo:%.6f,%.6f\">Geo-Ref</a> -", s->lat, s->lon);
|
||||
sprintf(ptr+strlen(ptr), "<a target=\"_empty\" href=\"https://www.google.com/maps/search/?api=1&query=%.6f,%.6f\">Google map</a> - ", s->lat, s->lon);
|
||||
s->lat, s->lon, s->alt);
|
||||
sprintf(ptr+strlen(ptr), "<tr><td><a target=\"_empty\" href=\"geo:%.6f,%.6f\">GEO-App</a> - ", s->lat, s->lon);
|
||||
sprintf(ptr+strlen(ptr), "<a target=\"_empty\" href=\"https://wx.dl2mf.de/?%s\">WX.DL2MF.de</a> - ", s->id);
|
||||
sprintf(ptr+strlen(ptr), "<a target=\"_empty\" href=\"https://www.openstreetmap.org/?mlat=%.6f&mlon=%.6f&zoom=14\">OSM</a></td></tr>", s->lat, s->lon);
|
||||
strcat(ptr, "</table><p/>\n");
|
||||
}
|
||||
|
@ -271,13 +267,31 @@ 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
|
||||
void *data;
|
||||
};
|
||||
#define N_CONFIG 16
|
||||
#define N_CONFIG 20
|
||||
struct st_configitems config_list[N_CONFIG] = {
|
||||
{"ShowSpectrum (s)", 0, &sonde.config.spectrum},
|
||||
{"Startfreq (MHz)", 0, &sonde.config.startfreq},
|
||||
{"Bandwidth (kHz)", 0, &sonde.config.channelbw},
|
||||
{"---", -1, NULL},
|
||||
{"Call", 8, sonde.config.call},
|
||||
{"Passcode", 8, sonde.config.passcode},
|
||||
{"---", -1, NULL},
|
||||
|
@ -400,11 +414,11 @@ void SetupAsyncServer() {
|
|||
|
||||
const char *fetchWifiPw(const char *id) {
|
||||
for(int i=0; i<nNetworks; i++) {
|
||||
Serial.print("Comparing '");
|
||||
Serial.print(id);
|
||||
Serial.print("' and '");
|
||||
Serial.print(networks[i].id.c_str());
|
||||
Serial.println("'");
|
||||
//Serial.print("Comparing '");
|
||||
//Serial.print(id);
|
||||
//Serial.print("' and '");
|
||||
//Serial.print(networks[i].id.c_str());
|
||||
//Serial.println("'");
|
||||
if(strcmp(id,networks[i].id.c_str())==0) return networks[i].pw.c_str();
|
||||
}
|
||||
return NULL;
|
||||
|
@ -414,7 +428,7 @@ const char *fetchWifiPw(const char *id) {
|
|||
enum KeyPress { KP_NONE=0, KP_SHORT, KP_DOUBLE, KP_MID, KP_LONG };
|
||||
|
||||
struct Button {
|
||||
const uint8_t PIN;
|
||||
uint8_t pin;
|
||||
uint32_t numberKeyPresses;
|
||||
KeyPress pressed;
|
||||
unsigned long press_ts;
|
||||
|
@ -423,7 +437,7 @@ struct Button {
|
|||
Button button1 = {0, 0, KP_NONE, 0, false};
|
||||
|
||||
void IRAM_ATTR buttonISR() {
|
||||
if(digitalRead(0)==0) { // Button down
|
||||
if(digitalRead(button1.pin)==0) { // Button down
|
||||
if(millis()-button1.press_ts<500) {
|
||||
// Double press
|
||||
button1.doublepress = true;
|
||||
|
@ -456,23 +470,81 @@ int hasKeyPress() {
|
|||
|
||||
void setup()
|
||||
{
|
||||
char buf[12];
|
||||
// Open serial communications and wait for port to open:
|
||||
Serial.begin(115200);
|
||||
pinMode(LORA_LED, OUTPUT);
|
||||
|
||||
u8x8.begin();
|
||||
aprs_gencrctab();
|
||||
|
||||
pinMode(LORA_LED, OUTPUT);
|
||||
|
||||
// Initialize SPIFFS
|
||||
// Initialize SPIFFS
|
||||
if(!SPIFFS.begin(true)){
|
||||
Serial.println("An Error has occurred while mounting SPIFFS");
|
||||
return;
|
||||
}
|
||||
|
||||
setupConfigData(); // configuration must be read first due to OLED ports!!!
|
||||
|
||||
u8x8 = new U8X8_SSD1306_128X64_NONAME_SW_I2C(/* clock=*/ sonde.config.oled_scl, /* data=*/ sonde.config.oled_sda, /* reset=*/ sonde.config.oled_rst); // Unbuffered, basic graphics, software I2C
|
||||
u8x8->begin();
|
||||
delay(100);
|
||||
|
||||
u8x8->clear();
|
||||
|
||||
u8x8->setFont(u8x8_font_7x14_1x2_r);
|
||||
u8x8->drawString(1, 1, "RDZ_TTGO_SONDE");
|
||||
u8x8->drawString(2, 3, " V0.1e");
|
||||
u8x8->drawString(1, 5, "Mods by DL2MF");
|
||||
delay(3000);
|
||||
|
||||
sonde.clearDisplay();
|
||||
|
||||
setupWifiList();
|
||||
button1.pin = sonde.config.button_pin;
|
||||
|
||||
// == show initial values from config.txt ========================= //
|
||||
if (sonde.config.debug == 1) {
|
||||
u8x8->setFont(u8x8_font_chroma48medium8_r);
|
||||
u8x8->drawString(0, 0, "Config:");
|
||||
|
||||
delay(500);
|
||||
itoa(sonde.config.oled_sda, buf, 10);
|
||||
u8x8->drawString(0, 1, " SDA:");
|
||||
u8x8->drawString(6, 1, buf);
|
||||
|
||||
delay(500);
|
||||
itoa(sonde.config.oled_scl, buf, 10);
|
||||
u8x8->drawString(0, 2, " SCL:");
|
||||
u8x8->drawString(6, 2, buf);
|
||||
|
||||
delay(500);
|
||||
itoa(sonde.config.oled_rst, buf, 10);
|
||||
u8x8->drawString(0, 3, " RST:");
|
||||
u8x8->drawString(6, 3, buf);
|
||||
|
||||
delay(1000);
|
||||
itoa(sonde.config.led_pin, buf, 10);
|
||||
u8x8->drawString(0, 4, " LED:");
|
||||
u8x8->drawString(6, 4, buf);
|
||||
|
||||
delay(500);
|
||||
itoa(sonde.config.spectrum, buf, 10);
|
||||
u8x8->drawString(0, 5, " SPEC:");
|
||||
u8x8->drawString(6, 5, buf);
|
||||
|
||||
delay(500);
|
||||
itoa(sonde.config.maxsonde, buf, 10);
|
||||
u8x8->drawString(0, 6, " MAX:");
|
||||
u8x8->drawString(6, 6, buf);
|
||||
|
||||
delay(5000);
|
||||
sonde.clearDisplay();
|
||||
}
|
||||
// == show initial values from config.txt ========================= //
|
||||
|
||||
|
||||
#if 0
|
||||
// == check the radio chip by setting default frequency =========== //
|
||||
if(rs41.setFrequency(402700000)==0) {
|
||||
Serial.println(F("Setting freq: SUCCESS "));
|
||||
} else {
|
||||
|
@ -481,6 +553,7 @@ void setup()
|
|||
float f = sx1278.getFrequency();
|
||||
Serial.print("Frequency set to ");
|
||||
Serial.println(f);
|
||||
// == check the radio chip by setting default frequency =========== //
|
||||
#endif
|
||||
|
||||
//sx1278.setLNAGain(-48);
|
||||
|
@ -491,11 +564,10 @@ void setup()
|
|||
Serial.println(gain);
|
||||
|
||||
// Print a success message
|
||||
Serial.println(F("sx1278 configured finished"));
|
||||
Serial.println();
|
||||
|
||||
Serial.println(F("SX1278 configuration finished"));
|
||||
|
||||
Serial.println("Setup finished");
|
||||
Serial.println();
|
||||
// int returnValue = pthread_create(&wifithread, NULL, wifiloop, (void *)0);
|
||||
|
||||
// if (returnValue) {
|
||||
|
@ -504,22 +576,28 @@ void setup()
|
|||
// xTaskCreate(mainloop, "MainServer", 10240, NULL, 10, NULL);
|
||||
|
||||
// Handle button press
|
||||
attachInterrupt(0, buttonISR, CHANGE);
|
||||
attachInterrupt(button1.pin, buttonISR, CHANGE);
|
||||
|
||||
// == setup default channel list if qrg.txt read fails =========== //
|
||||
setupChannelList();
|
||||
#if 0
|
||||
sonde.clearSonde();
|
||||
sonde.addSonde(402.300, STYPE_RS41);
|
||||
sonde.addSonde(402.700, STYPE_RS41);
|
||||
sonde.addSonde(405.700, STYPE_RS41);
|
||||
sonde.addSonde(405.900, STYPE_RS41);
|
||||
sonde.addSonde(403.450, STYPE_DFM09);
|
||||
Serial.println("No channel config file, using defaults!");
|
||||
Serial.println();
|
||||
#endif
|
||||
/// not here, done by sonde.setup(): rs41.setup();
|
||||
// == setup default channel list if qrg.txt read fails =========== //
|
||||
|
||||
sonde.setup();
|
||||
}
|
||||
|
||||
enum MainState { ST_DECODER, ST_SCANNER, ST_SPECTRUM, ST_WIFISCAN };
|
||||
|
||||
static MainState mainState = ST_DECODER;
|
||||
static MainState mainState = ST_WIFISCAN;
|
||||
|
||||
void enterMode(int mode) {
|
||||
mainState = (MainState)mode;
|
||||
|
@ -530,6 +608,8 @@ void loopDecoder() {
|
|||
switch(getKeyPress()) {
|
||||
case KP_SHORT:
|
||||
sonde.nextConfig();
|
||||
sonde.updateDisplayRXConfig();
|
||||
sonde.updateDisplay();
|
||||
break;
|
||||
case KP_DOUBLE:
|
||||
enterMode(ST_SCANNER);
|
||||
|
@ -551,7 +631,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->alt, 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);
|
||||
|
@ -580,7 +661,7 @@ void loopScanner() {
|
|||
}
|
||||
// receiveFrame returns 0 on success, 1 on timeout
|
||||
int res = sonde.receiveFrame(); // Maybe instead of receiveFrame, just detect if right type is present? TODO
|
||||
Serial.print("Scanner: receiveFrame returned");
|
||||
Serial.print("Scanner: receiveFrame returned: ");
|
||||
Serial.println(res);
|
||||
if(res==0) {
|
||||
enterMode(ST_DECODER);
|
||||
|
@ -645,71 +726,121 @@ 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);
|
||||
if (sonde.config.wifi != 0) {
|
||||
u8x8->drawString(0,0,"WiFi Scan...");
|
||||
}
|
||||
else if (sonde.config.wifiap != 0) {
|
||||
u8x8->drawString(0,0,"WiFi AP-Mode:");
|
||||
}
|
||||
|
||||
int line=0;
|
||||
int cnt=0;
|
||||
int marker=0;
|
||||
char buf[5];
|
||||
|
||||
WiFi.disconnect(true);
|
||||
WiFi.mode(WIFI_STA);
|
||||
const char *id, *pw;
|
||||
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());
|
||||
line = (line+1)%5;
|
||||
Serial.print("Signal strength: ");
|
||||
Serial.println(WiFi.RSSI(i));
|
||||
Serial.print("MAC address: ");
|
||||
Serial.println(WiFi.BSSIDstr(i));
|
||||
Serial.print("Encryption type: ");
|
||||
String encryptionTypeDescription = translateEncryptionType(WiFi.encryptionType(i));
|
||||
Serial.println(encryptionTypeDescription);
|
||||
Serial.println("-----------------------");
|
||||
id=WiFi.SSID(i).c_str();
|
||||
pw=fetchWifiPw(id);
|
||||
if(pw) break;
|
||||
}
|
||||
if(!pw) { id="test"; pw="test"; }
|
||||
Serial.print("Connecting to: "); Serial.println(id);
|
||||
u8x8.drawString(0,6, "Conn:");
|
||||
u8x8.drawString(6,6, id);
|
||||
//register event handler
|
||||
WiFi.onEvent(WiFiEvent);
|
||||
char idstr[64]="test";
|
||||
|
||||
if (sonde.config.wifi != 0) {
|
||||
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());
|
||||
line = (line+1)%5;
|
||||
Serial.print("Signal strength: ");
|
||||
Serial.println(WiFi.RSSI(i));
|
||||
Serial.print("MAC address: ");
|
||||
Serial.println(WiFi.BSSIDstr(i));
|
||||
Serial.print("Encryption type: ");
|
||||
String encryptionTypeDescription = translateEncryptionType(WiFi.encryptionType(i));
|
||||
Serial.println(encryptionTypeDescription);
|
||||
Serial.println("-----------------------");
|
||||
id=WiFi.SSID(i).c_str();
|
||||
pw=fetchWifiPw(id);
|
||||
if(pw) { strncpy(idstr, id, 63); }
|
||||
}
|
||||
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(idstr, pw);
|
||||
}
|
||||
|
||||
WiFi.begin(id, 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) {
|
||||
WiFi.disconnect(true);
|
||||
delay(1000);
|
||||
WiFi.softAP(networks[0].id.c_str(),networks[0].pw.c_str());
|
||||
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());
|
||||
sonde.setIP(myIP.toString().c_str(), true);
|
||||
sonde.updateDisplayIP();
|
||||
SetupAsyncServer();
|
||||
delay(5000);
|
||||
enterMode(ST_DECODER);
|
||||
|
||||
if (sonde.config.wifiap != 0) { // enable WiFi AP mode in config.txt: wifi=1
|
||||
delay(1000);
|
||||
WiFi.softAP(networks[0].id.c_str(),networks[0].pw.c_str());
|
||||
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());
|
||||
sonde.setIP(myIP.toString().c_str(), true);
|
||||
sonde.updateDisplayIP();
|
||||
SetupAsyncServer();
|
||||
delay(3000);
|
||||
}
|
||||
|
||||
if (sonde.config.spectrum != 0) { // enable Spectrum in config.txt: spectrum=number_of_seconds
|
||||
sonde.clearDisplay();
|
||||
u8x8->setFont(u8x8_font_chroma48medium8_r);
|
||||
u8x8->drawString(0, 0, "Spectrum Scan...");
|
||||
delay(500);
|
||||
|
||||
enterMode(ST_SPECTRUM);
|
||||
|
||||
for (int i = 0; i < sonde.config.spectrum; i++) {
|
||||
scanner.scan();
|
||||
scanner.plotResult();
|
||||
|
||||
if (sonde.config.marker != 0) {
|
||||
itoa((sonde.config.startfreq), buf, 10);
|
||||
u8x8->drawString(0, 1, buf);
|
||||
u8x8->drawString(7, 1, "MHz");
|
||||
itoa((sonde.config.startfreq + 6), buf, 10);
|
||||
u8x8->drawString(13, 1, buf);
|
||||
}
|
||||
|
||||
if (sonde.config.timer != 0) {
|
||||
itoa((sonde.config.spectrum - i), buf, 10);
|
||||
if (sonde.config.marker != 0) {
|
||||
marker = 1;
|
||||
}
|
||||
u8x8->drawString(0, 1+marker, buf);
|
||||
u8x8->drawString(2, 1+marker, "Sec.");
|
||||
}
|
||||
}
|
||||
|
||||
delay(1000);
|
||||
}
|
||||
|
||||
enterMode(ST_SCANNER);
|
||||
return;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
Serial.println("");
|
||||
|
@ -719,10 +850,11 @@ void loopWifiScan() {
|
|||
sonde.setIP(WiFi.localIP().toString().c_str(), false);
|
||||
sonde.updateDisplayIP();
|
||||
SetupAsyncServer();
|
||||
delay(5000);
|
||||
enterMode(ST_DECODER);
|
||||
}
|
||||
delay(2000);
|
||||
|
||||
// enterMode(ST_DECODER); ### 2019-04-20 - changed DL2MF
|
||||
enterMode(ST_SCANNER);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
Serial.println("Running main loop");
|
||||
|
|
|
@ -0,0 +1,57 @@
|
|||
#-------------------------------#
|
||||
# Hardware depending settings
|
||||
#-------------------------------#
|
||||
button_pin=0
|
||||
# LED port
|
||||
led_pin=25
|
||||
# OLED Setup is depending on hardware of LoRa board
|
||||
# TTGO v1: SDA=4 SCL=15, RST=16
|
||||
# TTGO v2: SDA=21 SCL=22, RST=16
|
||||
oled_sda=4
|
||||
oled_scl=15
|
||||
oled_rst=16
|
||||
#-------------------------------#
|
||||
# General config settings
|
||||
#-------------------------------#
|
||||
maxsonde=20
|
||||
debug=0
|
||||
wifi=0
|
||||
wifiap=1
|
||||
#-------------------------------#
|
||||
# Spectrum display settings
|
||||
#-------------------------------#
|
||||
startfreq=400
|
||||
channelbw=10
|
||||
spectrum=10
|
||||
timer=1
|
||||
noisefloor=-110
|
||||
marker=1
|
||||
#-------------------------------#
|
||||
# APRS settings
|
||||
#-------------------------------#
|
||||
call=N0CALL
|
||||
passcode=12345
|
||||
#-------------------------------#
|
||||
# axudp for sending to aprsmap
|
||||
#-------------------------------#
|
||||
# local use only, do not feed to public services
|
||||
# data not sanitized / 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
|
||||
#-------------------------------#
|
||||
# EOF
|
||||
#-------------------------------#
|
|
@ -1,13 +1,13 @@
|
|||
<!DOCTYPE html>
|
||||
<html>
|
||||
<head>
|
||||
<title>ESP32 Web Server</title>
|
||||
<title>RDZSonde Server</title>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1">
|
||||
<link rel="icon" href="data:,">
|
||||
<link rel="stylesheet" type="text/css" href="style.css">
|
||||
</head>
|
||||
<body>
|
||||
<h1>ESP32 Web Server</h1>
|
||||
<h2>RDZSonde Server</h2>
|
||||
<!--
|
||||
<p>GPIO state: <strong> %STATE%</strong></p>
|
||||
<p><a href="/on"><button class="button">ON</button></a></p>
|
||||
|
@ -16,19 +16,20 @@
|
|||
|
||||
<div class="tab">
|
||||
<button class="tablinks" onclick="selTab(event,'QRG')" id="defaultTab">QRG</button>
|
||||
<button class="tablinks" onclick="selTab(event,'WIFI')">WLAN</button>
|
||||
<button class="tablinks" onclick="selTab(event,'WLAN')">WLAN</button>
|
||||
<button class="tablinks" onclick="selTab(event,'Data')">Data</button>
|
||||
<button class="tablinks" onclick="selTab(event,'WebWX')">Webwx</button>
|
||||
<button class="tablinks" onclick="selTab(event,'Config')">Config</button>
|
||||
<button class="tablinks" onclick="selTab(event,'About')">About</button>
|
||||
</div>
|
||||
|
||||
<div id="QRG" class="tabcontent">
|
||||
<h3> QRG</h3>
|
||||
<h3> QRG - Setup</h3>
|
||||
<iframe src="qrg.html" style="border:none;" width="100%%" height="100%%"></iframe>
|
||||
</div>
|
||||
|
||||
<div id="WIFI" class="tabcontent">
|
||||
<h3> WIFI</h3>
|
||||
<div id="WLAN" class="tabcontent">
|
||||
<h3> WLAN - Settings</h3>
|
||||
<iframe src="wifi.html" style="border:none;" width="100%%" height="100%%"></iframe>
|
||||
</div>
|
||||
|
||||
|
@ -37,14 +38,29 @@
|
|||
<iframe src="status.html" style="border:none;" width="100%%" height="100%%"></iframe>
|
||||
</div>
|
||||
|
||||
<div id="Data" class="tabcontent">
|
||||
<h3>wetterson.de</h3>
|
||||
<iframe src="https://wetterson.de/karte/" style="border:none;" width="100%%" height="100%%"></iframe>
|
||||
</div>
|
||||
|
||||
<div id="Config" class="tabcontent">
|
||||
<h3>Config</h3>
|
||||
<h3>Configuration</h3>
|
||||
<iframe src="config.html" style="border:none;" width="100%%" height="100%%"></iframe>
|
||||
</div>
|
||||
|
||||
<div id="About" class="tabcontent">
|
||||
<h3>About</h3>
|
||||
RDZSonde
|
||||
RDZSonde<br>
|
||||
Copyright © 2019 by Hansi Reiser, DL9RDZ<br>
|
||||
(master-version v0.4)<br>
|
||||
with mods by Meinhard Guenther, DL2MF<br>
|
||||
<br>
|
||||
This program is free software; you can redistribute it and/or<br>
|
||||
modify it under the terms of the GNU General Public License as<br>
|
||||
published by the Free Software Foundation; either version 2 of<br>
|
||||
the License, or (at your option) any later version.<br>
|
||||
see <a href="https://www.gnu.org/licenses/gpl-2.0.txt">https://www.gnu.org/licenses/gpl-2.0.txt</a>
|
||||
for details
|
||||
</div>
|
||||
|
||||
<script>
|
||||
|
|
|
@ -2,5 +2,3 @@ RDZsonde
|
|||
RDZsonde
|
||||
DinoGast
|
||||
Schokolade
|
||||
AndroidDD
|
||||
dl9rdzhr
|
||||
|
|
|
@ -1,8 +1,23 @@
|
|||
# Frequency in Mhz (format nnn.nnn)
|
||||
# Type (4=RS41, 6=DFM normal, DFM-06, 9=DFM inverted, DFM-09)
|
||||
#
|
||||
402.700 4 +
|
||||
402.300 4 +
|
||||
403.450 9 +
|
||||
405.100 4 -
|
||||
402.300 4 + Greifswald
|
||||
402.500 4 - Schleswig
|
||||
402.700 4 + HH-Sasel
|
||||
403.000 4 - DeBilt
|
||||
404.100 4 + Norderney
|
||||
404.300 4 - Schleswig_2
|
||||
404.500 4 - Meppen
|
||||
404.700 4 - Greifswald_2
|
||||
405.100 4 - Lindenberg
|
||||
405.700 4 + Bergen
|
||||
405.900 4 + Bergen_2
|
||||
405.100 4 + Meppen_2
|
||||
405.300 4 - Essen
|
||||
403.330 9 - TrUebPl
|
||||
403.450 9 - TrUebPl
|
||||
403.470 9 - TrUebPl
|
||||
403.850 9 - TrUebPl
|
||||
403.870 9 - TrUebPl
|
||||
403.890 9 - TrUebPl
|
||||
# end
|
||||
|
|
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: ->
|
||||
|
|
|
@ -228,12 +228,12 @@ int DFM::decodeDAT(uint8_t *dat)
|
|||
break;
|
||||
case 4:
|
||||
{
|
||||
float hei, vv;
|
||||
hei = ((uint32_t)dat[0]<<24) + ((uint32_t)dat[1]<<16) + ((uint32_t)dat[2]<<8) + dat[3];
|
||||
float alt, vv;
|
||||
alt = ((uint32_t)dat[0]<<24) + ((uint32_t)dat[1]<<16) + ((uint32_t)dat[2]<<8) + dat[3];
|
||||
vv = (int16_t)( (dat[4]<<8) | dat[5] );
|
||||
Serial.print("GPS-height: "); Serial.print(hei*0.01);
|
||||
Serial.print("GPS-height: "); Serial.print(alt*0.01);
|
||||
Serial.print(", vv: "); Serial.print(vv*0.01);
|
||||
sonde.si()->hei = hei*0.01;
|
||||
sonde.si()->alt = alt*0.01;
|
||||
sonde.si()->vs = vv*0.01;
|
||||
sonde.si()->validPos |= 0x0C;
|
||||
}
|
||||
|
|
|
@ -339,6 +339,7 @@ static void posrs41(const byte b[], uint32_t b_len, uint32_t p)
|
|||
long0)+vz*(double)sin((float)lat);
|
||||
dir = X2C_DIVL(atang2(vn, ve),1.7453292519943E-2);
|
||||
if (dir<0.0) dir = 360.0+dir;
|
||||
sonde.si()->dir = dir;
|
||||
Serial.print(" ");
|
||||
sonde.si()->hs = sqrt((float)(vn*vn+ve*ve))*3.6f;
|
||||
Serial.print(sonde.si()->hs);
|
||||
|
@ -350,16 +351,17 @@ static void posrs41(const byte b[], uint32_t b_len, uint32_t p)
|
|||
Serial.print("m/s ");
|
||||
Serial.print(getcard16(b, b_len, p+18UL)&255UL);
|
||||
Serial.print("Sats");
|
||||
sonde.si()->hei = heig;
|
||||
sonde.si()->alt = heig;
|
||||
sonde.si()->validPos = true;
|
||||
} /* end posrs41() */
|
||||
|
||||
|
||||
|
||||
|
||||
void RS41::decode41(byte *data, int maxlen)
|
||||
// returns: 0: ok, -1: rs or crc error
|
||||
int RS41::decode41(byte *data, int maxlen)
|
||||
{
|
||||
char buf[128];
|
||||
char buf[128];
|
||||
int crcok = 0;
|
||||
|
||||
int32_t corr = reedsolomon41(data, 560, 131); // try short frame first
|
||||
if(corr<0) {
|
||||
|
@ -392,7 +394,8 @@ void RS41::decode41(byte *data, int maxlen)
|
|||
// check CRC
|
||||
if(!crcrs(data, 560, p, p+len)) {
|
||||
Serial.println("###CRC ERROR###");
|
||||
} else {
|
||||
} else {
|
||||
crcok = 1;
|
||||
switch(typ) {
|
||||
case 'y': // name
|
||||
{
|
||||
|
@ -420,6 +423,7 @@ void RS41::decode41(byte *data, int maxlen)
|
|||
p += len;
|
||||
Serial.println();
|
||||
}
|
||||
return crcok ? 0 : -1;
|
||||
}
|
||||
void RS41::printRaw(uint8_t *data, int len)
|
||||
{
|
||||
|
@ -472,8 +476,8 @@ int RS41::receiveFrame() {
|
|||
//printRaw(data, MAXLEN);
|
||||
for(int i=0; i<RS41MAXLEN; i++) { data[i] = data[i] ^ scramble[i&0x3F]; }
|
||||
//printRaw(data, MAXLEN);
|
||||
decode41(data, RS41MAXLEN);
|
||||
return RX_OK;
|
||||
int res = decode41(data, RS41MAXLEN);
|
||||
return res==0 ? RX_OK : RX_ERROR;
|
||||
}
|
||||
|
||||
RS41 rs41 = RS41();
|
||||
|
|
|
@ -23,7 +23,7 @@ private:
|
|||
uint32_t bits2val(const uint8_t *bits, int len);
|
||||
void printRaw(uint8_t *data, int len);
|
||||
int bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);
|
||||
void decode41(byte *data, int maxlen);
|
||||
int decode41(byte *data, int maxlen);
|
||||
|
||||
#define B 8
|
||||
#define S 4
|
||||
|
|
|
@ -2,21 +2,28 @@
|
|||
#include <SX1278FSK.h>
|
||||
#include <U8x8lib.h>
|
||||
|
||||
extern U8X8_SSD1306_128X64_NONAME_SW_I2C u8x8;
|
||||
#include "Sonde.h"
|
||||
|
||||
extern U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8;
|
||||
|
||||
#define CHANBW 10
|
||||
#define PIXSAMPL (50/CHANBW)
|
||||
#define SMOOTH 4
|
||||
#define STARTF 400000000
|
||||
#define SMOOTH 3
|
||||
//#define STARTF 401000000
|
||||
#define NCHAN ((int)(6000/CHANBW))
|
||||
|
||||
double STARTF = (sonde.config.startfreq * 1000000);
|
||||
//int CHANBW = (sonde.config.channelbw);
|
||||
//int NCHAN = ((int)(6000/CHANBW));
|
||||
//int PIXSAMPL = (50/CHANBW);
|
||||
|
||||
int scanresult[NCHAN];
|
||||
int scandisp[NCHAN/PIXSAMPL];
|
||||
|
||||
#define PLOT_N 120
|
||||
#define TICK1 (120/6)
|
||||
#define PLOT_N 128
|
||||
#define TICK1 (128/6)
|
||||
#define TICK2 (TICK1/4)
|
||||
#define PLOT_MIN -220
|
||||
#define PLOT_MIN -250
|
||||
#define PLOT_SCALE(x) (x<PLOT_MIN?0:(x-PLOT_MIN)/2)
|
||||
|
||||
const byte tilepatterns[9]={0,0x80,0xC0,0xE0,0xF0,0xF8,0xFC,0xFE,0xFF};
|
||||
|
@ -30,7 +37,7 @@ void Scanner::fillTiles(uint8_t *row, int value) {
|
|||
}
|
||||
/*
|
||||
* There are 16*8 columns to plot, NPLOT must be lower than that
|
||||
* currently, we use 120 * 50kHz channels
|
||||
* currently, we use 128 * 50kHz channels
|
||||
* There are 8*8 values to plot; MIN is bottom end,
|
||||
*/
|
||||
uint8_t tiles[16] = { 0x0f,0x0f,0x0f,0x0f,0xf0,0xf0,0xf0,0xf0, 1, 3, 7, 15, 31, 63, 127, 255};
|
||||
|
@ -44,7 +51,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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -82,7 +89,7 @@ void Scanner::scan()
|
|||
lastfrf = frf;
|
||||
// Wait TS_HOP (20us) + TS_RSSI ( 2^(SMOOTH+1) / 4 / CHANBW us)
|
||||
int wait = 20 + 1000*(1<<(SMOOTH+1))/4/CHANBW;
|
||||
delayMicroseconds(wait);
|
||||
delayMicroseconds(wait+5);
|
||||
int rssi = -(int)sx1278.readRegister(REG_RSSI_VALUE_FSK);
|
||||
if(iter==0) { scanresult[i] = rssi; } else {
|
||||
if(rssi>scanresult[i]) scanresult[i]=rssi;
|
||||
|
|
|
@ -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" };
|
||||
|
@ -17,10 +17,10 @@ static unsigned char ms_tiles[] U8X8_PROGMEM = {
|
|||
0x1F, 0x02, 0x04, 0x02, 0x1F, 0x40, 0x20, 0x10, 0x08, 0x04, 0x12, 0xA4, 0xA4, 0xA4, 0x40, 0x00
|
||||
};
|
||||
static unsigned char stattiles[4][4] = {
|
||||
0x00, 0x00, 0x00, 0x00 ,
|
||||
0x00, 0x10, 0x10, 0x00 ,
|
||||
0x1F, 0x15, 0x15, 0x00 ,
|
||||
0x00, 0x1F, 0x00, 0x00 };
|
||||
0x00, 0x1F, 0x00, 0x00 , // | == ok
|
||||
0x00, 0x10, 0x10, 0x00 , // . == no header found
|
||||
0x1F, 0x15, 0x15, 0x00 , // E == decode error
|
||||
0x00, 0x00, 0x00, 0x00 }; // ' ' == unknown/unassigned
|
||||
|
||||
byte myIP_tiles[8*11];
|
||||
|
||||
|
@ -48,23 +48,111 @@ static uint8_t empty_tile2[8]={0x00, 0x11, 0x02, 0x02, 0x02, 0x01, 0x00, 0x00};
|
|||
static uint8_t ap_tile[8]={0x00,0x04,0x22,0x92, 0x92, 0x22, 0x04, 0x00};
|
||||
|
||||
Sonde::Sonde() {
|
||||
config.button_pin = 0;
|
||||
config.oled_sda = 4;
|
||||
config.oled_scl = 15;
|
||||
config.oled_rst = 16;
|
||||
config.noisefloor = -130;
|
||||
strcpy(config.call,"NOCALL");
|
||||
strcpy(config.passcode, "---");
|
||||
config.maxsonde=15;
|
||||
config.debug=0;
|
||||
config.wifi=1;
|
||||
config.wifiap=1;
|
||||
config.startfreq=400;
|
||||
config.channelbw=10;
|
||||
config.spectrum=10;
|
||||
config.timer=0;
|
||||
config.marker=0;
|
||||
config.udpfeed.active = 1;
|
||||
config.udpfeed.type = 0;
|
||||
strcpy(config.udpfeed.host, "192.168.42.20");
|
||||
strcpy(config.udpfeed.symbol, "/O");
|
||||
config.udpfeed.port = 9002;
|
||||
config.udpfeed.highrate = 1;
|
||||
config.udpfeed.idformat = ID_DFMGRAW;
|
||||
config.tcpfeed.active = 0;
|
||||
config.tcpfeed.type = 1;
|
||||
strcpy(config.tcpfeed.host, "radiosondy.info");
|
||||
strcpy(config.tcpfeed.symbol, "/O");
|
||||
config.tcpfeed.port = 12345;
|
||||
config.tcpfeed.highrate = 10;
|
||||
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("configuration 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,"button_pin")==0) {
|
||||
config.button_pin = atoi(val);
|
||||
} else if(strcmp(cfg,"led_pin")==0) {
|
||||
config.led_pin = atoi(val);
|
||||
} 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,"maxsonde")==0) {
|
||||
config.maxsonde = atoi(val);
|
||||
} else if(strcmp(cfg,"debug")==0) {
|
||||
config.debug = atoi(val);
|
||||
} else if(strcmp(cfg,"wifi")==0) {
|
||||
config.wifi = atoi(val);
|
||||
} else if(strcmp(cfg,"wifiap")==0) {
|
||||
config.wifiap = atoi(val);
|
||||
} else if(strcmp(cfg,"startfreq")==0) {
|
||||
config.startfreq = atoi(val);
|
||||
} else if(strcmp(cfg,"channelbw")==0) {
|
||||
config.channelbw = atoi(val);
|
||||
} else if(strcmp(cfg,"spectrum")==0) {
|
||||
config.spectrum = atoi(val);
|
||||
} else if(strcmp(cfg,"timer")==0) {
|
||||
config.timer = atoi(val);
|
||||
} else if(strcmp(cfg,"marker")==0) {
|
||||
config.marker = 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);
|
||||
|
@ -86,21 +174,22 @@ void Sonde::setIP(const char *ip, bool AP) {
|
|||
void Sonde::clearSonde() {
|
||||
nSonde = 0;
|
||||
}
|
||||
void Sonde::addSonde(float frequency, SondeType type, int active) {
|
||||
if(nSonde>=MAXSONDE) {
|
||||
void Sonde::addSonde(float frequency, SondeType type, int active, char *launchsite) {
|
||||
if(nSonde>=config.maxsonde) {
|
||||
Serial.println("Cannot add another sonde, MAXSONDE reached");
|
||||
return;
|
||||
}
|
||||
sondeList[nSonde].type = type;
|
||||
sondeList[nSonde].freq = frequency;
|
||||
sondeList[nSonde].active = active;
|
||||
memcpy(sondeList[nSonde].rxStat, "\x00\x01\x2\x3\x2\x1\x1\x2\x0\x3\x0\x0\x1\x2\x3\x1\x0", 18);
|
||||
sondeList[nSonde].launchsite = launchsite;
|
||||
memcpy(sondeList[nSonde].rxStat, "\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3", 18); // unknown/undefined
|
||||
nSonde++;
|
||||
}
|
||||
void Sonde::nextConfig() {
|
||||
currentSonde++;
|
||||
// Skip non-active entries (but don't loop forever if there are no active ones
|
||||
for(int i=0; i<MAXSONDE; i++) {
|
||||
// Skip non-active entries (but don't loop forever if there are no active ones)
|
||||
for(int i=0; i<config.maxsonde; i++) {
|
||||
if(!sondeList[currentSonde].active) {
|
||||
currentSonde++;
|
||||
if(currentSonde>=nSonde) currentSonde=0;
|
||||
|
@ -131,9 +220,6 @@ void Sonde::setup() {
|
|||
dfm.setFrequency(sondeList[currentSonde].freq * 1000000);
|
||||
break;
|
||||
}
|
||||
// Update display
|
||||
//updateDisplayRXConfig();
|
||||
//updateDisplay();
|
||||
}
|
||||
int Sonde::receiveFrame() {
|
||||
int ret;
|
||||
|
@ -143,61 +229,61 @@ int Sonde::receiveFrame() {
|
|||
ret = dfm.receiveFrame();
|
||||
}
|
||||
memmove(sonde.si()->rxStat+1, sonde.si()->rxStat, 17);
|
||||
sonde.si()->rxStat[0] = ret==0 ? 3 : 1; // OK or Timeout; TODO: add error (2)
|
||||
return ret; // 0: OK, 1: Timeuot, 2: Other error (TODO)
|
||||
sonde.si()->rxStat[0] = ret;
|
||||
return ret; // 0: OK, 1: Timeuot, 2: Other error, 3: unknown
|
||||
}
|
||||
|
||||
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);
|
||||
snprintf(buf, 16, si()->alt>999?" %5.0fm":" %3.1fm", si()->alt);
|
||||
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() {
|
||||
|
@ -206,32 +292,35 @@ 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);
|
||||
//snprintf(buf, 8, "%s", si()->launchsite);
|
||||
//u8x8->drawString(0,5, 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]);
|
||||
snprintf(buf, 16, "%3.3f MHz", si()->freq);
|
||||
u8x8.drawString(0,3, buf);
|
||||
u8x8->setFont(u8x8_font_7x14_1x2_r);
|
||||
u8x8->drawString(0, 0, "Scan:");
|
||||
u8x8->drawString(8, 0, sondeTypeStr[si()->type]);
|
||||
snprintf(buf, 16, "%3.3f MHz", si()->freq);
|
||||
u8x8->drawString(0,3, buf);
|
||||
//snprintf(buf, 8, "%s", si()->launchsite);
|
||||
//u8x8->drawString(0,5, buf);
|
||||
updateDisplayIP();
|
||||
}
|
||||
|
||||
|
@ -244,11 +333,11 @@ void Sonde::updateDisplay()
|
|||
updateDisplayPos2();
|
||||
updateDisplayRSSI();
|
||||
updateStat();
|
||||
updateDisplayIP();
|
||||
updateDisplayIP();
|
||||
}
|
||||
|
||||
void Sonde::clearDisplay() {
|
||||
u8x8.clearDisplay();
|
||||
u8x8->clearDisplay();
|
||||
}
|
||||
|
||||
Sonde sonde = Sonde();
|
||||
|
|
|
@ -7,15 +7,29 @@
|
|||
// RX_TIMEOUT: no header detected
|
||||
// RX_ERROR: header detected, but data not decoded (crc error, etc.)
|
||||
// RX_OK: header and data ok
|
||||
enum RxResult { RX_OK, RX_TIMEOUT, RX_ERROR };
|
||||
enum RxResult { RX_OK, RX_TIMEOUT, RX_ERROR, RX_UNKNOWN };
|
||||
|
||||
enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41 };
|
||||
extern const char *sondeTypeStr[5];
|
||||
|
||||
typedef struct st_rdzconfig {
|
||||
int button_pin; // pin number of second button (for some boards)
|
||||
int led_pin; // pin number of LED
|
||||
int oled_sda; // OLED data pin
|
||||
int oled_scl; // OLED clock pin
|
||||
int oled_rst; // OLED reset pin
|
||||
int debug; // show port and config options after reboot
|
||||
int wifi; // connect to known WLAN 0=skip
|
||||
int wifiap; // enable/disable WiFi AccessPoint mode 0=disable
|
||||
int startfreq; // spectrum display start freq (400, 401, ...)
|
||||
int channelbw; // spectrum channel bandwidth (valid: 5, 10, 20, 25, 50, 100 kHz)
|
||||
int spectrum; // show freq spectrum for n seconds 0=disable
|
||||
int timer; // show remaining time in spectrum 0=disable
|
||||
int marker; // show freq marker in spectrum 0=disable
|
||||
int maxsonde; // number of max sonde in scan (range=1-99)
|
||||
int noisefloor; // for spectrum display
|
||||
char call[9];
|
||||
char passcode[9];
|
||||
char call[9]; // APRS callsign
|
||||
char passcode[9]; // APRS passcode
|
||||
// for now, one feed for each type is enough, but might get extended to more?
|
||||
struct st_feedinfo udpfeed; // target for AXUDP messages
|
||||
struct st_feedinfo tcpfeed; // target for APRS-IS TCP connections
|
||||
|
@ -23,28 +37,29 @@ typedef struct st_rdzconfig {
|
|||
|
||||
typedef struct st_sondeinfo {
|
||||
// receiver configuration
|
||||
bool active;
|
||||
bool active;
|
||||
SondeType type;
|
||||
float freq;
|
||||
// decoded ID
|
||||
char id[10];
|
||||
bool validID;
|
||||
char *launchsite;
|
||||
// decoded position
|
||||
float lat;
|
||||
float lon;
|
||||
float hei;
|
||||
float vs;
|
||||
float hs;
|
||||
float dir; // 0..360
|
||||
float lat; // latitude
|
||||
float lon; // longitude
|
||||
float alt; // altitude
|
||||
float vs; // vertical speed
|
||||
float hs; // horizontal speed
|
||||
float dir; // 0..360
|
||||
uint8_t validPos; // bit pattern for validity of above 6 fields
|
||||
// RSSI from receiver
|
||||
int rssi;
|
||||
int rssi; // signal strength
|
||||
uint8_t rxStat[20];
|
||||
} SondeInfo;
|
||||
// rxState: 0=undef[empty] 1=timeout[.] 2=errro[E] 3=ok[1]
|
||||
|
||||
|
||||
#define MAXSONDE 10
|
||||
#define MAXSONDE 99
|
||||
|
||||
class Sonde
|
||||
{
|
||||
|
@ -56,9 +71,10 @@ public:
|
|||
SondeInfo sondeList[MAXSONDE+1];
|
||||
|
||||
Sonde();
|
||||
void setConfig(const char *str);
|
||||
|
||||
void clearSonde();
|
||||
void addSonde(float frequency, SondeType type, int active);
|
||||
void addSonde(float frequency, SondeType type, int active, char *launchsite);
|
||||
void nextConfig();
|
||||
void setup();
|
||||
|
||||
|
|
|
@ -211,10 +211,47 @@ extern int aprsstr_mon2raw(const char *mon, char raw[], int raw_len)
|
|||
#define FEET (1.0/0.3048)
|
||||
#define KNOTS (1.851984)
|
||||
|
||||
#define X2C_max_longcard 0xFFFFFFFFUL
|
||||
static uint32_t X2C_TRUNCC(double x, uint32_t min0, uint32_t max0)
|
||||
{
|
||||
uint32_t i;
|
||||
|
||||
if (x < (double)min0)
|
||||
i = (uint32_t)min0;
|
||||
if (x > (double)max0)
|
||||
i = (uint32_t)max0;
|
||||
|
||||
i = (uint32_t)x;
|
||||
if ((double)i > x)
|
||||
--i;
|
||||
return i;
|
||||
}
|
||||
|
||||
|
||||
static uint32_t truncc(double r)
|
||||
{
|
||||
if (r<=0.0) return 0UL;
|
||||
else if (r>=2.E+9) return 2000000000UL;
|
||||
else return (uint32_t)X2C_TRUNCC(r,0UL,X2C_max_longcard);
|
||||
return 0;
|
||||
} /* end truncc() */
|
||||
|
||||
|
||||
|
||||
static uint32_t dao91(double x)
|
||||
/* radix91(xx/1.1) of dddmm.mmxx */
|
||||
{
|
||||
double a;
|
||||
a = fabs(x);
|
||||
return ((truncc((a-(double)(float)truncc(a))*6.E+5)%100UL)
|
||||
*20UL+11UL)/22UL;
|
||||
} /* end dao91() */
|
||||
|
||||
|
||||
char b[201];
|
||||
char raw[201];
|
||||
|
||||
char * aprs_senddata(float lat, float lon, float hei, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym)
|
||||
char * aprs_senddata(float lat, float lon, float alt, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym)
|
||||
{
|
||||
*b=0;
|
||||
aprsstr_append(b, usercall);
|
||||
|
@ -244,11 +281,11 @@ char * aprs_senddata(float lat, float lon, float hei, float speed, float dir, fl
|
|||
snprintf(b+i, APRS_MAXLEN-i, "%03d/%03d", realcard(dir+1.5), realcard(speed*1.0/KNOTS+0.5));
|
||||
}
|
||||
#endif
|
||||
if(hei>0.5) {
|
||||
if(alt>0.5) {
|
||||
i=strlen(b);
|
||||
snprintf(b+i, APRS_MAXLEN-i, "/A=%06d", realcard(hei*FEET+0.5));
|
||||
snprintf(b+i, APRS_MAXLEN-i, "/A=%06d", realcard(alt*FEET+0.5));
|
||||
}
|
||||
#if 0
|
||||
#if 1
|
||||
int dao=1;
|
||||
if(dao) {
|
||||
i=strlen(b);
|
||||
|
|
|
@ -9,6 +9,7 @@ typedef struct st_feedinfo {
|
|||
int type; // 0:UDP(axudp), 1:TCP(aprs.fi)
|
||||
char host[64];
|
||||
int port;
|
||||
char symbol[3];
|
||||
int lowrate;
|
||||
int highrate;
|
||||
int lowlimit;
|
||||
|
@ -19,7 +20,7 @@ typedef struct st_feedinfo {
|
|||
#define APRS_MAXLEN 201
|
||||
void aprs_gencrctab(void);
|
||||
int aprsstr_mon2raw(const char *mon, char raw[], int raw_len);
|
||||
char * aprs_senddata(float lat, float lon, float hei, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym);
|
||||
char * aprs_senddata(float lat, float lon, float alt, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym);
|
||||
|
||||
|
||||
#endif
|
||||
|
|
Ładowanie…
Reference in New Issue