Merge pull request #1 from oh3bsg/devel

Devel
pull/80/head
oh3bsg 2021-04-02 12:57:57 +03:00 zatwierdzone przez GitHub
commit f6161a9c9f
Nie znaleziono w bazie danych klucza dla tego podpisu
ID klucza GPG: 4AEE18F83AFDEB23
40 zmienionych plików z 3063 dodań i 930 usunięć

3
.gitignore vendored
Wyświetl plik

@ -30,3 +30,6 @@
*.exe
*.out
*.app
.pio
.vscode

Wyświetl plik

@ -7,21 +7,28 @@ before_install:
- "/sbin/start-stop-daemon --start --quiet --pidfile /tmp/custom_xvfb_1.pid --make-pidfile --background --exec /usr/bin/Xvfb -- :1 -ac -screen 0 1280x1024x16"
- sleep 3
- export DISPLAY=:1.0
- wget https://downloads.arduino.cc/arduino-1.8.10-linux64.tar.xz
- tar xf arduino-1.8.10-linux64.tar.xz
- sudo mv arduino-1.8.10 /usr/local/share/arduino
- wget https://downloads.arduino.cc/arduino-1.8.13-linux64.tar.xz
- tar xf arduino-1.8.13-linux64.tar.xz
- sudo mv arduino-1.8.13 /usr/local/share/arduino
- sudo ln -s /usr/local/share/arduino/arduino /usr/local/bin/arduino
- wget https://github.com/me-no-dev/ESPAsyncWebServer/archive/master.zip
- unzip master.zip
- sudo mv ESPAsyncWebServer-master /usr/local/share/arduino/libraries/ESPAsyncWebServer
- rm master.zip
- sudo mv ESPAsyncWebServer-master /usr/local/share/arduino/libraries/ESPAsyncWebServer
- wget https://github.com/me-no-dev/AsyncTCP/archive/master.zip
- unzip master.zip
- rm master.zip
- sudo mv AsyncTCP-master /usr/local/share/arduino/libraries/AsyncTCP
- wget https://github.com/me-no-dev/arduino-esp32fs-plugin/releases/download/1.0/ESP32FS-1.0.zip
- wget https://github.com/lewisxhe/AXP202X_Library/archive/v1.0.zip
- unzip v1.0.zip
- sudo mv AXP202X_Library-1.0 /usr/local/share/arduino/libraries/
- wget https://github.com/dx168b/async-mqtt-client/archive/master.zip
- unzip master.zip
- rm master.zip
- sudo mv async-mqtt-client-master /usr/local/share/arduino/libraries/
# Trying to get rid of mDNS warnings (1000s of them...)
# as suggested by https://forum.arduino.cc/index.php?topic=469428.0
# Arduino IDE adds a lot of noise caused by network traffic, trying to firewall it off
@ -40,7 +47,6 @@ install:
- arduino --pref "build.path=$PWD/build" --save-prefs
- arduino --install-boards esp32:esp32 --save-prefs
- ln -s $PWD/libraries/SondeLib /usr/local/share/arduino/libraries/SondeLib
- ln -s $PWD/libraries/SX1278FSK /usr/local/share/arduino/libraries/SX1278FSK
- arduino --install-library "U8g2"
- arduino --install-library "MicroNMEA"
script:

Wyświetl plik

@ -13,16 +13,21 @@ generate_website_index() {
echo '<p class="view"><a href="https://github.com/dl9rdz/rdz_ttgo_sonde">View the Project on GitHub <small>dl9rdz/rdz_ttgo_sonde</small></a></p>' >> download.html
echo '</header><section><h1 id="rdz_ttgo_sonde">rdz_ttgo_sonde</h1>' >> download.html
echo "<h2>Master repository</h2><ul>" >> download.html
for i in `ls master`; do
for i in `ls master|sort -r`; do
TS=`git log master/$i | grep "Date:" | head -1 | awk '{$1="";$2="";$7="";print substr($0,3,length($0)-3)}'`
if [ -z "$TS" ]; then TS=`date`; fi
echo "<li><a href=\"master/$i\">$i</a> ($TS)</li>\n" >> download.html;
done
echo "</ul><h2>Development repository</h2><ul>" >> download.html
for i in `ls devel`; do
for i in `ls devel|sort -r|grep "\.bin"`; do
TS=`git log devel/$i | grep "Date:" | head -1 | awk '{$1="";$2="";$7="";print substr($0,3,length($0)-3)}'`
if [ -z "$TS" ]; then TS=`date`; fi
echo "<li><a href=\"devel/$i\">$i</a> ($TS)</li>\n" >> download.html;
VERS=`basename $i -full.bin`
CL=`cat devel/${VERS}-changelog.txt 2>/dev/null`
echo "VERS $VERS: CL $CL"
echo "<li><a href=\"devel/$i\">$i</a> ($TS)" >> download.html
if [ -n "${CL}" ]; then echo "<br>${CL}" >> download.html; fi
echo "</li>\n" >> download.html
done
echo "</ul>
<br>
@ -54,6 +59,8 @@ commit_website_files() {
git add ${BRANCH}/${VERSION}-full.bin
cp ${MYPATH}/build/RX_FSK.ino.bin ${BRANCH}/update.ino.bin
git add ${BRANCH}/update.ino.bin
echo "${TRAVIS_COMMIT_MESSAGE}" > ${BRANCH}/${VERSION}-changelog.txt
git add ${BRANCH}/${VERSION}-changelog.txt
git commit --message "Travis build: $TRAVIS_BUILD_NUMBER"
}
upload_files() {

Wyświetl plik

@ -1,16 +1,14 @@
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.
This a simple, experimental decoder for radiosonde RS41, RS92, DFM06/09/17 and M10/M20 on
a TTGO LoRa ESP32 board with either a OLED or extern TFT display.
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
Please consult the Wiki at https://github.com/dl9rdz/rdz_ttgo_sonde/wiki/Supported-boards
for details on supported boardsi, and additional setup instructions.
## 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:
@ -19,6 +17,10 @@ issue some commands. The software distinguishes between several inputs:
- MID Medium-length button press (2-4 seconds)
- LONG Long button press (>5 seconds)
You can optionally use a second button, which you have to add manually to your board.
See https://github.com/dl9rdz/rdz_ttgo_sonde/wiki/Hardware-configuration for details.
## Wireless configuration
On startup, as well as after a LONG button press, the WiFI configuration will
@ -32,19 +34,23 @@ bottom line. Then the board will switch to scanning mode.
## Scanning mode
In the scanning mode, the board will iterate over all channels configured in
channels.txt, trying to decode a radio sonde on each channel for about 1 second
for RS41, a bit less for DMF06/09. If a valid signal is found, the board switches
to receiving mode on that channel. a SHORT buttong press will also switch to
receiving mode.
channels.txt, trying to decode a radio sonde on each channel for about 1 second.
If a valid signal is found, the board switches to receiving mode on that channel.
A SHORT buttong press will also switch to receiving mode.
## Receiving mode
In receiving mode, a single frequency will be decoded, and sonde info (ID, GPS
coordinates, RSSI) will be displayed. The bar above the IP address indicates,
for the last 18 frames, if reception was successfull (|) or failed (.)
for the last 18 frames, if reception was successfull (|) or failed (.), or had
some errors (E), e.g., CRC check failed.
A DOUBLE press will switch to scanning mode.
A SHORT press will switch to the next channel in channels.txt
A SHORT press on the second button will switch to a different display screen.
## Spectrum mode
A medium press will active scan the whole band (400..406 MHz) and display a

Wyświetl plik

@ -3,7 +3,6 @@
#include <WiFi.h>
#include <WiFiUdp.h>
#include <ESPAsyncWebServer.h>
#include <SPIFFS.h>
//#include <U8x8lib.h>
//#include <U8g2lib.h>
@ -21,7 +20,9 @@
#include "version.h"
#include "geteph.h"
#include "rs92gps.h"
#include "mqtt.h"
#include "esp_heap_caps.h"
//#define ESP_MEM_DEBUG 1
int e;
enum MainState { ST_DECODER, ST_SPECTRUM, ST_WIFISCAN, ST_UPDATE, ST_TOUCHCALIB };
@ -47,9 +48,16 @@ boolean connected = false;
WiFiUDP udp;
WiFiClient client;
// KISS over TCP für communicating with APRSdroid
// KISS over TCP for communicating with APRSdroid
WiFiServer tncserver(14580);
WiFiClient tncclient;
// JSON over TCP for communicating with my kotlin andoird test stuff
WiFiServer rdzserver(14570);
WiFiClient rdzclient;
unsigned long lastMqttUptime = 0;
boolean mqttEnabled;
MQTT mqttclient;
boolean forceReloadScreenConfig = false;
@ -74,6 +82,10 @@ static int currentDisplay = 1;
// timestamp when spectrum display was activated
static unsigned long specTimer;
void enterMode(int mode);
void WiFiEvent(WiFiEvent_t event);
// Read line from file, independent of line termination (LF or CR LF)
String readLine(Stream &stream) {
String s = stream.readStringUntil('\n');
@ -88,8 +100,11 @@ String readLine(Stream &stream) {
int readLine(Stream &stream, char *buffer, int maxlen) {
int n = stream.readBytesUntil('\n', buffer, maxlen);
buffer[n] = 0;
if(n <= 0) return 0;
if(buffer[n-1]=='\r') { buffer[n-1]=0; n--; }
if (n <= 0) return 0;
if (buffer[n - 1] == '\r') {
buffer[n - 1] = 0;
n--;
}
return n;
}
@ -122,13 +137,13 @@ const String sondeTypeSelect(int activeType) {
String sts = "";
for (int i = 0; i < NSondeTypes; i++) {
sts += "<option value=\"";
sts += sondeTypeStr[i];
sts += sondeTypeLongStr[i];
sts += "\"";
if (activeType == i) {
sts += " selected";
}
sts += ">";
sts += sondeTypeStr[i];
sts += sondeTypeLongStr[i];
sts += "</option>";
}
return sts;
@ -169,14 +184,20 @@ void setupChannelList() {
type = STYPE_RS92;
}
else if (space[1] == '9') {
type = STYPE_DFM09;
type = STYPE_DFM09_OLD;
}
else if (space[1] == '6') {
type = STYPE_DFM06;
type = STYPE_DFM06_OLD;
}
else if (space[1] == 'D') {
type = STYPE_DFM;
}
else if (space[1] == 'M') {
type = STYPE_M10;
}
else if (space[1] == '2') {
type = STYPE_M20;
}
else continue;
int active = space[3] == '+' ? 1 : 0;
if (space[4] == ' ') {
@ -195,22 +216,50 @@ 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>Launchsite</th><th>Mode</th></tr>");
strcpy(ptr, "<html><head><link rel=\"stylesheet\" type=\"text/css\" href=\"style.css\">");
strcat(ptr, "<script type=\"text/javascript\">"
"let stypes=new Map();"
"stypes.set('4', 'RS41');"
"stypes.set('R', 'RS92');"
"stypes.set('9', 'DFM9 (old)');"
"stypes.set('6', 'DFM6 (old)');"
"stypes.set('D', 'DFM');"
"stypes.set('M', 'M10');"
"stypes.set('2', 'M20');"
"function prep() {"
" var stlist=document.querySelectorAll(\"input.stype\");"
" for(txt of stlist){"
" var val=txt.getAttribute('value'); var nam=txt.getAttribute('name'); "
" var sel=document.createElement('select');"
" sel.setAttribute('name',nam);"
" for(stype of stypes) { "
" var opt=document.createElement('option');"
" opt.value=stype[0];"
" opt.innerHTML=stype[1];"
" if(stype[0]==val) { opt.setAttribute('selected','selected'); }"
" sel.appendChild(opt);"
" } txt.replaceWith(sel); } } "
" window.onload = prep; "
"</script>");
strcat(ptr, "</head><body><form action=\"qrg.html\" method=\"post\"><table><tr><th>ID</th><th>Active</th><th>Freq</th><th>Launchsite</th><th>Mode</th></tr>");
for (int i = 0; i < sonde.config.maxsonde; i++) {
String s = sondeTypeSelect(i >= sonde.nSonde ? 2 : sonde.sondeList[i].type);
//String s = sondeTypeSelect(i >= sonde.nSonde ? 2 : sonde.sondeList[i].type);
String site = sonde.sondeList[i].launchsite;
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>"
"<td><input name=\"S%d\" type=\"text\" value=\"%s\"></td>"
"<td><select name=\"T%d\">%s</select></td>",
//"<td><select name=\"T%d\">%s</select></td>",
"<td><input class='stype' name='T%d' value='%c'>",
i + 1,
i + 1, (i < sonde.nSonde && sonde.sondeList[i].active) ? "checked" : "",
i + 1, i >= sonde.nSonde ? 400.000 : sonde.sondeList[i].freq,
i + 1, i >= sonde.nSonde ? " " : sonde.sondeList[i].launchsite,
i + 1, s.c_str());
i + 1, i >= sonde.nSonde ? 2 : sondeTypeChar[sonde.sondeList[i].type] );
//i + 1, s.c_str());
}
strcat(ptr, "</table><input type=\"submit\" value=\"Update\"/></form></body></html>");
Serial.printf("QRG form: size=%d bytes\n",strlen(message));
Serial.printf("QRG form: size=%d bytes\n", strlen(message));
return message;
}
@ -250,7 +299,7 @@ const char *handleQRGPost(AsyncWebServerRequest *request) {
const char *tstr = tstring.c_str();
const char *sstr = sstring.c_str();
Serial.printf("Processing a=%s, f=%s, t=%s, site=%s\n", active ? "YES" : "NO", fstr, tstr, sstr);
char typech = (tstr[2] == '4' ? '4' : tstr[2] == '9' ? 'R' : tstr[0] == 'M' ? 'M' : tstr[3]); // a bit ugly
char typech = tstr[0];
file.printf("%3.3f %c %c %s\n", atof(fstr), typech, active ? '+' : '-', sstr);
}
file.close();
@ -314,7 +363,7 @@ const char *createWIFIForm() {
i + 1, i < nNetworks ? networks[i].pw.c_str() : "");
}
strcat(ptr, "</table><input type=\"submit\" value=\"Update\"></input></form></body></html>");
Serial.printf("WIFI form: size=%d bytes\n",strlen(message));
Serial.printf("WIFI form: size=%d bytes\n", strlen(message));
return message;
}
@ -362,9 +411,9 @@ void addSondeStatus(char *ptr, int i)
struct tm ts;
SondeInfo *s = &sonde.sondeList[i];
strcat(ptr, "<table>");
sprintf(ptr + strlen(ptr), "<tr><td id=\"sfreq\">%3.3f MHz, Type: %s</td><tr><td>ID: %s", s->freq, sondeTypeStr[s->type],
sprintf(ptr + strlen(ptr), "<tr><td id=\"sfreq\">%3.3f MHz, Type: %s</td><tr><td>ID: %s", s->freq, sondeTypeLongStr[s->type],
s->validID ? s->id : "<?""?>");
if (s->validID && (s->type == STYPE_DFM06 || s->type == STYPE_DFM09 || s->type == STYPE_M10)) {
if (s->validID && (TYPE_IS_DFM(s->type) || TYPE_IS_METEO(s->type)) ) {
sprintf(ptr + strlen(ptr), " (ser: %s)", s->ser);
}
sprintf(ptr + strlen(ptr), "</td></tr><tr><td>QTH: %.6f,%.6f h=%.0fm</td></tr>\n", s->lat, s->lon, s->alt);
@ -377,8 +426,11 @@ void addSondeStatus(char *ptr, int i)
s->burstKT, s->launchKT, s->countKT, ((uint16_t)s->frame - s->crefKT));
}
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);
sprintf(ptr + strlen(ptr), "<a target=\"_empty\" href=\"https://wetterson.de/karte/?%s\">wetterson.de</a> - ", s->id);
sprintf(ptr + strlen(ptr), "<a target=\"_empty\" href=\"https://radiosondy.info/sonde_archive.php?sondenumber=%s\">radiosondy.info</a> - ", s->id);
sprintf(ptr + strlen(ptr), "<a target=\"_empty\" href=\"https://www.openstreetmap.org/?mlat=%.6f&mlon=%.6f&zoom=14\">OSM</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</a></td></tr>", s->lat, s->lon);
strcat(ptr, "</table><p/>\n");
}
@ -393,7 +445,7 @@ const char *createStatusForm() {
}
}
strcat(ptr, "</body></html>");
Serial.printf("Status form: size=%d bytes\n",strlen(message));
Serial.printf("Status form: size=%d bytes\n", strlen(message));
return message;
}
@ -426,13 +478,14 @@ struct st_configitems config_list[] = {
{"wifi", "Wifi mode (0/1/2/3)", 0, &sonde.config.wifi},
{"debug", "Debug mode (0/1)", 0, &sonde.config.debug},
{"maxsonde", "Maxsonde", 0, &sonde.config.maxsonde},
{"screenfile", "Screen config (0=old, 1=OLED, 2=TFT, 3=TFT[port])", 0, &sonde.config.screenfile},
{"display", "Display screens (scan,default,...)", -6, sonde.config.display},
/* Spectrum display settings */
{"spectrum", "Show spectrum (-1=no, 0=forever, >0=seconds)", 0, &sonde.config.spectrum},
{"startfreq", "Startfreq (MHz)", 0, &sonde.config.startfreq},
{"channelbw", "Bandwidth (kHz)", 0, &sonde.config.channelbw},
{"marker", "Spectrum MHz marker", 0, &sonde.config.marker},
{"noisefloor", "Sepctrum noisefloor", 0, &sonde.config.noisefloor},
{"noisefloor", "Spectrum noisefloor", 0, &sonde.config.noisefloor},
/* decoder settings */
{"", "Receiver configuration", -5, NULL},
{"showafc", "Show AFC value", 0, &sonde.config.showafc},
@ -441,8 +494,11 @@ struct st_configitems config_list[] = {
{"rs41.rxbw", "RS41 RX bandwidth", 0, &sonde.config.rs41.rxbw},
{"rs92.rxbw", "RS92 RX (and AGC) bandwidth", 0, &sonde.config.rs92.rxbw},
{"rs92.alt2d", "RS92 2D fix default altitude", 0, &sonde.config.rs92.alt2d},
{"dfm.agcbw", "DFM6/9 AGC bandwidth", 0, &sonde.config.dfm.agcbw},
{"dfm.rxbw", "DFM6/9 RX bandwidth", 0, &sonde.config.dfm.rxbw},
{"dfm.agcbw", "DFM AGC bandwidth", 0, &sonde.config.dfm.agcbw},
{"dfm.rxbw", "DFM RX bandwidth", 0, &sonde.config.dfm.rxbw},
{"m10m20.agcbw", "M10/M20 AGC bandwidth", 0, &sonde.config.m10m20.agcbw},
{"m10m20.rxbw", "M10/M20 RX bandwidth", 0, &sonde.config.m10m20.rxbw},
{"ephftp", "FTP for eph (RS92)", 39, &sonde.config.ephftp},
{"", "Data feed configuration", -5, NULL},
/* APRS settings */
{"call", "Call", 8, sonde.config.call},
@ -462,6 +518,16 @@ struct st_configitems config_list[] = {
{"tcp.port", "APRS TCP Port", 0, &sonde.config.tcpfeed.port},
{"tcp.idformat", "DFM ID Format", -2, &sonde.config.tcpfeed.idformat},
{"tcp.highrate", "Rate limit", 0, &sonde.config.tcpfeed.highrate},
/* MQTT */
{"mqtt.active", "MQTT Active (needs reboot)", 0, &sonde.config.mqtt.active},
{"mqtt.id", "MQTT client ID", 63, &sonde.config.mqtt.id},
{"mqtt.host", "MQTT server hostname", 63, &sonde.config.mqtt.host},
{"mqtt.port", "MQTT Port", 0, &sonde.config.mqtt.port},
{"mqtt.username", "MQTT Username", 63, &sonde.config.mqtt.username},
{"mqtt.password", "MQTT Password", 63, &sonde.config.mqtt.password},
{"mqtt.prefix", "MQTT Prefix", 63, &sonde.config.mqtt.prefix},
/* Hardware dependeing settings */
{"", "Hardware configuration (requires reboot)", -5, NULL},
{"disptype", "Display type (0=OLED/SSD1306, 1=TFT/ILI9225, 2=OLED/SH1106)", 0, &sonde.config.disptype},
@ -481,6 +547,7 @@ struct st_configitems config_list[] = {
{"gps_rxd", "GPS RXD pin (-1 to disable)", 0, &sonde.config.gps_rxd},
{"gps_txd", "GPS TXD pin (not really needed)", 0, &sonde.config.gps_txd},
{"mdnsname", "mDNS name", 14, &sonde.config.mdnsname},
};
const static int N_CONFIG = (sizeof(config_list) / sizeof(struct st_configitems));
@ -570,7 +637,7 @@ const char *createConfigForm() {
}
}
strcat(ptr, "</table><input type=\"submit\" value=\"Update\"></input></form></body></html>");
Serial.printf("Config form: size=%d bytes\n",strlen(message));
Serial.printf("Config form: size=%d bytes\n", strlen(message));
return message;
}
@ -643,7 +710,7 @@ const char *createControlForm() {
strcat(ptr, "\"></input><br>");
}
strcat(ptr, "</form></body></html>");
Serial.printf("Control form: size=%d bytes\n",strlen(message));
Serial.printf("Control form: size=%d bytes\n", strlen(message));
return message;
}
@ -692,6 +759,7 @@ const char *handleControlPost(AsyncWebServerRequest *request) {
// bad idea. prone to buffer overflow. use at your own risk...
const char *createEditForm(String filename) {
Serial.println("Creating edit form");
char *ptr = message;
File file = SPIFFS.open("/" + filename, "r");
if (!file) {
@ -710,41 +778,45 @@ const char *createEditForm(String filename) {
strcat(ptr, line.c_str()); strcat(ptr, "\n");
}
strcat(ptr, "</textarea><input type=\"submit\" value=\"Save\"></input></form></body></html>");
Serial.printf("Edit form: size=%d bytes\n",strlen(message));
Serial.printf("Edit form: size=%d bytes\n", strlen(message));
return message;
}
const char *handleEditPost(AsyncWebServerRequest *request) {
Serial.println("Handling post request");
int params = request->params();
Serial.printf("Post:, %d params\n", params);
for(int i = 0; i < params; i++) {
AsyncWebParameter* p = request->getParam(i);
String name = p->name();
String value = p->value();
if(name.c_str()==NULL) { name=String("NULL"); }
if(value.c_str()==NULL) { value=String("NULL"); }
if(p->isFile()){
Serial.printf("_FILE[%s]: %s, size: %u\n", name.c_str(), value.c_str(), p->size());
} else if(p->isPost()){
Serial.printf("_POST[%s]: %s\n", name.c_str(), value.c_str());
} else {
Serial.printf("_GET[%s]: %s\n", name.c_str(), value.c_str());
}
int params = request->params();
Serial.printf("Post:, %d params\n", params);
for (int i = 0; i < params; i++) {
AsyncWebParameter* p = request->getParam(i);
String name = p->name();
String value = p->value();
if (name.c_str() == NULL) {
name = String("NULL");
}
if (value.c_str() == NULL) {
value = String("NULL");
}
if (p->isFile()) {
Serial.printf("_FILE[%s]: %s, size: %u\n", name.c_str(), value.c_str(), p->size());
} else if (p->isPost()) {
Serial.printf("_POST[%s]: %s\n", name.c_str(), value.c_str());
} else {
Serial.printf("_GET[%s]: %s\n", name.c_str(), value.c_str());
}
}
AsyncWebParameter *filep = request->getParam("file");
if (!filep) return NULL;
String filename = filep->value();
Serial.printf("Writing file <%s>\n",filename.c_str());
Serial.printf("Writing file <%s>\n", filename.c_str());
AsyncWebParameter *textp = request->getParam("text", true);
if (!textp) return NULL;
Serial.printf("Parameter size is %d\n", textp->size());
Serial.printf("Multipart: %d contentlen=%d \n",
request->multipart(), request->contentLength());
request->multipart(), request->contentLength());
String content = textp->value();
if(content.length()==0) {
if (content.length() == 0) {
Serial.println("File is empty. Not written.");
return NULL;
}
@ -757,7 +829,7 @@ const char *handleEditPost(AsyncWebServerRequest *request) {
int len = file.print(content);
file.close();
Serial.printf("Written: %d bytes\n", len);
if (strcmp(filename.c_str(), "screens.txt") == 0) {
if (strncmp(filename.c_str(), "screens", 7) == 0) {
// screens update => reload
forceReloadScreenConfig = true;
}
@ -773,7 +845,7 @@ const char *createUpdateForm(boolean run) {
strcat(ptr, "<input type=\"submit\" name=\"master\" value=\"Master-Update\"></input><br><input type=\"submit\" name=\"devel\" value=\"Devel-Update\">");
}
strcat(ptr, "</form></body></html>");
Serial.printf("Update form: size=%d bytes\n",strlen(message));
Serial.printf("Update form: size=%d bytes\n", strlen(message));
return message;
}
@ -831,32 +903,6 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT
Serial.println("Client disconnected");
}
}
#if 0
void onWebSocketEvent(uint8_t clientNum, WStype_t type, uint8_t *payload, size_t length) {
switch (type) {
case WStype_DISCONNECTED:
Serial.printf("[%u] WS client disconnected\n", clientNum);
break;
case WStype_CONNECTED:
{
IPAddress ip = webSocket.remoteIP(clientNum);
Serial.printf("[%u] WS client connection from %s\n", clientNum, ip.toString().c_str());
}
break;
case WStype_TEXT:
//
{
char msg[80];
Serial.printf("[%u] WS client sent me some text: %s\n", clientNum, payload);
snprintf(msg, 80, "You sent me: %s\n", payload);
webSocket.sendTXT(clientNum, msg);
}
break;
default:
break;
}
}
#endif
const char* PARAM_MESSAGE = "message";
@ -924,19 +970,21 @@ void SetupAsyncServer() {
});
server.on("/edit.html", HTTP_POST, [](AsyncWebServerRequest * request) {
const char *ret = handleEditPost(request);
if(ret==NULL)
request->send(200, "text/html", "<html><head>ERROR</head><body><p>Something went wrong. Uploaded file is empty.</p></body></hhtml>");
if (ret == NULL)
request->send(200, "text/html", "<html><head>ERROR</head><body><p>Something went wrong. Uploaded file is empty.</p></body></hhtml>");
else
request->send(200, "text/html", createEditForm(request->getParam(0)->value()));
request->send(200, "text/html", createEditForm(request->getParam(0)->value()));
},
NULL,
[](AsyncWebServerRequest * request, uint8_t *data, size_t len, size_t index, size_t total) {
Serial.printf("post data: index=%d len=%d total=%d\n", index, len, total);
Serial.printf("post data: index=%d len=%d total=%d\n", index, len, total);
});
// Route to load style.css file
server.on("/style.css", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(SPIFFS, "/style.css", "text/css");
AsyncWebServerResponse *response = request->beginResponse(SPIFFS, "/style.css", "text/css");
response->addHeader("Cache-Control","max-age=86400");
request->send(response);
});
// Route to set GPIO to HIGH
@ -1077,17 +1125,25 @@ void initTouch() {
char buffer[85];
MicroNMEA nmea(buffer, sizeof(buffer));
int lastCourse = 0;
void unkHandler(const MicroNMEA& nmea) {
/// Arrg. MicroNMEA changes type definition... so lets auto-infer type
template<typename T>
//void unkHandler(const MicroNMEA& nmea) {
void unkHandler(T nmea) {
if (strcmp(nmea.getMessageID(), "VTG") == 0) {
const char *s = nmea.getSentence();
while (*s && *s != ',') s++;
if (*s == ',') s++; else return;
if (*s == ',') return; /// no new course data
lastCourse = nmea.parseFloat(s, 0, NULL);
int lastCourse = nmea.parseFloat(s, 0, NULL);
Serial.printf("Course update: %d\n", lastCourse);
}
}
#define DEBUG_GPS 0
static bool gpsCourseOld;
static int lastCourse;
void gpsTask(void *parameter) {
nmea.setUnknownSentenceHandler(unkHandler);
@ -1096,25 +1152,58 @@ void gpsTask(void *parameter) {
char c = Serial2.read();
//Serial.print(c);
if (nmea.process(c)) {
//Serial.println(nmea.getSentence());
long lat = nmea.getLatitude();
long lon = nmea.getLongitude();
long alt = -1;
bool b = nmea.getAltitude(alt);
bool valid = nmea.isValid();
int course = nmea.getCourse() / 1000;
gpsPos.valid = nmea.isValid();
if(gpsPos.valid) {
gpsPos.lon = nmea.getLongitude()*0.000001;
gpsPos.lat = nmea.getLatitude()*0.000001;
long alt = 0;
nmea.getAltitude(alt);
gpsPos.alt=(int)(alt/1000);
gpsPos.course = (int)(nmea.getCourse()/1000);
gpsCourseOld = false;
if(gpsPos.course==0) {
// either north or not new
if(lastCourse!=0) // use old value...
{
gpsCourseOld = true;
gpsPos.course = lastCourse;
}
}
}
#ifdef DEBUG_GPS
uint8_t hdop = nmea.getHDOP();
//Serial.printf("\nDecode: valid: %d N %ld E %ld alt %ld (%d) course:%d dop:%d", valid ? 1 : 0, lat, lon, alt, b, c, hdop);
Serial.printf(" =>: valid: %d N %f E %f alt %d course:%d dop:%d\n", gpsPos.valid ? 1 : 0, gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.course, hdop);
#endif
}
}
delay(50);
}
}
#define UBX_SYNCH_1 0xB5
#define UBX_SYNCH_2 0x62
uint8_t ubx_set9k6[]={UBX_SYNCH_1, UBX_SYNCH_2, 0x06, 0x00, 0x14, 0x00, 0x01, 0x00, 0x00, 0x00, 0xC0, 0x08, 0x00, 0x00, 0x80, 0x25, 0x00, 0x00, 0x03, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x8D, 0x8F};
uint8_t ubx_factorydef[]={UBX_SYNCH_1, UBX_SYNCH_2, 0x06, 0x09, 13, 0, 0xff, 0xff, 0xff, 0xff, 0, 0, 0, 0, 0, 0, 0, 0, 0xff, 0x17, 0x8A };
void initGPS() {
if (sonde.config.gps_rxd < 0) return; // GPS disabled
Serial2.begin(9600, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
if (sonde.config.gps_txd >= 0) { // TX enable, thus try setting baud to 9600 and do a factory reset
Serial.println("Trying to reset GPS...");
Serial2.begin(115200, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
delay(100);
Serial2.begin(38400, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
delay(100);
Serial2.begin(19200, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
delay(100);
Serial2.begin(9600, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_factorydef, sizeof(ubx_factorydef));
delay(1000);
} else {
Serial2.begin(9600, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
}
xTaskCreate( gpsTask, "gpsTask",
5000, /* stack size */
NULL, /* paramter */
@ -1288,13 +1377,14 @@ void IRAM_ATTR button2ISR() {
int getKeyPress() {
KeyPress p = button1.pressed;
button1.pressed = KP_NONE;
int x = digitalRead(button1.pin);
//int x = digitalRead(button1.pin);
//Serial.printf("Debug: bdd1=%ld, bdd2=%ld\b", bdd1, bdd2);
//Serial.printf("button1 press (dbl:%d) (now:%d): %d at %ld (%d)\n", button1.doublepress, x, p, button1.keydownTime, button1.numberKeyPresses);
return p;
}
int getKey2Press() {
// called by arduino main loop (from Sonde::waitRXcomplete) as soon as pmu_irq is set
void handlePMUirq() {
if (sonde.config.button2_axp) {
// Use AXP power button as second button
if (pmu_irq) {
@ -1313,7 +1403,14 @@ int getKey2Press() {
axp.clearIRQ();
xSemaphoreGive( axpSemaphore );
}
} else {
Serial.println("handlePMIirq() called. THIS SHOULD NOT HAPPEN w/o button2_axp set");
pmu_irq = false; // prevent main loop blocking
}
}
int getKey2Press() {
// TODO: Should be atomic
KeyPress p = button2.pressed;
button2.pressed = KP_NONE;
//Serial.printf("button2 press: %d at %ld (%d)\n", p, button2.keydownTime, button2.numberKeyPresses);
@ -1376,6 +1473,18 @@ int scanI2Cdevice(void)
extern int initlevels[40];
#ifdef ESP_MEM_DEBUG
typedef void (*esp_alloc_failed_hook_t) (size_t size, uint32_t caps, const char * function_name);
extern esp_err_t heap_caps_register_failed_alloc_callback(esp_alloc_failed_hook_t callback);
void heap_caps_alloc_failed_hook(size_t requested_size, uint32_t caps, const char *function_name)
{
printf("%s was called but failed to allocate %d bytes with 0x%X capabilities. \n",function_name, requested_size, caps);
}
#endif
void setup()
{
char buf[12];
@ -1386,6 +1495,9 @@ void setup()
Serial.printf("%d:%d ", i, v);
}
Serial.println("");
#ifdef ESP_MEM_DEBUG
esp_err_t error = heap_caps_register_failed_alloc_callback(heap_caps_alloc_failed_hook);
#endif
axpSemaphore = xSemaphoreCreateBinary();
xSemaphoreGive(axpSemaphore);
@ -1427,7 +1539,9 @@ void setup()
Serial.println("Reading initial configuration");
setupConfigData(); // configuration must be read first due to OLED ports!!!
if ((sonde.fingerprint & 16) == 16) { // NOT TTGO v1 (fingerprint 64) or Heltec v1/v2 board (fingerprint 4)
// NOT TTGO v1 (fingerprint 64) or Heltec v1/v2 board (fingerprint 4)
// and NOT TTGO Lora32 v2.1_1.6 (fingerprint 31/63)
if ( ( (sonde.fingerprint&(64+31)) != 31) && ((sonde.fingerprint & 16) == 16) ) {
// FOr T-Beam 1.0
for (int i = 0; i < 10; i++) { // try multiple times
Wire.begin(21, 22);
@ -1450,14 +1564,16 @@ void setup()
axp.setDCDC1Voltage(3300);
axp.adc1Enable(AXP202_VBUS_VOL_ADC1, 1);
axp.adc1Enable(AXP202_VBUS_CUR_ADC1, 1);
pinMode(PMU_IRQ, INPUT_PULLUP);
attachInterrupt(PMU_IRQ, [] {
pmu_irq = true;
}, FALLING);
axp.adc1Enable(AXP202_BATT_CUR_ADC1, 1);
if(sonde.config.button2_axp) {
pinMode(PMU_IRQ, INPUT_PULLUP);
attachInterrupt(PMU_IRQ, [] {
pmu_irq = true;
}, FALLING);
//axp.enableIRQ(AXP202_VBUS_REMOVED_IRQ | AXP202_VBUS_CONNECT_IRQ | AXP202_BATT_REMOVED_IRQ | AXP202_BATT_CONNECT_IRQ, 1);
axp.enableIRQ( AXP202_PEK_LONGPRESS_IRQ | AXP202_PEK_SHORTPRESS_IRQ, 1 );
axp.clearIRQ();
axp.enableIRQ( AXP202_PEK_LONGPRESS_IRQ | AXP202_PEK_SHORTPRESS_IRQ, 1 );
axp.clearIRQ();
}
int ndevices = scanI2Cdevice();
if (sonde.fingerprint != 17 || ndevices > 0) break; // only retry for fingerprint 17 (startup problems of new t-beam with oled)
delay(500);
@ -1512,7 +1628,7 @@ void setup()
setupWifiList();
Serial.printf("before disp.initFromFile... layouts is %p", disp.layouts);
disp.initFromFile();
disp.initFromFile(sonde.config.screenfile);
Serial.printf("disp.initFromFile... layouts is %p", disp.layouts);
@ -1602,13 +1718,13 @@ void setup()
#endif
/// not here, done by sonde.setup(): rs41.setup();
// == setup default channel list if qrg.txt read fails =========== //
#ifndef DISABLE_SX1278
#ifndef DISABLE_SX1278
xTaskCreate( sx1278Task, "sx1278Task",
10000, /* stack size */
NULL, /* paramter */
1, /* priority */
NULL); /* task handle*/
#endif
#endif
sonde.setup();
initGPS();
@ -1660,11 +1776,53 @@ static const char *action2text(uint8_t action) {
}
return text;
}
#define RDZ_DATA_LEN 128
void parseGpsJson(char *data) {
char *key = NULL;
char *value = NULL;
// very simple json parser: look for ", then key, then ", then :, then number, then , or } or \0
for(int i=0; i<RDZ_DATA_LEN; i++) {
if(key==NULL) {
if(data[i]!='"') continue;
key=data+i+1;
i+=2;
continue;
}
if(value==NULL) {
if(data[i]!=':') continue;
value = data+i+1;
i += 2;
continue;
}
if(data[i]==',' || data[i]=='}' || data[i]==0) {
// get value
double val = strtod(value,NULL);
// get data
if(strncmp(key,"lat",3)==0) { gpsPos.lat = val; }
else if(strncmp(key,"lon",3)==0) { gpsPos.lon = val; }
else if(strncmp(key,"alt",3)==0) { gpsPos.alt = (int)val; }
else if(strncmp(key,"course",6)==0) { gpsPos.course = (int)val; }
gpsPos.valid = true;
// next item:
if(data[i]!=',') break;
key = NULL;
value = NULL;
}
}
Serial.printf("Parse result: lat=%f, lon=%f, alt=%d, valid=%d\n", gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.valid);
}
static char rdzData[RDZ_DATA_LEN];
static int rdzDataPos = 0;
void loopDecoder() {
// sonde knows the current type and frequency, and delegates to the right decoder
uint16_t res = sonde.waitRXcomplete();
int action;
Serial.printf("waitRX result is %x\n", (int)res);
//Serial.printf("waitRX result is %x\n", (int)res);
action = (int)(res >> 8);
// TODO: update displayed sonde?
@ -1688,7 +1846,7 @@ void loopDecoder() {
}
if (!tncclient.connected()) {
Serial.println("TNC client not connected");
//Serial.println("TNC client not connected");
tncclient = tncserver.available();
if (tncclient.connected()) {
Serial.println("new TCP KISS connection");
@ -1701,18 +1859,50 @@ void loopDecoder() {
}
Serial.println("");
}
#if 0
if (!rdzclient.connected()) {
rdzclient = rdzserver.available();
if(rdzclient.connected()) {
Serial.println("RDZ JSON socket: new connection");
}
}
#else
if (rdzserver.hasClient()) {
Serial.println("TCP JSON socket: new connection");
if(rdzclient) rdzclient.stop();
rdzclient = rdzserver.available();
}
#endif
if(rdzclient.available()) {
Serial.print("RDZ JSON socket: received ");
while(rdzclient.available()) {
char c = (char)rdzclient.read();
Serial.print(c);
if(c=='\n'||c=='}'||rdzDataPos>=RDZ_DATA_LEN) {
// parse GPS position from phone
rdzData[rdzDataPos] = c;
if(rdzDataPos>2) parseGpsJson(rdzData);
rdzDataPos = 0;
}
else {
rdzData[rdzDataPos++] = c;
}
}
Serial.println("");
}
// wifi (axudp) or bluetooth (bttnc) active => send packet
SondeInfo *s = &sonde.sondeList[rxtask.receiveSonde];
if ((res & 0xff) == 0 && (connected || tncclient.connected() )) {
//Send a packet with position information
// first check if ID and position lat+lonis ok
SondeInfo *s = &sonde.sondeList[rxtask.receiveSonde];
if (s->validID && ((s->validPos & 0x03) == 0x03)) {
const char *str = aprs_senddata(s, sonde.config.call, sonde.config.udpfeed.symbol);
if (connected) {
char raw[201];
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
Serial.println("Sending position via UDP");
Serial.print("Sending: "); Serial.println(raw);
Serial.println("Sending AXUDP");
//Serial.println(raw);
udp.beginPacket(sonde.config.udpfeed.host, sonde.config.udpfeed.port);
udp.write((const uint8_t *)raw, rawlen);
udp.endPacket();
@ -1725,17 +1915,90 @@ void loopDecoder() {
tncclient.write(raw, rawlen);
}
}
// send to MQTT if enabled
if (connected && mqttEnabled) {
Serial.println("Sending sonde info via MQTT");
mqttclient.publishPacket(s);
}
// also send to web socket
//TODO
}
Serial.println("updateDisplay started");
// always send data, even if not valid....
if (rdzclient.connected()) {
Serial.println("Sending position via TCP as rdzJSON");
char raw[1024];
const char *typestr = s->typestr;
if(*typestr==0) typestr = sondeTypeStr[s->type];
int len = snprintf(raw, 1024, "{"
"\"res\": %d,"
"\"type\": \"%s\","
"\"active\": %d,"
"\"freq\": %.2f,"
"\"id\": \"%s\","
"\"ser\": \"%s\","
"\"validId\": %d,"
"\"launchsite\": \"%s\","
"\"lat\": %.5f,"
"\"lon\": %.5f,"
"\"alt\": %.1f,"
"\"vs\": %.1f,"
"\"hs\": %.1f,"
"\"dir\": %.1f,"
"\"sats\": %d,"
"\"validPos\": %d,"
"\"time\": %d,"
"\"sec\": %d,"
"\"frame\": %d,"
"\"validTime\": %d,"
"\"rssi\": %d,"
"\"afc\": %d,"
"\"launchKT\": %d,"
"\"burstKT\": %d,"
"\"countKT\": %d,"
"\"crefKT\": %d"
"}\n",
res&0xff,
typestr,
(int)s->active,
s->freq,
s->id,
s->ser,
(int)s->validID,
s->launchsite,
s->lat,
s->lon,
s->alt,
s->vs,
s->hs,
s->dir,
s->sats,
s->validPos,
s->time,
s->sec,
s->frame,
(int)s->validTime,
s->rssi,
s->afc,
s->launchKT,
s->burstKT,
s->countKT,
s->crefKT
);
rdzclient.write(raw, len>1024?1024:len);
}
Serial.print("updateDisplay started... ");
if (forceReloadScreenConfig) {
disp.initFromFile();
disp.initFromFile(sonde.config.screenfile);
sonde.clearDisplay();
forceReloadScreenConfig = false;
}
int t = millis();
sonde.updateDisplay();
Serial.println("updateDisplay done");
Serial.printf("updateDisplay done (after %d ms)\n", (int)(millis() - t));
}
void setCurrentDisplay(int value) {
@ -1810,15 +2073,25 @@ String translateEncryptionType(wifi_auth_mode_t encryptionType) {
}
}
void enableNetwork(bool enable) {
if (enable) {
MDNS.begin(sonde.config.mdnsname);
SetupAsyncServer();
udp.begin(WiFi.localIP(), LOCALUDPPORT);
MDNS.addService("http", "tcp", 80);
MDNS.addService("kisstnc", "tcp", 14580);
MDNS.addService("jsonrdz", "tcp", 14570);
if (sonde.config.kisstnc.active) {
tncserver.begin();
rdzserver.begin();
}
if (sonde.config.mqtt.active && strlen(sonde.config.mqtt.host) > 0) {
mqttEnabled = true;
mqttclient.init(sonde.config.mqtt.host, sonde.config.mqtt.port, sonde.config.mqtt.id, sonde.config.mqtt.username, sonde.config.mqtt.password, sonde.config.mqtt.prefix);
}
connected = true;
} else {
MDNS.end();
@ -2018,11 +2291,11 @@ void startAP() {
Serial.println("Activating access point mode");
wifi_state = WIFI_APMODE;
WiFi.softAP(networks[0].id.c_str(), networks[0].pw.c_str());
Serial.println("Wait 100 ms for AP_START...");
delay(100);
Serial.println(WiFi.softAPConfig(IPAddress (192,168,4,1), IPAddress (0,0,0,0), IPAddress (255,255,255,0)) ? "Ready" : "Failed!");
Serial.println(WiFi.softAPConfig(IPAddress (192, 168, 4, 1), IPAddress (0, 0, 0, 0), IPAddress (255, 255, 255, 0)) ? "Ready" : "Failed!");
IPAddress myIP = WiFi.softAPIP();
String myIPstr = myIP.toString();
sonde.setIP(myIPstr.c_str(), true);
@ -2350,16 +2623,17 @@ void execOTA() {
void loop() {
Serial.printf("\nRunning main loop in state %d. free heap: %d;\n", mainState, ESP.getFreeHeap());
Serial.printf("currentDisp:%d lastDisp:%d\n", currentDisplay, lastDisplay);
Serial.printf("\nRunning main loop in state %d [currentDisp:%d, lastDiso:%d]. free heap: %d;\n",
mainState, currentDisplay, lastDisplay, ESP.getFreeHeap());
switch (mainState) {
case ST_DECODER:
#ifndef DISABLE_MAINRX
case ST_DECODER:
#ifndef DISABLE_MAINRX
loopDecoder();
#else
delay(1000);
#endif
#endif
break;
case ST_SPECTRUM: loopSpectrum(); break;
case ST_WIFISCAN: loopWifiScan(); break;
@ -2382,5 +2656,12 @@ void loop() {
sonde.updateDisplay();
lastDisplay = currentDisplay;
}
int now = millis();
if (mqttEnabled && (lastMqttUptime == 0 || (lastMqttUptime + 60000 < now) || (lastMqttUptime > now))) {
mqttclient.publishUptime();
lastMqttUptime = now;
}
Serial.printf("Unused stack: %d\n", uxTaskGetStackHighWaterMark(0));
}

Wyświetl plik

@ -27,8 +27,8 @@
tft_orient=1
#gps_rxd=-1
gps_txd=-1
# Show AFC value (for RS41 only, maybe also DFM, but useful for RS92 or M10)
# showafc=1
# Show AFC value (for RS41 and M10/M20, maybe also DFM, but not useful for RS92)
showafc=1
# Frequency correction, in Hz
# freqofs=0
#-------------------------------#
@ -41,6 +41,9 @@ wifi=3
# TCP/IP KISS TNC in port 14590 for APRSdroid (0=disabled, 1=enabled)
kisstnc.active = 1
# which screens file to use (0: screens.txt, i>0: screens${i}.txt
# 0: old version; 1: for OLED, 2: for TFT; 3: for TFT (portrait mode)
# screenfile=2
# display configuration. List of "displays"
# first entry: "Scanner" display
# second entry: default "Receiver" display
@ -75,6 +78,14 @@ rs92.alt2d=480
dfm.agcbw=20800
dfm.rxbw=10400
#-------------------------------#
# ftp server for RINEX data (for RS92)
# YYYY/DDD/brdcDDD0.YYn.gz is appended
# s1: igs.bkg.bund.de/IGS/BRDC/
# s2: www.ngs.noaa.gov/cors/rinex/
#-------------------------------#
ephftp=www.ngs.noaa.gov/cors/rinex/
#ephftp=igs.bkg.bund.de/IGS/BRDC/
#-------------------------------#
# axudp for sending to aprsmap
#-------------------------------#
# local use only, do not feed to public services
@ -96,5 +107,16 @@ tcp.symbol=/O
tcp.highrate=20
tcp.idformat=0
#-------------------------------#
# mqtt settings
#-------------------------------#
# data not sanitized / quality checked, outliers not filtered out
mqtt.active=0
mqtt.id=rdz_sonde_server
mqtt.ip=
mqtt.port=1883
mqtt.username=
mqtt.password=
mqtt.prefix=rdz_sonde_server/
#-------------------------------#
# EOF
#-------------------------------#

Wyświetl plik

@ -18,47 +18,53 @@
<button class="tablinks" onclick="selTab(event,'QRG')" id="defaultTab">QRG</button>
<button class="tablinks" onclick="selTab(event,'WiFi')">WiFi</button>
<button class="tablinks" onclick="selTab(event,'Data')">Data</button>
<button class="tablinks" onclick="selTab(event,'SondeMap')">SondeMap</button>
<!-- <button class="tablinks" onclick="selTab(event,'SondeMap')">SondeMap</button> -->
<button class="tablinks" onclick="selTab(event,'Config')">Config</button>
<button class="tablinks" onclick="selTab(event,'Control')">Control</button>
<button class="tablinks" onclick="selTab(event,'About')">About</button>
</div>
<div id="QRG" class="tabcontent">
<div id="QRG" class="tabcontent" data-src="qrg.html">
<h3> QRG - Setup</h3>
<iframe src="qrg.html" style="border:none;" width="100%%" height="100%%"></iframe>
<iframe src="" style="border:none;" width="100%%" height="100%%"></iframe>
</div>
<div id="WiFi" class="tabcontent">
<div id="WiFi" class="tabcontent" data-src="wifi.html">
<h3> WiFi - Settings</h3>
<iframe src="wifi.html" style="border:none;" width="100%%" height="100%%"></iframe>
<iframe src="" style="border:none;" width="100%%" height="100%%"></iframe>
</div>
<div id="Data" class="tabcontent" data-src="status.html">
<h3>Data</h3>
<iframe src="status.html" style="border:none;" width="100%%" height="100%%"></iframe>
<iframe src="" style="border:none;" width="100%%" height="100%%"></iframe>
</div>
<div id="SondeMap" class="tabcontent" data-src="https://wx.dl2mf.de/#?">
<!--
<div id="SondeMap" class="tabcontent" data-src="https://wetterson.de/karte/">
<iframe src="" style="border:none;" width="98%%" height="98%%"></iframe>
</div>
-->
<div id="Config" class="tabcontent">
<div id="Config" class="tabcontent" data-src="config.html">
<h3>Configuration</h3>
<iframe src="config.html" style="border:none;" width="100%%" height="100%%"></iframe>
<iframe src="" style="border:none;" width="100%%" height="100%%"></iframe>
</div>
<div id="Control" class="tabcontent">
<div id="Control" class="tabcontent" data-src="control.html">
<h3>Control</h3>
<iframe src="control.html" style="border:none;" width="100%%" height="100%%"></iframe>
<iframe src="" style="border:none;" width="100%%" height="100%%"></iframe>
</div>
<div id="About" class="tabcontent">
<h3>About</h3>
%VERSION_NAME%<br>
Copyright &copy; 2019 by Hansi Reiser, DL9RDZ<br>
(version %VERSION_ID%)<br>
with mods by <a href="https://www.dl2mf.de/" target="_blank">Meinhard Guenther, DL2MF</a><br>
Copyright &copy; 2019-2020 by Hansi Reiser, DL9RDZ<br>
(version %VERSION_ID%)<br><br>
with contributions by Vigor and Xavier (M20 support), <a href="https://www.dl2mf.de/" target="_blank">Meinhard Guenther, DL2MF</a>,
<a href="https://github.com/bazjo">Johannes</a>, <a href="http://www.p1337.synology.me/dokuwiki/doku.php?id=public:wettersonden">Robert Stefanowicz</a>,
<a href="https://github.com/puspis">Josema</a>, and probably some more people I forgot to mention here.
<br>
<br>
Autodetect info: %AUTODETECT_INFO%<br>
<br>

Wyświetl plik

@ -32,7 +32,10 @@
# Hm(suffix) hor. speed m/s (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
# Hk(suffix) hor. speed km/h (suffix: e.g. "km/h"; no suffix=>km/h as 16x8 bitmap for SSD1306 display only)
# V(suffix) vert. speef (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
# Ix sonde ID (dfm format by x: d=>dxlaprs, a=>autorx, s=>real serial number)
# Ix sonde ID (default/d: dxlaprs; s: short id, n: real serial number)
# RS41,RS92: all identical R1234567
# DFMx: ID M12345678; short ID and serial 12345678
# M10: ID ME95231F0; short ID: M95231F0; serial 9062104592
# Q signal quality statistics bar
# T type string (RS41/DFM9/DFM6/RS92)
# C afC value
@ -210,7 +213,7 @@ key2action=#,#,#,#
timeaction=#,D,+
fonts=5,6
0,0=XScan
0,5,-3=S#:
0,8,-3=S#:
0,9,5=T
3,0=F MHz
5,0,16=S
@ -223,7 +226,7 @@ key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,0
color=FFD700
0,0=Id
0,0=Is
color=0000FF
0,11,-5.5=f
1,1,6=c

Wyświetl plik

@ -0,0 +1,226 @@
### screens1.txt: OLED display
# Definition of display content and action behaviour
#
# Timer: (view timer, rx timer, norx timer)
# - value -1: timer is disabled; value>=0: timer fires after (value) seconds
# - view timer: time since current view (display mode and sonde) was started
# - rx timer: time since when sonde data has been received continuously (trigger immediatly after RX)
# - norx timer: time since when no sonde data has been received continuously
# (rx and norx timer is started after tuning a new frequency and receiving a signal or not receiving
# anything for a 1s period)
#
# Actions:
# - W: activate WiFi scan
# - F: activate frequency spectrum display
# - 0: activate "Scan:" display (this is basically just display mode 0)
# - x: (1..N): activate display mode x [deprecated]
# - >: activate next display mode
# - D: activate default receiver display (display mode specified in config)
# - +: advance to next active sonde from QRG config
# - #: no action
#
# Display content (lower/upper case: small/large font)
# line,column=content
# for ILI9225 its also possible to indicate
# line,column,width=content for text within a box of width 'width'
# line,column,-width=content for right-justified text
#
# XText : Text
# F(suffix): frequency (with suffix, e.g., " MHz")
# L latitade
# O lOngitute
# A altitude
# Hm(suffix) hor. speed m/s (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
# Hk(suffix) hor. speed km/h (suffix: e.g. "km/h"; no suffix=>km/h as 16x8 bitmap for SSD1306 display only)
# V(suffix) vert. speef (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
# Ix sonde ID (default/d: dxlaprs; s: short id, n: real serial number)
# RS41,RS92: all identical R1234567
# DFMx: ID M12345678; short ID and serial 12345678
# M10: ID ME95231F0; short ID: M95231F0; serial 9062104592
# Q signal quality statistics bar
# T type string (RS41/DFM9/DFM6/RS92)
# C afC value
# N ip address (only tiny font)
# S scan list entry info: l/empty: launch site name, #=entry nr, t=total entries, a=active entries, /: #/t
# K RS41 kill timer values: Kl launch timer, Kb burst timer, Kc kill countdown
# format: K_4: h:mm k_6: h:mm:ss k_s: sssss, nothing shown for other sonde
# Mx telemetry value x (t temp p preassure h hyg) [not yet implemented, maybe some day in future]
# Gx GPS-related data
# raw data from GPS: GA, GO, GH, GC: LAtitude, lOngitude, Altutide(Height), Course over ground
# relative to sonde: GD, GI, GB: Distance, dIrection (absolute), relative Bearing
# G0 GPS circle diagram e.g. 3,5=g0NCS,50,ff0000,000033,5,ffff00,4,ffffff
# "N" (what is on top: N=north C=course)
# "C" (where does the arrow point to: C=course, S=sonde)
# "S" (what is shown by the bullet: C=course, S=sonde)
# 50: circle radius, followed by fg and bg color
# 5: bullet radius, followed by fg color
# 4: arrow width, followed by fg color
# R RSSI
# B battery(T-Beam 1.0) S=status V=Batt.Volt C=charge current D=discharge current
# U=USB volt I=USB current T=IC temp
#
# fonts=x,y can be used to select font (x=small, y=large) for all items below
# for SSD1306, x and y can be used to select one of those fonts:
# (y should be a 1x2 font (1,5,6,7), x a small font)
# u8x8_font_chroma48medium8_r, // 0 ** default small
# u8x8_font_7x14_1x2_f, // 1 ** default large
# u8x8_font_amstrad_cpc_extended_f, // 2
# u8x8_font_5x7_f, // 3
# u8x8_font_5x8_f, // 4
# u8x8_font_8x13_1x2_f, // 5
# u8x8_font_8x13B_1x2_f, // 6
# u8x8_font_7x14B_1x2_f, // 7
# u8x8_font_artossans8_r, // 8
# u8x8_font_artosserif8_r, // 9
# u8x8_font_torussansbold8_r, // 10
# u8x8_font_victoriabold8_r, // 11
# u8x8_font_victoriamedium8_r, // 12
# u8x8_font_pressstart2p_f, // 13
# u8x8_font_pcsenior_f, // 14
# u8x8_font_pxplusibmcgathin_f, // 15
# u8x8_font_pxplusibmcga_f, // 16
# u8x8_font_pxplustandynewtv_f, // 17
#
# for ILI9225, these fonts are available:
# Terminal6x8 // 0
# Terminal11x16 // 1
# Terminal12x16 // 2
# FreeMono9pt7b, // 3
# FreeMono12pt7b, // 4
# FreeSans9pt7b, // 5
# FreeSans12pt7b, // 6
# Picopixel, // 7
#
# color=rrggbb,rrggbb can be used to select color (foreground, background)
# see https://github.com/Nkawu/TFT_22_ILI9225/wiki#color-reference for example (use without "#"-sign)
#
# for TFT display, coordinates and width are multiplied by xscale,yscale and later used in pixels
# with scale=1,1 you can directly use pixel coordinates. (default: xscale=13,yscale=22 => 8 lines, 16 columns)
###########
#
# Default configuration for "Scanner" display:
# - view timer disabled; rx timer=0; norx timer = 0
# => after 1 second immediately an action is triggered
# (norx: go to next sonde; rx: go to default receiver display)
# - key1 actions: D,0,F,W
# => Button press activates default receiver view, double press does nothing
# Mid press activates Spectrum display, long press activates Wifi scan
# - key2 has no function
@Scanner
timer=-1,0,0
key1action=D,#,F,W
key2action=#,#,#,#
timeaction=#,D,+
0,0=XScan
0,5=S#:
0,9=T
3,0=F MHz
5,0=S
7,5=n
############
# Default configuration for "Legacy" display:
# - view timer=-1, rx timer=-1 (disabled); norx timer=20 (or -1 for "old" behaviour)
# => norx timer fires after not receiving a singla for 20 seconds
# - key1 actions: +,0,F,W
# => Button1 press: next sonde; double press => @Scanner display
# => Mid press activates Spectrum display, long press activates Wifi scan
# - key2 actions: 2,#,#,#
# => BUtton2 activates display 2 (@Field)
# - timer actions: #,#,0
# (norx timer: if no signal for >20 seconds: go back to scanner mode)
#
@Legacy
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,0
0,5=f MHz
1,8=c
0,0=t
1,0=is
2,0=L
4,0=O
2,10=a
3,10=h
4,9=v
6,0=R
6,7=Q
############
# Configuratoon for "Field" display (display 2)
# similar to @Legacy, but no norx timer, and Key2 goes to display 4
@Field
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
2,0=L
4,0=O
3,10=h
4,9=v
0,0=Is
6,0=A
6,7=Q
############
# Configuration for "Field2" display (display 3)
# similar to @Field
@Field2
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
2,0=L
4,0=O
1,12=t
0,9=f
3,10=h
4,9=v
0,0=Is
6,0=A
6,7=Q
#############
# Configuration for "GPS" display
# not yet the final version, just for testing
@GPSDIST
timer=-1,-1,-1
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
0,0=Is
0,9=f
1,12=t
2,0=L
4,0=O
2,10=a
3,10=h
4,9=v
5,9=gC
5,13=gB
6,7=Q
7,0=gV
7,2=xd=
7,4=gD
7,12=gI°
############
@BatteryOLED
timer=-1,-1,-1
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
fonts=0,1
0,0=xBat.Status:
0,12=bS
1,0=xBatt:
1,6=bVV
2,0=bCmA (charge)
3,0=bDmA (disch.)
4,0=xUSB:
4,5=bUV
5,5=bImA
6,0=xTemp:
6,5=bT C

Wyświetl plik

@ -0,0 +1,573 @@
## screens2.txt: TFT display (landscape)
# Definition of display content and action behaviour
#
# Timer: (view timer, rx timer, norx timer)
# - value -1: timer is disabled; value>=0: timer fires after (value) seconds
# - view timer: time since current view (display mode and sonde) was started
# - rx timer: time since when sonde data has been received continuously (trigger immediatly after RX)
# - norx timer: time since when no sonde data has been received continuously
# (rx and norx timer is started after tuning a new frequency and receiving a signal or not receiving
# anything for a 1s period)
#
# Actions:
# - W: activate WiFi scan
# - F: activate frequency spectrum display
# - 0: activate "Scan:" display (this is basically just display mode 0)
# - x: (1..N): activate display mode x [deprecated]
# - >: activate next display mode
# - D: activate default receiver display (display mode specified in config)
# - +: advance to next active sonde from QRG config
# - #: no action
#
# Display content (lower/upper case: small/large font)
# line,column=content
# for ILI9225 its also possible to indicate
# line,column,width=content for text within a box of width 'width'
# line,column,-width=content for right-justified text
#
# XText : Text
# F(suffix): frequency (with suffix, e.g., " MHz")
# L latitade
# O lOngitute
# A altitude
# Hm(suffix) hor. speed m/s (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
# Hk(suffix) hor. speed km/h (suffix: e.g. "km/h"; no suffix=>km/h as 16x8 bitmap for SSD1306 display only)
# V(suffix) vert. speef (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
# Ix sonde ID (default/d: dxlaprs; s: short id, n: real serial number)
# RS41,RS92: all identical R1234567
# DFMx: ID M12345678; short ID and serial 12345678
# M10: ID ME95231F0; short ID: M95231F0; serial 9062104592
# Q signal quality statistics bar
# T type string (RS41/DFM9/DFM6/RS92)
# C afC value
# N ip address (only tiny font)
# S scan list entry info: l/empty: launch site name, #=entry nr, t=total entries, a=active entries, /: #/t
# K RS41 kill timer values: Kl launch timer, Kb burst timer, Kc kill countdown
# format: K_4: h:mm k_6: h:mm:ss k_s: sssss, nothing shown for other sonde
# Mx telemetry value x (t temp p preassure h hyg) [not yet implemented, maybe some day in future]
# Gx GPS-related data
# raw data from GPS: GA, GO, GH, GC: LAtitude, lOngitude, Altutide(Height), Course over ground
# relative to sonde: GD, GI, GB: Distance, dIrection (absolute), relative Bearing
# G0 GPS circle diagram e.g. 3,5=g0NCS,50,ff0000,000033,5,ffff00,4,ffffff
# "N" (what is on top: N=north C=course)
# "C" (where does the arrow point to: C=course, S=sonde)
# "S" (what is shown by the bullet: C=course, S=sonde)
# 50: circle radius, followed by fg and bg color
# 5: bullet radius, followed by fg color
# 4: arrow width, followed by fg color
# R RSSI
# B battery(T-Beam 1.0) S=status V=Batt.Volt C=charge current D=discharge current
# U=USB volt I=USB current T=IC temp
#
# fonts=x,y can be used to select font (x=small, y=large) for all items below
# for SSD1306, x and y can be used to select one of those fonts:
# (y should be a 1x2 font (1,5,6,7), x a small font)
# u8x8_font_chroma48medium8_r, // 0 ** default small
# u8x8_font_7x14_1x2_f, // 1 ** default large
# u8x8_font_amstrad_cpc_extended_f, // 2
# u8x8_font_5x7_f, // 3
# u8x8_font_5x8_f, // 4
# u8x8_font_8x13_1x2_f, // 5
# u8x8_font_8x13B_1x2_f, // 6
# u8x8_font_7x14B_1x2_f, // 7
# u8x8_font_artossans8_r, // 8
# u8x8_font_artosserif8_r, // 9
# u8x8_font_torussansbold8_r, // 10
# u8x8_font_victoriabold8_r, // 11
# u8x8_font_victoriamedium8_r, // 12
# u8x8_font_pressstart2p_f, // 13
# u8x8_font_pcsenior_f, // 14
# u8x8_font_pxplusibmcgathin_f, // 15
# u8x8_font_pxplusibmcga_f, // 16
# u8x8_font_pxplustandynewtv_f, // 17
#
# for ILI9225, these fonts are available:
# Terminal6x8 // 0
# Terminal11x16 // 1
# Terminal12x16 // 2
# FreeMono9pt7b, // 3
# FreeMono12pt7b, // 4
# FreeSans9pt7b, // 5
# FreeSans12pt7b, // 6
# Picopixel, // 7
#
# color=rrggbb,rrggbb can be used to select color (foreground, background)
# see https://github.com/Nkawu/TFT_22_ILI9225/wiki#color-reference for example (use without "#"-sign)
#
# for TFT display, coordinates and width are multiplied by xscale,yscale and later used in pixels
# with scale=1,1 you can directly use pixel coordinates. (default: xscale=13,yscale=22 => 8 lines, 16 columns)
###########
############
# Scan display for large 2" TFT dispaly
@ScannerTFT
timer=-1,0,0
key1action=D,#,F,W
key2action=#,#,#,#
timeaction=#,D,+
fonts=5,6
0,0=XScan
0,5,-3=S#:
0,9,5.5=T
3,0=F MHz
5,0,16=S
7,5=n
############
@MainTFT
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,0
color=FFD700
0,0,10.5=Is
color=0000FF
0,11,-5.5=f
1,0,4=t
1,10.5,-6=c
color=00ff00
2,0,7=L
4,0,7=O
color=FFA500
2,9.5,-7=A
3,9.5,-7=vm/s
color=AA5522
4,9.5,-7=hkkm/h
color=FFFFFF
6,2=r
6.3,10=Q4
7,0=xd=
7,2,6=gD
7,12=gI
############
@PeilungTFT
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
color=ffff00,000033
color=bbbbbb,000000
0,2=xN Top:
0,8=xCourse Top:
color=ffff00,000033
1,0=g0NCS,48,ffff00,000044,6,33ff33,5,eeaa00
1,8=g0CCS,48,ffff00,000044,6,55ff55,5,eeaa00
color=ffffff,000000
6,0=xDirection:
6,8,4=gI
7,0=xCOG:
7,4,4=gC
7,8=xturn:
7,12,4=gB
############
@GPSdataTFT
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
0,0=xOn-board GPS:
1,0,8=gA
2,0,8=gO
3,0,8=gH
4,0,8=gC
5,0=xGPS vs Sonde:
6,0,8=gD
7,0,8=gI
7,8,8=gB
############
@BatteryTFT
timer=-1,-1,-1
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
0,0=xBattery status:
0,14=bS
1,0=xBatt:
1,5,5=bVV
2,0,16=bCmA(charging)
3,0,16=bDmA(discharging)
4.4,0=xUSB:
4.4,5,5=bUV
5.4,0,10=bImA
6.4,0=xTemp:
6.4,5,5=bT C
### Alternative display layouts based on https://gist.github.com/bazjo
# Scan display for large 2" TFT dispaly
@Scan.TFT.Bazjo
timer=-1,0,0
key1action=D,#,F,W
key2action=#,#,#,#
timeaction=#,D,+
scale=11,10
fonts=0,2
color=e0e0e0
#Row 1
0.5,0=XScanning...
#Row 2
3,0=xIndex
4,0,8=S/
3,9=xSite
4,9=S
#Row 3
6,0=xType
7,0,6=T
6,9=xFrequency
7,9=F
#Row 4
9,0=xWeb UI IP
10,0=N
#Row 5
#Footer
color=6C757D
15,0=xScan Mode
15,18=bVV
############
@Decode/General.TFT.Bazjo
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,0
scale=11,10
fonts=0,2
#Row 1
color=996A06
0,0=xSerial
0,5=t
color=FFB10B
1,0=Is
color=996A06
0,11=xFreq.
0,16=c
color=FFB10B
1,11=F
#Row 2
color=3C5C99
3,0=xLatitude
color=639AFF
4,0=L
color=3C5C99
3,11=xLongitude
color=639AFF
4,11=O
#Row 3
color=3C5C99
6,0=xHoriz. Speed
color=639AFF
7,0=Hkkm/h
color=3C5C99
6,11=xVert. Speed
color=639AFF
7,11=Vm/s
#Row 4
color=99004A
9,0=xAltitude
color=FF007B
10,0=A
color=99004A
9,11=xBearing
color=FF007B
10,11=GB
#Row 5
color=06998E
12,0=xRSSI
color=0AFFEF
13,0=R
color=06998E
12,11=xHistory
color=0AFFEF
13.5,11=Q4
#Footer
color=6C757D
15,0=xDecode Mode / General View
15,18=bVV
############
@Decode/Battery.TFT.Bazjo
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
scale=11,10
fonts=0,2
#Row 1
color=99001F
0,0=xBattery Status
0,11=xBattery Voltage
color=FF0035
1,0=BS
1,11=BVV
#Row 2
color=99001F
3,0=xCharge Current
3,11=xDischarge Current
color=FF0035
4,0=BCmA
4,11=BDmA
#Row 3
color=99001F
6,0=xUSB Voltage
6,11=xUSB Current
color=FF0035
7,0=BUV
7,11=BImA
#Row 4
color=99001F
9,0=xIC Temperature
#9,11=xKey
color=FF0035
10,0=BTC
#10,11=XValue
#Row 5
#12,0=xKey
#12,11=xKey
#13,0=XValue
#13,11=XValue
#Footer
color=99001F
15,0=xDecode Mode/Battery View
15,18=bVV
# based on https://github.com/puspis/rdz_ttgo_sonde
##########
@Scanner.Puspis
timer=-1,0,4
key1action=D,#,F,W
key2action=#,#,#,#
timeaction=#,D,+
scale=13,10
fonts=0,1
#Row 1
color=90EE90
0.5,3=XFREQUENCY SCAN
#Row 2
color=00FF00
3,0=xMEMORY
3,9=xLAUNCH SITE
color=639AFF
4,0,9=S/
4,9=S
#Row 3
color=00FF00
6,0=xTYPE
6,9=xFREQUENCY
color=639AFF
7,0,9=T
7,9=F MHz
#Row 4
fonts=0,5
color=285454
11.5,0=xIP ADDRESS:
10.9,7,-15=N
#Footer
color=FF0000
12.7,18=bVV
############
@Main.Puspis
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,0
scale=11,10
fonts=0,2
#Row 1
color=00FF00
0,0=xSONDE ID
0,11=xFREQUENCY
color=90EE90
0,7.4=t
1,0=Is
1,11=F
#Row 2
fonts=0,1
color=00FF00
3,0=xLATITUDE
3,11=xLONGITUDE
color=FF007B
4,0=L
4,11=O
#Row 3
color=00FF00
6,0=xWIND SPEED
6,11=xCLIMB RATE
color=639AFF
7,0=Hkkm/h
7,11=Vm/s
#Row 4
color=00FF00
9,0=xRX ALTITUDE
9,11=xSONDE ALTITUDE
color=639AFF
10,0=GH
10,11=A
#Row 5
color=00FF00
12,0=xDISTANCE
12,11=xFRAMES
color=FFFFFF
13,0=GD
13.5,11=Q4
#Footer
color=FF0000
15,0.2=xIP:
15,2.5=n
15,18=bVV
############
@JotaEme.Puspis
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,0
scale=11,10
fonts=0,1
#Row 1
color=90EE90
0,0=Is
0.7,10.5=t
0,14=F
#Row 2
color=00FF00
2,1.2=xWIND SPEED
2,14=xCLIMB RATE
color=639AFF
3,1=Hkkm/h
3,13=Vm/s
#Row 3
color=00FF00
5,1=xRX ALTITUDE
5,12.5=xSONDE ALTITUDE
color=639AFF
6,2=GH
6,14=A
#Row 4
color=00FF00
8,0=xSONDE POSITION
color=FF007B
9,2=l
10,2=o
#Row 5
color=00FF00
11.4,2=xDISTANCE
color=FFFFFF
12.4,1.5=GD
#Circle
color=EEAA00,000033
8,13.8=g0CCS,28,FFFF00,000033,5,9ACD32,5,EEAA00
#Footer
color=FF0000
15,0=n
color=FFFFFF,000000
15,8.7=Q4
color=FF0000
15,18.4=bVV
############
@CompassTFT.Puspis
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
scale=13,10
fonts=0,1
#Row 1
color=90EE90
0.5,1.5=XCOMPASS
#Row 2
color=00FF00
4,2=xRX HEADING
color=639AFF
5,3.8=GC
#Row 3
color=00FF00
9.5,3=xDISTANCE
9.5,13.5=xBEARING
color=639AFF
10.5,3.4=GD
10.5,14.3=GI
#Circle
color=EEAA00,000033
0.2,10=g0CCS,52,FFFF00,000033,10,9ACD32,6,EEAA00
#Footer
color=FF0000,000000
12.7,1=Q4
12.7,18=bVV
############
@GPSdataTFT.Puspis
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
scale=13,10
fonts=0,1
#Row 1
color=90EE90
0.5,0.5=XGPS RECEIVER STATION
#Row 2
color=00FF00
3,0=xRX LATITUDE
3,12=xRX LONGITUDE
color=639AFF
4,0=GA
4,12=GO
#Row 3
color=00FF00
6,0=xRX ALTITUDE
6,12=xRX HEADING
color=639AFF
7,0=GH
7,12=GC
#Row 4
color=00FF00
9,0=xDISTANCE
9,12=xBEARING
color=639AFF
10,0=GD
10,12=GB
#Footer
color=FF0000,000000
12.7,0.4=Q4
12.7,18=bVV
############
@BatteryTFT.Puspis
timer=-1,-1,-1
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
scale=13,10
fonts=0,1
#Row 1
color=90EE90
0.5,4=XBATTERY STATUS
#Row 2
color=00FF00
3,0=x(C)HARGE/(B)ATT
3,11.5=xBATTERY VOLTAGE
color=639AFF
4,4=BS
4,11.5=BVV
#Row 3
color=00FF00
6,0=xCHARGE CURRENT
6,11.5=xDISCHG. CURRENT
color=639AFF
7,0=BCmA
7,11.5=BDmA
#Row 3
color=00FF00
9,0=xIC TEMPERATURE
9,11.5=xFREQ. OFFSET
color=639AFF
10,0=BTC
10,10=C
#Footer
color=FF0000,000000
12.7,0.4=Q4
12.7,18=bVV

Wyświetl plik

@ -0,0 +1,217 @@
## screens3.txt: TFT display (portrait)
## based on http://www.p1337.synology.me/dokuwiki/doku.php?id=public:wettersonden
# Definition of display content and action behaviour
#
# Timer: (view timer, rx timer, norx timer)
# - value -1: timer is disabled; value>=0: timer fires after (value) seconds
# - view timer: time since current view (display mode and sonde) was started
# - rx timer: time since when sonde data has been received continuously (trigger immediatly after RX)
# - norx timer: time since when no sonde data has been received continuously
# (rx and norx timer is started after tuning a new frequency and receiving a signal or not receiving
# anything for a 1s period)
#
# Actions:
# - W: activate WiFi scan
# - F: activate frequency spectrum display
# - 0: activate "Scan:" display (this is basically just display mode 0)
# - x: (1..N): activate display mode x [deprecated]
# - >: activate next display mode
# - D: activate default receiver display (display mode specified in config)
# - +: advance to next active sonde from QRG config
# - #: no action
#
# Display content (lower/upper case: small/large font)
# line,column=content
# for ILI9225 its also possible to indicate
# line,column,width=content for text within a box of width 'width'
# line,column,-width=content for right-justified text
#
# XText : Text
# F(suffix): frequency (with suffix, e.g., " MHz")
# L latitade
# O lOngitute
# A altitude
# Hm(suffix) hor. speed m/s (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
# Hk(suffix) hor. speed km/h (suffix: e.g. "km/h"; no suffix=>km/h as 16x8 bitmap for SSD1306 display only)
# V(suffix) vert. speef (suffix: e.g. "m/s"; no suffix=>m/s as 16x8 bitmap for SSD1306 display only)
# Ix sonde ID (default/d: dxlaprs; s: short id, n: real serial number)
# RS41,RS92: all identical R1234567
# DFMx: ID M12345678; short ID and serial 12345678
# M10: ID ME95231F0; short ID: M95231F0; serial 9062104592
# Q signal quality statistics bar
# T type string (RS41/DFM9/DFM6/RS92)
# C afC value
# N ip address (only tiny font)
# S scan list entry info: l/empty: launch site name, #=entry nr, t=total entries, a=active entries, /: #/t
# K RS41 kill timer values: Kl launch timer, Kb burst timer, Kc kill countdown
# format: K_4: h:mm k_6: h:mm:ss k_s: sssss, nothing shown for other sonde
# Mx telemetry value x (t temp p preassure h hyg) [not yet implemented, maybe some day in future]
# Gx GPS-related data
# raw data from GPS: GA, GO, GH, GC: LAtitude, lOngitude, Altutide(Height), Course over ground
# relative to sonde: GD, GI, GB: Distance, dIrection (absolute), relative Bearing
# G0 GPS circle diagram e.g. 3,5=g0NCS,50,ff0000,000033,5,ffff00,4,ffffff
# "N" (what is on top: N=north C=course)
# "C" (where does the arrow point to: C=course, S=sonde)
# "S" (what is shown by the bullet: C=course, S=sonde)
# 50: circle radius, followed by fg and bg color
# 5: bullet radius, followed by fg color
# 4: arrow width, followed by fg color
# R RSSI
# B battery(T-Beam 1.0) S=status V=Batt.Volt C=charge current D=discharge current
# U=USB volt I=USB current T=IC temp
#
# fonts=x,y can be used to select font (x=small, y=large) for all items below
# for SSD1306, x and y can be used to select one of those fonts:
# (y should be a 1x2 font (1,5,6,7), x a small font)
# u8x8_font_chroma48medium8_r, // 0 ** default small
# u8x8_font_7x14_1x2_f, // 1 ** default large
# u8x8_font_amstrad_cpc_extended_f, // 2
# u8x8_font_5x7_f, // 3
# u8x8_font_5x8_f, // 4
# u8x8_font_8x13_1x2_f, // 5
# u8x8_font_8x13B_1x2_f, // 6
# u8x8_font_7x14B_1x2_f, // 7
# u8x8_font_artossans8_r, // 8
# u8x8_font_artosserif8_r, // 9
# u8x8_font_torussansbold8_r, // 10
# u8x8_font_victoriabold8_r, // 11
# u8x8_font_victoriamedium8_r, // 12
# u8x8_font_pressstart2p_f, // 13
# u8x8_font_pcsenior_f, // 14
# u8x8_font_pxplusibmcgathin_f, // 15
# u8x8_font_pxplusibmcga_f, // 16
# u8x8_font_pxplustandynewtv_f, // 17
#
# for ILI9225, these fonts are available:
# Terminal6x8 // 0
# Terminal11x16 // 1
# Terminal12x16 // 2
# FreeMono9pt7b, // 3
# FreeMono12pt7b, // 4
# FreeSans9pt7b, // 5
# FreeSans12pt7b, // 6
# Picopixel, // 7
#
# color=rrggbb,rrggbb can be used to select color (foreground, background)
# see https://github.com/Nkawu/TFT_22_ILI9225/wiki#color-reference for example (use without "#"-sign)
#
# for TFT display, coordinates and width are multiplied by xscale,yscale and later used in pixels
# with scale=1,1 you can directly use pixel coordinates. (default: xscale=13,yscale=22 => 8 lines, 16 columns)
###########
#
# Default configuration for "Scanner" display:
# - view timer disabled; rx timer=0; norx timer = 0
# => after 1 second immediately an action is triggered
# (norx: go to next sonde; rx: go to default receiver display)
# - key1 actions: D,0,F,W
# => Button press activates default receiver view, double press does nothing
# Mid press activates Spectrum display, long press activates Wifi scan
# - key2 has no function
@ScannerPortrait
timer=-1,0,0
key1action=D,#,F,W
key2action=>,#,#,#
timeaction=#,D,+
0,0=XScan
0,5=S#:
0,9,4.5=T
6,0=XHoehe
6,5=GH
color=ffff00
2,0=F MHz
4,0=S
color=00ff00,444444
7,5=n
7,0=bV
############
# Default configuration for "Legacy" display:
# - view timer=-1, rx timer=-1 (disabled); norx timer=20 (or -1 for "old" behaviour)
# => norx timer fires after not receiving a singla for 20 seconds
# - key1 actions: +,0,F,W
# => Button1 press: next sonde; double press => @Scanner display
# => Mid press activates Spectrum display, long press activates Wifi scan
# - key2 actions: 2,#,#,#
# => BUtton2 activates display 2 (@Field)
# - timer actions: #,#,0
# (norx timer: if no signal for >20 seconds: go back to scanner mode)
#
@LegacyPortrait
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,0
9,10=f
9,0=r
9,4=Q
5,0=g0NCS,35,ffff00,000044,6,33ff33,5,eeaa00
5,7=g0CCS,35,ffff00,000044,6,55ff55,5,eeaa00
0,0=s
0,9=is
2,0=L
3,0=O
color=FFFF00
1,6=Hk km/h
color=FF0000
1,0=GD
color=FFFFFF
4,9=GH
3,9=V
4,0=A
############
@PeilungTFTPortrait
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
color=ffff00,000033
color=bbbbbb,000000
0,2=xN Top:
0,8=xCourse Top:
color=ffff00,000033
1,0=g0NCS,35,ffff00,000044,6,33ff33,5,eeaa00
1,7=g0CCS,35,ffff00,000044,6,55ff55,5,eeaa00
color=ffffff,000000
6,0=xDirection:
6,8,4=gI
7,0=xCOG:
7,4,4=gC
7,8=xturn:
7,12,4=gB
############
@GPSdataTFTPortrait
timer=-1,-1,N
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
0,0=xOn-board GPS:
1,0,8=gA
2,0,8=gO
3,0,8=gH
4,0,8=gC
5,0=xGPS vs Sonde:
6,0,8=gD
7,0,8=gI
7,8,8=gB
############
@BatteryTFTPortrait
timer=-1,-1,-1
key1action=+,0,F,W
key2action=>,#,#,#
timeaction=#,#,#
0,0=xBattery status:
0,14=bS
1,0=xBatt:
1,5,5=bVV
2,0,16=bCmA(charging)
3,0,16=bDmA(discharging)
4.4,0=xUSB:
4.4,5,5=bUV
5.4,0,10=bImA
6.4,0=xTemp:
6.4,5,5=bT C

Wyświetl plik

@ -1,4 +1,4 @@
const char *version_name = "rdzTTGOsonde";
const char *version_id = "master_v0.8.0";
const char *version_id = "devel20210205";
const int SPIFFS_MAJOR=2;
const int SPIFFS_MINOR=4;
const int SPIFFS_MINOR=9;

Wyświetl plik

@ -49,6 +49,9 @@ of your Arduino IDE, and rename main folder to AsyncTCP
From https://github.com/lewisxhe/AXP202X_Library select "Download ZIP", extract to the libraries
folder of your Arduino IDE, and rename main folder to AXP202X_Library-1.0
From https://github.com/dx168b/async-mqtt-client select "Download ZIP", extract to the libraries
folder of your Arduino IDE, and rename main folder to async-mqtt-client
## Additional libraries, part 3
Copy the SX1278FSK, SondeLib and fonts folders from libraries of this project to your Arduino IDE's libraries

Wyświetl plik

@ -12,11 +12,26 @@
#define DFM_DBG(x)
#endif
int DFM::setup(float frequency, int inv)
#define DFM_FRAMELEN 33
// single data structure, search restarts after decoder change
static struct st_dfmstat {
int idcnt0;
int idcnt1;
int lastfrid;
int lastfrcnt;
uint8_t start[50];
uint16_t dat[50*2];
uint8_t cnt[50*2];
uint8_t nameregok;
uint8_t nameregtop;
} dfmstate;
int DFM::setup(float frequency, int type)
{
inverse = inv;
stype = type;
#if DFM_DEBUG
Serial.printf("Setup sx1278 for DFM sonde (inv=%d)\n",inv);
Serial.printf("Setup sx1278 for DFM sonde (type=%d)\n", stype);
#endif
if(sx1278.ON()!=0) {
DFM_DBG(Serial.println("Setting SX1278 power on FAILED"));
@ -44,35 +59,70 @@ int DFM::setup(float frequency, int inv)
DFM_DBG(Serial.printf("Setting RX bandwidth to %d Hz FAILED", sonde.config.dfm.rxbw));
return 1;
}
// Enable auto-AFC, auto-AGC, RX Trigger by preamble
if(sx1278.setRxConf(0x1E)!=0) {
DFM_DBG(Serial.println("Setting RX Config FAILED"));
return 1;
}
// Set autostart_RX to 01, preamble 0, SYNC detect==on, syncsize=3 (==4 byte
//char header[] = "0110.0101 0110.0110 1010.0101 1010.1010";
const char *SYNC=inverse?"\x9A\x99\x5A\x55":"\x65\x66\xA5\xAA";
if(sx1278.setSyncConf(0x53, 4, (const uint8_t *)SYNC)!=0) {
DFM_DBG(Serial.println("Setting SYNC Config FAILED"));
return 1;
}
if(sx1278.setPreambleDetect(0xA8)!=0) {
DFM_DBG(Serial.println("Setting PreambleDetect FAILED"));
return 1;
}
if(type == STYPE_DFM09_OLD || type == STYPE_DFM06_OLD) {
// packet mode, old version, misses some frames because chip enables rx too late after
// one frame was recevied. TODO: check if this can be fixed by changing parameters
// Enable auto-AFC, auto-AGC, RX Trigger by preamble
if(sx1278.setRxConf(0x1E)!=0) {
DFM_DBG(Serial.println("Setting RX Config FAILED"));
return 1;
}
// Set autostart_RX to 01, preamble 0, SYNC detect==on, syncsize=3 (==4 byte
//char header[] = "0110.0101 0110.0110 1010.0101 1010.1010";
const char *SYNC=(stype==STYPE_DFM09_OLD)?"\x9A\x99\x5A\x55":"\x65\x66\xA5\xAA";
if(sx1278.setSyncConf(0x53, 4, (const uint8_t *)SYNC)!=0) {
DFM_DBG(Serial.println("Setting SYNC Config FAILED"));
return 1;
}
//if(sx1278.setPreambleDetect(0xA8)!=0) {
if(sx1278.setPreambleDetect(0xAA)!=0) {
DFM_DBG(Serial.println("Setting PreambleDetect FAILED"));
return 1;
}
// Packet config 1: fixed len, mancecer, no crc, no address filter
// Packet config 2: packet mode, no home ctrl, no beackn, msb(packetlen)=0)
if(sx1278.setPacketConfig(0x28, 0x40)!=0) {
DFM_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
// Packet config 1: fixed len, mancecer, no crc, no address filter
// Packet config 2: packet mode, no home ctrl, no beackn, msb(packetlen)=0)
if(sx1278.setPacketConfig(0x28, 0x40)!=0) {
DFM_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
sx1278.setPayloadLength(33); // Expect 33 bytes (7+13+13 bytes)
} else {
// continuous mode
// Enable auto-AFC, auto-AGC, RX Trigger by preamble ????
if(sx1278.setRxConf(0x1E)!=0) {
DFM_DBG(Serial.println("Setting RX Config FAILED"));
return 1;
}
// working with continuous RX
const char *SYNC="\xAA\xAA";
if(sx1278.setSyncConf(0x70, 2, (const uint8_t *)SYNC)!=0) {
DFM_DBG(Serial.println("Setting SYNC Config FAILED"));
return 1;
}
if(sx1278.setPreambleDetect(0xA8)!=0) {
//if(sx1278.setPreambleDetect(0x9F)!=0) {
DFM_DBG(Serial.println("Setting PreambleDetect FAILED"));
return 1;
}
if(sx1278.setPacketConfig(0x08, 0x40)!=0) {
DFM_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
sx1278.setPayloadLength(0); // infinite for now...
}
Serial.print("DFM: setting RX frequency to ");
Serial.println(frequency);
int retval = sx1278.setFrequency(frequency);
sx1278.clearIRQFlags();
// Do this only once in setup in continous mode
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
memset((void *)&dfmstate, 0, sizeof(dfmstate));
DFM_DBG(Serial.println("Setting SX1278 config for DFM finished\n"); Serial.println());
return retval;
}
@ -163,8 +213,147 @@ void DFM::printRaw(const char *label, int len, int ret, const uint8_t *data)
Serial.print(" ");
}
const char* typestr[16]={
"", "", "", "", "", "", // 00..05
"DFM6", // 06 => DFM6
"PS15", // 07 => PS15 (untested)
"", "",
"DFM9", // 0A => DFM9
"DF17", // 0B => DFM17?
"DF9P", // 0C => DFM9P or DFM17 test
"DF17", // 0D => DFM17
"", ""
};
#define DFMIDTHRESHOLD 2
/* inspired by oe5dxl's finddnmae in sondeudp.c of dxlaprs */
void DFM::finddfname(uint8_t *b)
{
uint8_t st;
uint32_t thres;
uint32_t i;
uint8_t ix;
uint16_t d;
st = b[0]; /* frame start byte */
ix = b[3]; /* hi/lo part of ser; (LSB due to our bitsToBytes...) */
d = (b[1]<<8) + b[2]; /* data byte */
/* find highest channel number single frame serial,
(2 frame serial will make a single serial too) */
if(dfmstate.idcnt0 < DFMIDTHRESHOLD && dfmstate.idcnt1 < DFMIDTHRESHOLD) {
uint32_t v = (st<<20) | (d<<4) | ix;
if ( st > (dfmstate.lastfrid>>20) ) {
dfmstate.lastfrid = v;
Serial.print(" MAXCH:"); Serial.print(st);
dfmstate.lastfrcnt = 0;
} else if ( st == (dfmstate.lastfrid>>20) ) {
/* same id found */
if (v == dfmstate.lastfrid) {
++dfmstate.lastfrcnt;
thres = DFMIDTHRESHOLD * 2;
/* may be a 2 frame serial so increase safety level */
if (ix <= 1) thres *= 2;
/* may be not a dfm6 so increase safety level */
if ( (st>>4) != 6) thres *= 2;
if (dfmstate.lastfrcnt >= thres) {
/* id found */
if (dfmstate.lastfrcnt == thres) {
uint32_t id = ((st&0x0F)<<20) | (d<<4) | ix;
uint32_t chkid = id;
int i;
/* check validity */
for(i=0; i<6; i++) {
if((chkid&0x0f)>9) { break; /* not ok */ }
chkid >>= 4;
}
if(i==6) {
snprintf(sonde.si()->id, 10, "D%x ", id);
sonde.si()->validID = true;
strncpy(sonde.si()->typestr, typestr[ (st>>4)&0x0F ], 5);
return;
}
dfmstate.lastfrcnt = 0;
Serial.print(" NOT NUMERIC SERIAL");
}
//anonym->idtime = osic_time();
} else {
Serial.print(" MAXCHCNT/SECLVL:");
Serial.print(dfmstate.lastfrcnt);
Serial.print("/");
Serial.print(thres);
}
} else {
dfmstate.lastfrid = v; /* not stable ser */
dfmstate.lastfrcnt = 0UL;
}
}
} /*find highest channel number single frame serial */
i = 0;
while (i<dfmstate.nameregtop && dfmstate.start[i]!=st) i++;
Serial.printf(" %02x:i=%d,top=%d", st, i, dfmstate.nameregtop);
if (i<dfmstate.nameregtop) {
if (ix<=1UL && (dfmstate.cnt[2*i+ix]==0 || dfmstate.dat[2*i+ix]==d)) {
dfmstate.dat[2*i+ix] = d;
if(dfmstate.cnt[2*i+ix] < 255) dfmstate.cnt[2*i+ix]++;
Serial.print(" ID:");
Serial.print(st, HEX);
Serial.print("[");
Serial.print(ix);
Serial.print("] CNT:");
Serial.print(dfmstate.cnt[2*i]);
Serial.print(",");
Serial.print(dfmstate.cnt[2*i+1]);
Serial.print(",st=");
Serial.print(st);
Serial.print(",lastfrid=");
Serial.print(dfmstate.lastfrid>>20);
if( (dfmstate.cnt[2*i]>DFMIDTHRESHOLD && dfmstate.cnt[2*i+1]>DFMIDTHRESHOLD) ||
(dfmstate.cnt[2*i]>0 && dfmstate.cnt[2*i+1]>0 && st == (dfmstate.lastfrid>>20) && (st>>4)>6) ) {
if(dfmstate.idcnt0 <= 1) {
dfmstate.idcnt0 = dfmstate.cnt[2*i];
dfmstate.idcnt1 = dfmstate.cnt[2*i+1];
dfmstate.nameregok = i;
// generate id.....
snprintf(sonde.si()->id, 10, "D%d", ((dfmstate.dat[2*i]<<16)|dfmstate.dat[2*i+1])%100000000);
Serial.print("\nNEW AUTOID:");
Serial.println(sonde.si()->id);
sonde.si()->validID = true;
strncpy(sonde.si()->typestr, typestr[ (st>>4)&0x0F ], 5);
}
if(dfmstate.nameregok==i) {
Serial.print(" ID OK");
// idtime = .... /* TODO */
}
}
} else {
/* data changed so not ser */
dfmstate.cnt[2*i] = 0;
dfmstate.cnt[2*i+1] = 0;
if(dfmstate.nameregok == i) { /* found id wrong */
dfmstate.idcnt0 = 0;
dfmstate.idcnt1 = 0;
}
}
} else if (ix<=1) { /* add new entry for possible ID */
dfmstate.start[dfmstate.nameregtop] = st;
dfmstate.cnt[2*dfmstate.nameregtop] = 0;
dfmstate.cnt[2*dfmstate.nameregtop+1] = 0;
dfmstate.cnt[2*dfmstate.nameregtop+ix] = 1;
dfmstate.dat[2*dfmstate.nameregtop+ix] = d;
if(dfmstate.nameregtop<49) dfmstate.nameregtop++;
}
}
void DFM::decodeCFG(uint8_t *cfg)
{
#if 1
// new ID
finddfname(cfg);
// new aprs ID (dxlaprs, autorx) is now "D" + serial (8 digits) by consensus
memcpy(sonde.si()->ser, sonde.si()->id+1, 9);
#else
// old ID
static int lowid, highid, idgood=0, type=0;
if((cfg[0]>>4)==0x06 && type==0) { // DFM-6 ID
lowid = ((cfg[0]&0x0F)<<20) | (cfg[1]<<12) | (cfg[2]<<4) | (cfg[3]&0x0f);
@ -190,6 +379,7 @@ void DFM::decodeCFG(uint8_t *cfg)
sonde.si()->validID = true;
}
}
#endif
}
static int bitCount(int x) {
@ -288,20 +478,140 @@ void DFM::bitsToBytes(uint8_t *bits, uint8_t *bytes, int len)
bytes[(i-1)/8] &= 0x0F;
}
static int haveNewFrame = 0;
int DFM::processDFMdata(uint8_t dt) {
static uint8_t data[1024];
static uint32_t rxdata = 0;
static uint8_t rxbitc = 0;
static uint8_t rxbyte = 0;
static uint8_t rxsearching = 1;
static uint8_t rxp;
static int rssi=0, fei=0, afc=0;
static uint8_t invers = 0;
for(int i=0; i<8; i++) {
uint8_t d = (dt&0x80)?1:0;
dt <<= 1;
rxdata = (rxdata<<1) | d;
if( (rxbitc&1)==0 ) {
// "bit1"
rxbyte = (rxbyte<<1) | d;
} else {
// "bit2" ==> 01 or 10 => 1, otherweise => 0
// not here: (10=>1, 01=>0)!!! rxbyte = rxbyte ^ d;
}
//
if(rxsearching) {
if( rxdata == 0x6566A5AA || rxdata == 0x9A995A55 ) {
rxsearching = false;
rxbitc = 0;
rxp = 0;
rxbyte = 0;
rssi=sx1278.getRSSI();
fei=sx1278.getFEI();
afc=sx1278.getAFC();
sonde.si()->rssi = rssi;
sonde.si()->afc = afc;
invers = (rxdata == 0x6566A5AA)?1:0;
}
} else {
rxbitc = (rxbitc+1)%16; // 16;
if(rxbitc == 0) { // got 8 data bit
if(invers) rxbyte=~rxbyte;
data[rxp++] = rxbyte&0xff; // (rxbyte>>1)&0xff;
if(rxp>=DFM_FRAMELEN) {
rxsearching = true;
//Serial.println("Got a DFM frame!");
Serial.print("[RSSI="); Serial.print(rssi);
Serial.print(" FEI="); Serial.print(fei);
Serial.print(" AFC="); Serial.print(afc); Serial.print("] ");
decodeFrameDFM(data);
haveNewFrame = 1;
}
}
}
}
return 0;
}
int DFM::receive() {
if( stype == STYPE_DFM ) {
return receiveNew();
} else {
return receiveOld();
}
}
int DFM::receiveNew() {
int rxframes = 4;
// tentative continuous RX version...
unsigned long t0 = millis();
while( ( millis() - t0 ) < 1000 ) {
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2);
if ( bitRead(value, 7) ) {
Serial.println("FIFO full");
}
if ( bitRead(value, 4) ) {
Serial.println("FIFO overflow");
// new: (maybe clear only overflow??) TODO
sx1278.clearIRQFlags();
}
if ( bitRead(value, 2) == 1 ) {
Serial.println("FIFO: payload ready()");
// does not make much sence? (from m10): TODO
// ??????? sx1278.clearIRQFlags();
}
if(bitRead(value, 6) == 0) { // while FIFO not empty
byte data = sx1278.readRegister(REG_FIFO);
processDFMdata(data);
value = sx1278.readRegister(REG_IRQ_FLAGS2);
} else {
#if 0
if(headerDetected) {
t0 = millis(); // restart timer... don't time out if header detected...
headerDetected = 0;
}
#endif
if(haveNewFrame) {
//Serial.printf("DFM::receive(): new frame complete after %ldms\n", millis()-t0);
haveNewFrame = 0;
rxframes--;
if(rxframes==0) return RX_OK;
}
delay(2);
}
}
return RX_TIMEOUT;
}
int DFM::receiveOld() {
byte data[1000]; // pending data from previous mode may write more than 33 bytes. TODO.
for(int i=0; i<2; i++) {
sx1278.setPayloadLength(33); // Expect 33 bytes (7+13+13 bytes)
sx1278.setPayloadLength(33); // Expect 33 bytes (7+13+13 bytes)
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
//int t = millis();
int e = sx1278.receivePacketTimeout(1000, data);
//Serial.printf("rxPTO done after %d ms", (int)(millis()-t));
if(e) { return RX_TIMEOUT; } //if timeout... return 1
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
int e = sx1278.receivePacketTimeout(1000, data);
if(e) { return RX_TIMEOUT; } //if timeout... return 1
if(!(stype==STYPE_DFM09_OLD)) { for(int i=0; i<33; i++) { data[i]^=0xFF; } }
decodeFrameDFM(data);
}
return RX_OK;
}
Serial.printf("inverse is %d\b", inverse);
if(!inverse) { for(int i=0; i<33; i++) { data[i]^=0xFF; } }
int DFM::decodeFrameDFM(uint8_t *data) {
deinterleave(data, 7, hamming_conf);
deinterleave(data+7, 13, hamming_dat1);
deinterleave(data+20, 13, hamming_dat2);
#if 0
Serial.print("RAWCFG:");
for(int i=0; i<7*8; i++) {
Serial.print(hamming_conf[i]?"1":"0");
}
#endif
int ret0 = hamming(hamming_conf, 7, block_conf);
int ret1 = hamming(hamming_dat1, 13, block_dat1);
@ -318,7 +628,7 @@ int DFM::receive() {
decodeCFG(byte_conf);
decodeDAT(byte_dat1);
decodeDAT(byte_dat2);
}
Serial.println("");
return RX_OK;
}

Wyświetl plik

@ -23,16 +23,23 @@
class DFM
{
private:
int inverse=0;
int stype;
char *stypename=NULL;
void deinterleave(uint8_t *str, int L, uint8_t *block);
uint32_t bits2val(const uint8_t *bits, int len);
int check(uint8_t code[8]);
int hamming(uint8_t *ham, int L, uint8_t *sym);
void printRaw(const char *prefix, int len, int ret, const uint8_t* data);
void finddfname(uint8_t *cfg);
void decodeCFG(uint8_t *cfg);
void decodeDAT(uint8_t *dat);
void bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);
int processDFMdata(uint8_t dt);
int decodeFrameDFM(uint8_t *data);
int receiveOld();
int receiveNew();
#define B 8
#define S 4
@ -55,7 +62,7 @@ private:
public:
DFM();
// main decoder API
int setup(float frequency, int inverse);
int setup(float frequency, int type);
int receive();
int waitRXcomplete();

Wyświetl plik

@ -11,24 +11,25 @@ int readLine(Stream &stream, char *buffer, int maxlen);
extern const char *version_name;
extern const char *version_id;
#include <../fonts/FreeMono9pt7b.h>
#include <../fonts/FreeMono12pt7b.h>
#include <../fonts/FreeSans9pt7b.h>
#include <../fonts/FreeSans12pt7b.h>
#include <../fonts/Picopixel.h>
#include <fonts/FreeMono9pt7b.h>
#include <fonts/FreeMono12pt7b.h>
#include <fonts/FreeSans9pt7b.h>
#include <fonts/FreeSans12pt7b.h>
#include <fonts/Picopixel.h>
extern Sonde sonde;
extern MicroNMEA nmea;
extern AXP20X_Class axp;
extern bool axp192_found;
extern SemaphoreHandle_t axpSemaphore;
struct GpsPos gpsPos;
SPIClass spiDisp(HSPI);
const char *sondeTypeStr[NSondeTypes] = { "DFM6", "DFM9", "RS41", "RS92", "M10 " };
const char *sondeTypeStr[NSondeTypes] = { "DFM ", "DFM9", "RS41", "RS92", "M10 ", "M20 ", "DFM6" };
const char *sondeTypeLongStr[NSondeTypes] = { "DFM (all)", "DFM9 (old)", "RS41", "RS92", "M10 ", "M20 ", "DFM6 (old)" };
const char sondeTypeChar[NSondeTypes] = { 'D', '9', '4', 'R', 'M', '2', '6' };
byte myIP_tiles[8*11];
static uint8_t ap_tile[8]={0x00,0x04,0x22,0x92, 0x92, 0x22, 0x04, 0x00};
@ -267,7 +268,7 @@ void U8x8Display::welcome() {
drawString(8 - strlen(version_name) / 2, 0, version_name);
drawString(8 - strlen(version_id) / 2, 2, version_id);
setFont(FONT_SMALL);
drawString(0, 4, "RS41/92,DFM,M10");
drawString(0, 4, "RS41/92,DFM,Mx0");
drawString(0, 6, "by Hansi, DL9RDZ");
}
@ -384,39 +385,85 @@ void ILI9225Display::getDispSize(uint8_t *height, uint8_t *width, uint8_t *lines
}
}
// Note: alignright means that there is a box from x to x+(-width), with text right-justified
// x is the *left* corner! not the right...
void ILI9225Display::drawString(uint8_t x, uint8_t y, const char *s, int16_t width, uint16_t fg, uint16_t bg) {
int16_t w,h;
boolean alignright=false;
if(findex<3) { // standard font
Serial.printf("Simple Text %s at %d,%d [%d]\n", s, x, y, width);
tft->drawText(x, y, s, fg);
return;
}
// GFX font
if(width<0) {
width = -width;
alignright = true;
}
// Standard font
if(findex<3) {
DebugPrintf(DEBUG_DISPLAY, "Simple Text %s at %d,%d [%d]\n", s, x, y, width);
tft->setBackgroundColor(bg);
int h = tft->getFont().height;
if( alignright ) {
w = tft->getTextWidth(s);
if( width==WIDTH_AUTO ) { width = w; }
if( width > w ) {
tft->fillRectangle(x, y, x + width - w, y + h - 1, bg);
}
tft->drawText(x + width - w, y, s, fg);
} else {
int curx = tft->drawText(x, y, s, fg);
if( width==WIDTH_AUTO ) { return; }
if(curx < x + width) {
tft->fillRectangle(curx, y, x + width - 1, y + h - 1, bg);
}
}
return;
}
// GFX font
if(width==WIDTH_AUTO || alignright) {
tft->getGFXTextExtent(s, x, y + gfxoffsets[findex-3].yofs, &w, &h);
if(width==WIDTH_AUTO) {
width=w;
if(alignright) {
x -= w;
Serial.print("reducing x by widht, its now ");
Serial.println(x);
if(width==WIDTH_AUTO) { width=w; }
if(alignright) {
if(w > width) {
// fast drawBitmap does bad things if not within viewport
// Maybe better truncate on the right? (TODO)
x = x - w + width; if(x<0) x=0;
width = w;
}
//x -= width;
//DebugPrintf(DEBUG_DISPLAY, "Reducing x by width %d, its now %d\n", width, x);
}
}
if(findex-3>=ngfx) findex=3;
DebugPrintf(DEBUG_DISPLAY,"GFX Text %s at %d,%d+%d in color %x, width=%d (w=%d)\n", s, x, y, gfxoffsets[findex-3].yofs, fg, width, w);
#if 0
// Text by clear rectangle and refill, causes some flicker
tft->fillRectangle(x, y, x + width, y + gfxoffsets[findex-3].yclear, bg);
Serial.printf("GFX Text %s at %d,%d+%d in color %x, width=%d (w=%d)\n", s, x, y, gfxoffsets[findex-3].yofs, fg, width, w);
if(alignright) {
tft->drawGFXText(x + width - w, y + gfxoffsets[findex-3].yofs, s, fg);
} else {
tft->drawGFXText(x, y + gfxoffsets[findex-3].yofs, s, fg);
}
#else
// Text by drawing bitmap.... => less "flicker"
uint16_t height = gfxoffsets[findex-3].yclear;
uint16_t *bitmap = (uint16_t *)malloc(sizeof(uint16_t) * width * height);
if(!bitmap) {
Serial.println("FATAL: OUT OF MEMORY when allocating bitmap");
Serial.printf("w=%d, h=%d, s==%d\n",width, height, 2*width*height);
heap_caps_print_heap_info(MALLOC_CAP_DEFAULT);
return;
}
for(int i=0; i<width*height; i++) { bitmap[i] = bg; } // fill with background
int x0 = 0;
if(alignright) { x0 = width - w; }
int y0 = gfxoffsets[findex-3].yofs;
DebugPrintf(DEBUG_DISPLAY,"GFX: w=%d h=%d\n", width, height);
for (uint8_t k = 0; k < strlen(s); k++) {
x0 += tft->drawGFXcharBM(x0, y0, s[k], fg, bitmap, width, height) + 1;
DebugPrintf(DEBUG_DISPLAY,"[%c->%d]",s[k],x0);
}
// TODO: if x+width exceeds display width, garbage is generated....
drawBitmap(x, y, bitmap, width, height);
free(bitmap);
#endif
}
void ILI9225Display::drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr) {
@ -455,10 +502,10 @@ void ILI9225Display::welcome() {
setFont(5);
int l=3*22;
if(sonde.config.tft_orient&1) {
drawString(0, 1*22, "RS41/92,DFM6/9,M10");
drawString(0, 1*22, "RS41/92,DFM,M10/20");
} else {
drawString(0, 1*22, "RS41,RS92,");
drawString(0, 2*22, "DFM6/9,M10");
drawString(0, 2*22, "DFM,M10/20");
l+=22;
}
drawString(0, l, version_id);
@ -686,6 +733,7 @@ void Display::parseDispElement(char *text, DispEntry *de)
// Large font can be used arbitrarily
if(de->fmt==fontsma) de->fmt=0;
de->func = disp.drawIP; break;
de->extra = strdup(text+1);
case 's':
de->func = disp.drawSite;
de->extra = strdup(text+1);
@ -795,8 +843,16 @@ int Display::countEntries(File f) {
return n;
}
void Display::initFromFile() {
File d = SPIFFS.open("/screens.txt", "r");
void Display::initFromFile(int index) {
File d;
if(index>0) {
char file[20];
snprintf(file, 20, "/screens%d.txt", index);
Serial.printf("Trying %i (%s)\n", index, file);
d = SPIFFS.open(file, "r");
if(!d || d.available()==0 ) { Serial.printf("%s not found, using /screens.txt\n", file); }
}
if(!d || d.available()==0 ) d = SPIFFS.open("/screens.txt", "r");
if(!d) return;
DispInfo *newlayouts = (DispInfo *)malloc(MAXSCREENS * sizeof(DispInfo));
@ -806,13 +862,18 @@ void Display::initFromFile() {
}
memset(newlayouts, 0, MAXSCREENS * sizeof(DispInfo));
// default values
xscale=13;
yscale=22;
fontsma=0;
fontlar=1;
// default color
colfg = 0xffff; // white; only used for ILI9225
colbg = 0; // black; only used for ILI9225
int idx = -1;
int what = -1;
int entrysize;
Serial.printf("Reading from /screens.txt. available=%d\n",d.available());
Serial.printf("Reading from screen config: available=%d\n",d.available());
while(d.available()) {
//Serial.printf("Unused stack: %d\n", uxTaskGetStackHighWaterMark(0));
const char *ptr;
@ -821,7 +882,7 @@ void Display::initFromFile() {
// String line = readLine(d);
// line.trim();
// const char *s = line.c_str();
Serial.printf("Line: '%s'\n", s);
DebugPrintf(DEBUG_SPARSER, "Line: '%s'\n", s);
if(*s == '#') continue; // ignore comments
switch(what) {
case -1: // wait for start of screen (@)
@ -832,7 +893,7 @@ void Display::initFromFile() {
}
char *label = strdup(s+1);
entrysize = countEntries(d);
Serial.printf("Reading entry with %d elements\n", entrysize);
DebugPrintf(DEBUG_SPARSER,"Reading entry with %d elements\n", entrysize);
idx++;
int res = allocDispInfo(entrysize, &newlayouts[idx], label);
Serial.printf("allocDispInfo: idx %d: label is %p - %s\n",idx,newlayouts[idx].label, newlayouts[idx].label);
@ -847,7 +908,7 @@ void Display::initFromFile() {
if(strncmp(s,"timer=",6)==0) { // timer values
char t1[10],t2[10],t3[10];
sscanf(s+6, "%5[0-9a-zA-Z-] , %5[0-9a-zA-Z-] , %5[0-9a-zA-Z-]", t1, t2, t3);
Serial.printf("timers are %s, %s, %s\n", t1, t2, t3);
DebugPrintf(DEBUG_SPARSER,"timers are %s, %s, %s\n", t1, t2, t3);
newlayouts[idx].timeouts[0] = (*t1=='n'||*t1=='N')?sonde.config.norx_timeout:atoi(t1);
newlayouts[idx].timeouts[1] = (*t2=='n'||*t2=='N')?sonde.config.norx_timeout:atoi(t2);
newlayouts[idx].timeouts[2] = (*t3=='n'||*t3=='N')?sonde.config.norx_timeout:atoi(t3);
@ -901,7 +962,7 @@ void Display::initFromFile() {
newlayouts[idx].de[what].y = y;
newlayouts[idx].de[what].width = n>2 ? w : WIDTH_AUTO;
parseDispElement(text, newlayouts[idx].de+what);
Serial.printf("entry at %d,%d width=%d font %d, color=%x,%x\n", (int)x, (int)y, newlayouts[idx].de[what].width, newlayouts[idx].de[what].fmt,
DebugPrintf(DEBUG_SPARSER,"entry at %d,%d width=%d font %d, color=%x,%x\n", (int)x, (int)y, newlayouts[idx].de[what].width, newlayouts[idx].de[what].fmt,
newlayouts[idx].de[what].fg, newlayouts[idx].de[what].bg);
if(newlayouts[idx].de[what].func == disp.drawGPS) {
newlayouts[idx].usegps = GPSUSE_BASE|GPSUSE_DIST|GPSUSE_BEARING; // just all for now
@ -1004,7 +1065,7 @@ void Display::drawHS(DispEntry *de) {
}
boolean is_ms = (de->extra && de->extra[0]=='m')?true:false; // m/s or km/h
float hs = sonde.si()->hs;
if(is_ms) hs = hs / 3.6;
if(!is_ms) hs = hs * 3.6;
boolean has_extra = (de->extra && de->extra[1]!=0)? true: false;
snprintf(buf, 16, hs>99?" %3.0f":" %2.1f", hs);
if(has_extra) { strcat(buf, de->extra+1); }
@ -1018,7 +1079,7 @@ void Display::drawVS(DispEntry *de) {
return;
}
snprintf(buf, 16, " %+2.1f", sonde.si()->vs);
Serial.printf("drawVS: extra is %s width=%d\n", de->extra?de->extra:"<null>", de->width);
DebugPrintf(DEBUG_DISPLAY, "drawVS: extra is %s width=%d\n", de->extra?de->extra:"<null>", de->width);
if(de->extra) { strcat(buf, de->extra); }
drawString(de, buf+strlen(buf)-5- (de->extra?strlen(de->extra):0) );
if(!de->extra) rdis->drawTile(de->x+5,de->y,2,ms_tiles);
@ -1029,24 +1090,24 @@ void Display::drawID(DispEntry *de) {
drawString(de, "nnnnnnnn ");
return;
}
// TODO: handle DFM6 IDs
if(!de->extra || de->extra[0]=='s') {
// real serial number, as printed on sonde
if(de->extra && de->extra[0]=='n') {
// real serial number, as printed on sonde, can be up to 11 digits long
drawString(de, sonde.si()->ser);
} else if (de->extra[0]=='a') {
// autorx sonde number ("DF9" and last 6 digits of real serial number)
if(sonde.si()->type == STYPE_DFM09) {
int n = strlen(sonde.si()->ser) - 6;
if(n<0) n=0;
memcpy(buf, "DF9", 3);
memcpy(buf+3, sonde.si()->ser+n, 6);
drawString(de, buf);
} else if (de->extra && de->extra[0]=='s') {
// short ID, max 8 digits (no initial "D" for DFM, "M" instead of "ME" for M10)
if( TYPE_IS_DFM(sonde.si()->type) ) {
drawString(de, sonde.si()->id+1);
} else if (TYPE_IS_METEO(sonde.si()->type)) {
char sid[9];
sid[0]='M';
memcpy(sid+1, sonde.si()->id+2, 8);
sid[8] = 0;
drawString(de, sid);
} else {
drawString(de, sonde.si()->ser);
drawString(de, sonde.si()->id);
}
} else {
// dxlAPRS sonde number (DF6 (why??) and 5 last digits of serial number as hex number
// dxlAPRS sonde number, max 9 digits, as used on aprs.fi and radiosondy.info
drawString(de, sonde.si()->id);
}
}
@ -1073,7 +1134,9 @@ void Display::drawQS(DispEntry *de) {
void Display::drawType(DispEntry *de) {
rdis->setFont(de->fmt);
drawString(de, sondeTypeStr[sonde.si()->type]);
const char *typestr = sonde.si()->typestr;
if(*typestr==0) typestr = sondeTypeStr[sonde.si()->type];
drawString(de, typestr);
}
void Display::drawFreq(DispEntry *de) {
rdis->setFont(de->fmt);
@ -1131,7 +1194,7 @@ void Display::drawTelemetry(DispEntry *de) {
void Display::drawKilltimer(DispEntry *de) {
rdis->setFont(de->fmt);
uint16_t value;
uint16_t value=0;
switch(de->extra[0]) {
case 'l': value = sonde.si()->launchKT; break;
case 'b': value = sonde.si()->burstKT; break;
@ -1169,6 +1232,7 @@ void Display::drawKilltimer(DispEntry *de) {
extern int lastCourse; // from RX_FSK.ino
void Display::calcGPS() {
// base data
#if 0
#if FAKEGPS
gpsValid = true;
gpsLat = 48.9;
@ -1181,7 +1245,7 @@ static int tmpc=0;
gpsValid = nmea.isValid();
gpsLon = nmea.getLongitude()*0.000001;
gpsLat = nmea.getLatitude()*0.000001;
long alt;
long alt = 0;
nmea.getAltitude(alt); gpsAlt=(int)(alt/1000);
gpsCourse = (int)(nmea.getCourse()/1000);
gpsCourseOld = false;
@ -1193,12 +1257,13 @@ static int tmpc=0;
gpsCourse = lastCourse;
}
}
#endif
#endif
// distance
if( gpsValid && (sonde.si()->validPos&0x03)==0x03 && (layout->usegps&GPSUSE_DIST)) {
float lat1 = nmea.getLatitude()*0.000001;
if( gpsPos.valid && (sonde.si()->validPos&0x03)==0x03 && (layout->usegps&GPSUSE_DIST)) {
float lat1 = gpsPos.lat;
float lat2 = sonde.si()->lat;
float x = radians(nmea.getLongitude()*0.000001-sonde.si()->lon) * cos( radians((lat1+lat2)/2) );
float x = radians(gpsPos.lon-sonde.si()->lon) * cos( radians((lat1+lat2)/2) );
float y = radians(lat2-lat1);
float d = sqrt(x*x+y*y)*EARTH_RADIUS;
gpsDist = (int)d;
@ -1206,17 +1271,17 @@ static int tmpc=0;
gpsDist = -1;
}
// bearing
if( gpsValid && (sonde.si()->validPos&0x03)==0x03 && (layout->usegps&GPSUSE_BEARING)) {
float lat1 = radians(gpsLat);
if( gpsPos.valid && (sonde.si()->validPos&0x03)==0x03 && (layout->usegps&GPSUSE_BEARING)) {
float lat1 = radians(gpsPos.lat);
float lat2 = radians(sonde.si()->lat);
float lon1 = radians(gpsLon);
float lon1 = radians(gpsPos.lon);
float lon2 = radians(sonde.si()->lon);
float y = sin(lon2-lon1)*cos(lat2);
float x = cos(lat1)*sin(lat2) - sin(lat1)*cos(lat2)*cos(lon2-lon1);
float dir = atan2(y, x)/PI*180;
if(dir<0) dir+=360;
gpsDir = (int)dir;
gpsBear = gpsDir - gpsCourse;
gpsBear = gpsDir - gpsPos.course;
if(gpsBear < 0) gpsBear += 360;
if(gpsBear >= 360) gpsBear -= 360;
} else {
@ -1224,39 +1289,39 @@ static int tmpc=0;
gpsBear = -1;
}
Serial.printf("GPS data: valid%d GPS at %f,%f (alt=%d,cog=%d); sonde at dist=%d, dir=%d rel.bear=%d\n",gpsValid?1:0,
gpsLat, gpsLon, gpsAlt, gpsCourse, gpsDist, gpsDir, gpsBear);
DebugPrintf(DEBUG_DISPLAY, "GPS data: valid%d GPS at %f,%f (alt=%d,cog=%d); sonde at dist=%d, dir=%d rel.bear=%d\n",gpsPos.valid?1:0,
gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.course, gpsDist, gpsDir, gpsBear);
}
void Display::drawGPS(DispEntry *de) {
if(sonde.config.gps_rxd<0) return;
// TODO: FIXME: ??? if(sonde.config.gps_rxd<0) return;
rdis->setFont(de->fmt);
switch(de->extra[0]) {
case 'V':
{
// show if GPS location is valid
uint8_t *tile = disp.gpsValid?gps_tile:nogps_tile;
uint8_t *tile = gpsPos.valid?gps_tile:nogps_tile;
rdis->drawTile(de->x, de->y, 1, tile);
}
break;
case 'O':
// GPS long
snprintf(buf, 16, "%2.5f", disp.gpsLon);
snprintf(buf, 16, "%2.5f", gpsPos.lon);
drawString(de,buf);
break;
case 'A':
// GPS lat
snprintf(buf, 16, "%2.5f", disp.gpsLat);
snprintf(buf, 16, "%2.5f", gpsPos.lat);
drawString(de,buf);
break;
case 'H':
// GPS alt
snprintf(buf, 16, "%4dm", disp.gpsAlt);
snprintf(buf, 16, "%4dm", gpsPos.alt);
drawString(de,buf);
break;
case 'C':
// GPS Course over ground
snprintf(buf, 4, "%3d", disp.gpsCourse);
snprintf(buf, 4, "%3d", gpsPos.course);
drawString(de, buf);
break;
case 'D':
@ -1266,7 +1331,7 @@ void Display::drawGPS(DispEntry *de) {
if( (sonde.si()->validPos&0x03)!=0x03 ) {
snprintf(buf, 16, "no pos ");
if(de->extra && *de->extra=='5') buf[5]=0;
} else if(!disp.gpsValid) {
} else if(!gpsPos.valid) {
snprintf(buf, 16, "no gps ");
if(de->extra && *de->extra=='5') buf[5]=0;
} else {
@ -1286,7 +1351,7 @@ void Display::drawGPS(DispEntry *de) {
break;
case 'I':
// dIrection
if( (!disp.gpsValid) || ((sonde.si()->validPos&0x03)!=0x03 ) ) {
if( (!gpsPos.valid) || ((sonde.si()->validPos&0x03)!=0x03 ) ) {
drawString(de, "---");
break;
}
@ -1298,7 +1363,7 @@ void Display::drawGPS(DispEntry *de) {
break;
case 'B':
// relative bearing
if( (!disp.gpsValid) || ((sonde.si()->validPos&0x03)!=0x03 ) ) {
if( (!gpsPos.valid) || ((sonde.si()->validPos&0x03)!=0x03 ) ) {
drawString(de, "---");
break;
}
@ -1328,21 +1393,21 @@ void Display::drawGPS(DispEntry *de) {
bool rxgood = (sonde.si()->rxStat[0]==0);
int angN, angA, angB; // angle of north, array, bullet
int validA, validB; // 0: no, 1: yes, -1: old
if(circinfo->arr=='C') { angA=disp.gpsCourse; validA=disp.gpsCourseOld?-1:1; }
if(circinfo->arr=='C') { angA=gpsPos.course; validA=disp.gpsCourseOld?-1:1; }
else { angA=disp.gpsDir; validA=sonde.si()->validPos?(rxgood?1:-1):0; }
if(circinfo->bul=='C') { angB=disp.gpsCourse; validB=disp.gpsCourseOld?-1:1; }
if(circinfo->bul=='C') { angB=gpsPos.course; validB=disp.gpsCourseOld?-1:1; }
else { angB=disp.gpsDir; validB=sonde.si()->validPos?(rxgood?1:-1):0; }
if(circinfo->top=='N') {
angN = 0;
} else {
//if (circinfo->top=='C') {
angN = 360-disp.gpsCourse;
angN = 360-gpsPos.course;
angA += angN; if(angA>=360) angA-=360;
angB += angN; if(angB>=360) angB-=360;
}
Serial.printf("GPS0: %c%c%c N=%d, A=%d, B=%d\n", circinfo->top, circinfo->arr, circinfo->bul, angN, angA, angB);
// "N" in direction angN
static_cast<ILI9225Display *>(rdis)->tft->drawGFXcharBM(x0 + circinfo->radius*sin(angN*PI/180)-6, y0 - circinfo->radius*cos(angN*PI/180)+7, 'N', 0xffff, bitmap, size);
static_cast<ILI9225Display *>(rdis)->tft->drawGFXcharBM(x0 + circinfo->radius*sin(angN*PI/180)-6, y0 - circinfo->radius*cos(angN*PI/180)+7, 'N', 0xffff, bitmap, size, size);
// small circle in direction angB
if(validB) {

Wyświetl plik

@ -10,6 +10,15 @@
#include <U8x8lib.h>
#include <SPIFFS.h>
struct GpsPos {
double lat;
double lon;
int alt;
int course;
int valid;
};
extern struct GpsPos gpsPos;
#define WIDTH_AUTO 9999
struct DispEntry {
int16_t y;
@ -123,11 +132,8 @@ private:
static void circ(uint16_t *bm, int16_t w, int16_t x0, int16_t y0, int16_t r, uint16_t fg, boolean fill, uint16_t bg);
static int countEntries(File f);
void calcGPS();
boolean gpsValid;
float gpsLat, gpsLon;
int gpsAlt;
int gpsDist; // -1: invalid
int gpsCourse, gpsDir, gpsBear; // 0..360; -1: invalid
int gpsDir, gpsBear; // 0..360; -1: invalid
boolean gpsCourseOld;
static const int LINEBUFLEN{ 255 };
static char lineBuf[LINEBUFLEN];
@ -145,7 +151,7 @@ private:
return ret;
}
public:
void initFromFile();
void initFromFile(int index);
int layoutIdx;
DispInfo *layout;

Wyświetl plik

@ -1,529 +0,0 @@
/* M10 decoder functions */
#include "M10.h"
#include "SX1278FSK.h"
#include "rsc.h"
#include "Sonde.h"
#include <SPIFFS.h>
// well...
//#include "rs92gps.h"
#define M10_DEBUG 1
#if M10_DEBUG
#define M10_DBG(x) x
#else
#define M10_DBG(x)
#endif
static byte data1[512];
static byte *dataptr=data1;
static uint8_t rxbitc;
static uint16_t rxbyte;
static int rxp=0;
static int haveNewFrame = 0;
static int lastFrame = 0;
static int headerDetected = 0;
int M10::setup(float frequency)
{
#if M10_DEBUG
Serial.println("Setup sx1278 for M10 sonde");
#endif
//if(!initialized) {
//Gencrctab();
//initrsc();
// not here for now.... get_eph("/brdc.19n");
// initialized = true;
//}
if(sx1278.ON()!=0) {
M10_DBG(Serial.println("Setting SX1278 power on FAILED"));
return 1;
}
if(sx1278.setFSK()!=0) {
M10_DBG(Serial.println("Setting FSJ mode FAILED"));
return 1;
}
if(sx1278.setBitrate(9600)!=0) {
M10_DBG(Serial.println("Setting bitrate 9600bit/s FAILED"));
return 1;
}
#if M10_DEBUG
float br = sx1278.getBitrate();
Serial.print("Exact bitrate is ");
Serial.println(br);
#endif
if(sx1278.setAFCBandwidth(sonde.config.rs92.rxbw)!=0) {
M10_DBG(Serial.printf("Setting AFC bandwidth %d Hz FAILED", sonde.config.rs92.rxbw));
return 1;
}
if(sx1278.setRxBandwidth(sonde.config.rs92.rxbw)!=0) {
M10_DBG(Serial.printf("Setting RX bandwidth to %d Hz FAILED", sonde.config.rs92.rxbw));
return 1;
}
// Enable auto-AFC, auto-AGC, RX Trigger by preamble
if(sx1278.setRxConf(0x1E)!=0) {
M10_DBG(Serial.println("Setting RX Config FAILED"));
return 1;
}
// Set autostart_RX to 01, preamble 0, SYNC detect==on, syncsize=3 (==4 byte
//char header[] = "0110.0101 0110.0110 1010.0101 1010.1010";
//const char *SYNC="\x10\xB6\xCA\x11\x22\x96\x12\xF8";
//const char *SYNC="\x08\x6D\x53\x88\x44\x69\x48\x1F";
// was 0x57
//const char *SYNC="\x99\x9A";
#if 1
// version 1, working with continuous RX
const char *SYNC="\x66\x65";
if(sx1278.setSyncConf(0x70, 2, (const uint8_t *)SYNC)!=0) {
M10_DBG(Serial.println("Setting SYNC Config FAILED"));
return 1;
}
//if(sx1278.setPreambleDetect(0xA8)!=0) {
if(sx1278.setPreambleDetect(0x9F)!=0) {
M10_DBG(Serial.println("Setting PreambleDetect FAILED"));
return 1;
}
#endif
#if 0
// version 2, with per-packet rx start, untested
// header is 2a 10 65, i.e. with lsb first
// 0 0101 0100 1 0 0000 1000 1 0 1010 0110 1
// 10 10011001 10011010 01 10 10101010 01101010 01 10 01100110 10010110 01
// preamble 0x6A 0x66 0x6A
// i.e. preamble detector on (0x80), preamble detector size 1 (0x00), preample chip errors??? (0x0A)
// after 2a2a2a2a2a1065
if(sx1278.setPreambleDetect(0xA8)!=0) {
M10_DBG(Serial.println("Setting PreambleDetect FAILED"));
return 1;
}
// sync config: ato restart (01), preamble polarity AA (0), sync on (1), resevered (0), syncsize 2+1 (010) => 0x52
const char *SYNC="\x6A\x66\x69";
if(sx1278.setSyncConf(0x52, 3, (const uint8_t *)SYNC)!=0) {
M10_DBG(Serial.println("Setting SYNC Config FAILED"));
return 1;
}
// payload length is ((240 - 7)*10 +6)/8 = 292
#endif
// Packet config 1: fixed len, no mancecer, no crc, no address filter
// Packet config 2: packet mode, no home ctrl, no beackn, msb(packetlen)=0)
if(sx1278.setPacketConfig(0x08, 0x40)!=0) {
M10_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
Serial.print("M10: setting RX frequency to ");
Serial.println(frequency);
int res = sx1278.setFrequency(frequency);
// enable RX
sx1278.setPayloadLength(0); // infinite for now...
//sx1278.setPayloadLength(292);
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
#if M10_DEBUG
M10_DBG(Serial.println("Setting SX1278 config for M10 finished\n"); Serial.println());
#endif
return res;
}
#if 0
int M10::setFrequency(float frequency) {
Serial.print("M10: setting RX frequency to ");
Serial.println(frequency);
int res = sx1278.setFrequency(frequency);
// enable RX
sx1278.setPayloadLength(0); // infinite for now...
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
return res;
}
#endif
#if 0
uint32_t M10::bits2val(const uint8_t *bits, int len) {
uint32_t val = 0;
for (int j = 0; j < len; j++) {
val |= (bits[j] << (len-1-j));
}
return val;
}
#endif
M10::M10() {
}
#define M10_FRAMELEN 101
#define M10_CRCPOS 99
void M10::printRaw(uint8_t *data, int len)
{
char buf[3];
int i;
for(i=0; i<len; i++) {
snprintf(buf, 3, "%02X ", data[i]);
Serial.print(buf);
}
Serial.println();
}
static int update_checkM10(int c, uint8_t b) {
int c0, c1, t, t6, t7, s;
c1 = c & 0xFF;
// B
b = (b >> 1) | ((b & 1) << 7);
b ^= (b >> 2) & 0xFF;
// A1
t6 = ( c & 1) ^ ((c >> 2) & 1) ^ ((c >> 4) & 1);
t7 = ((c >> 1) & 1) ^ ((c >> 3) & 1) ^ ((c >> 5) & 1);
t = (c & 0x3F) | (t6 << 6) | (t7 << 7);
// A2
s = (c >> 7) & 0xFF;
s ^= (s >> 2) & 0xFF;
c0 = b ^ t ^ s;
return ((c1 << 8) | c0) & 0xFFFF;
}
static bool checkM10crc(uint8_t *msg) {
int i, cs, cs1;
cs = 0;
for (i = 0; i < M10_CRCPOS; i++) {
cs = update_checkM10(cs, msg[i]);
}
cs = cs & 0xFFFF;
cs1 = (msg[M10_CRCPOS] << 8) | msg[M10_CRCPOS+1];
return (cs1 == cs);
}
typedef uint32_t SET256[8];
static SET256 sondeudp_VARSET = {0x03BBBBF0UL,0x80600000UL,0x06A001A0UL,
0x0000001CUL,0x00000000UL,0x00000000UL,0x00000000UL,
0x00000000UL};
// VARSET=SET256{4..9,11..13,15..17,19..21,23..25,53..54,63,69,71,72,85,87,89,90,98..100};
static uint8_t fixcnt[M10_FRAMELEN];
static uint8_t fixbytes[M10_FRAMELEN];
static int32_t getint32(uint8_t *data) {
return (int32_t)( data[3]|(data[2]<<8)|(data[1]<<16)|(data[0]<<24) );
}
static int16_t getint16(uint8_t *data) {
return (int16_t)(data[1]|((uint16_t)data[0]<<8));
}
static char dez(uint8_t nr) {
nr = nr%10;
return '0'+nr;
}
static char hex(uint8_t nr) {
nr = nr&0x0f;
if(nr<10) return '0'+nr;
else return 'A'+nr-10;
}
const static float DEGMUL = 1.0/0xB60B60;
#define VMUL 0.005
#ifndef PI
#define PI (3.1415926535897932384626433832795)
#endif
#define RAD (PI/180)
// ret: 1=frame ok; 2=frame with errors; 0=ignored frame (m10dop-alternativ)
int M10::decodeframeM10(uint8_t *data) {
int repairstep = 16;
int repl = 0;
bool crcok;
// error correction, inspired by oe5dxl's sondeudp
do {
crcok = checkM10crc(data);
if(crcok) break;
repl = 0;
for(int i=0; i<M10_CRCPOS; i++) {
if( ((sondeudp_VARSET[i/32]&(1<<(i%32))) != 1) && (fixcnt[i]>=repairstep) ) {
repl++;
data[i] = fixbytes[i];
}
}
repairstep >>= 1;
} while(repairstep>0);
if(crcok) {
for(int i=0; i<M10_CRCPOS; i++) {
if(fixbytes[i]==data[i] &&fixcnt[i]<255) fixcnt[i]++;
else { fixcnt[i]=0; fixbytes[i]=data[i]; }
}
}
Serial.println(crcok?"CRC OK":"CRC NOT OK");
if(data[1]==0x9F && data[2]==0x20) {
Serial.println("Decoding...");
// Its a M10
// getid...
char ids[11];
ids[0] = 'M';
ids[1] = 'E';
ids[2] = hex(data[95]/16);
ids[3] = hex(data[95]);
ids[4] = hex(data[93]);
uint32_t id = data[96] + data[97]*256;
ids[5] = hex(id/4096);
ids[6] = hex(id/256);
ids[7] = hex(id/16);
ids[8] = hex(id);
ids[9] = 0;
strncpy(sonde.si()->id, ids, 10);
ids[0] = hex(data[95]/16);
ids[1] = dez((data[95]&0x0f)/10);
ids[2] = dez((data[95]&0x0f));
ids[3] = dez(data[93]);
ids[4] = dez(id>>13);
id &= 0x1fff;
ids[5] = dez(id/1000);
ids[6] = dez((id/100)%10);
ids[7] = dez((id/10)%10);
ids[8] = dez(id%10);
strncpy(sonde.si()->ser, ids, 10);
sonde.si()->validID = true;
Serial.printf("ID is %s [%02x %02x %d]\n", ids, data[95], data[93], id);
// ID printed on sonde is ...-.-abbbb, with a=id>>13, bbbb=id&0x1fff in decimal
// position data
sonde.si()->lat = getint32(data+14) * DEGMUL;
sonde.si()->lon = getint32(data+18) * DEGMUL;
sonde.si()->alt = getint32(data+22) * 0.001;
float ve = getint16(data+4)*VMUL;
float vn = getint16(data+6)*VMUL;
sonde.si()->vs = getint16(data+8) * VMUL;
sonde.si()->hs = sqrt(ve*ve+vn*vn);
float dir = atan2(vn, ve)*(1.0/RAD);
if(dir<0) dir+=360;
sonde.si()->dir = dir;
sonde.si()->validPos = 0x3f;
uint32_t gpstime = getint32(data+10);
uint16_t gpsweek = getint16(data+32);
// UTC is GPSTIME - 18s (24*60*60-18 = 86382)
// one week = 7*24*60*60 = 604800 seconds
// unix epoch starts jan 1st 1970 0:00
// gps time starts jan 6, 1980 0:00. thats 315964800 epoch seconds.
// subtracting 86400 yields 315878400UL
sonde.si()->time = (gpstime/1000) + 86382 + gpsweek*604800 + 315878400UL;
sonde.si()->validTime = true;
} else {
Serial.printf("data is %02x %02x %02x\n", data[0], data[1], data[2]);
return 0;
}
return crcok?1:2;
}
static uint32_t rxdata;
static bool rxsearching=true;
// search for
// //101001100110011010011010011001100110100110101010100110101001
// //1010011001100110100110100110 0110.0110 1001.1010 1010.1001 1010.1001 => 0x669AA9A9
void M10::processM10data(uint8_t dt)
{
for(int i=0; i<8; i++) {
uint8_t d = (dt&0x80)?1:0;
dt <<= 1;
rxdata = (rxdata<<1) | d;
//uint8_t value = ((rxdata>>1)^rxdata)&0x01;
//if((rxbitc&1)==1) { rxbyte = (rxbyte>>1) + ((value)<<8); } // mancester decoded data
//rxbyte = (rxbyte>>1) | (d<<8);
if( (rxbitc&1)==0 ) {
// "bit1"
rxbyte = (rxbyte<<1) | d;
} else {
// "bit2" ==> 01 or 10 => 1, otherweise => 0
rxbyte = rxbyte ^ d;
}
//
if(rxsearching) {
if( rxdata == 0xcccca64c || rxdata == 0x333359b3 ) {
rxsearching = false;
rxbitc = 0;
rxp = 0;
#if 1
int rssi=sx1278.getRSSI();
int fei=sx1278.getFEI();
int afc=sx1278.getAFC();
Serial.print("Test: RSSI="); Serial.print(rssi);
Serial.print(" FEI="); Serial.print(fei);
Serial.print(" AFC="); Serial.println(afc);
sonde.si()->rssi = rssi;
sonde.si()->afc = afc;
#endif
}
} else {
rxbitc = (rxbitc+1)%16; // 16;
if(rxbitc == 0) { // got 8 data bit
//Serial.printf("%03x ",rxbyte);
dataptr[rxp++] = rxbyte&0xff; // (rxbyte>>1)&0xff;
#if 0
if(rxp==7 && dataptr[6] != 0x65) {
Serial.printf("wrong start: %02x\n",dataptr[6]);
rxsearching = true;
}
#endif
if(rxp>=M10_FRAMELEN) {
rxsearching = true;
haveNewFrame = decodeframeM10(dataptr);
}
}
}
}
}
int M10::receive() {
unsigned long t0 = millis();
Serial.printf("M10::receive() start at %ld\n",t0);
while( millis() - t0 < 1000 ) {
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2);
if ( bitRead(value, 7) ) {
Serial.println("FIFO full");
}
if ( bitRead(value, 4) ) {
Serial.println("FIFO overflow");
}
if ( bitRead(value, 2) == 1 ) {
Serial.println("FIFO: ready()");
sx1278.clearIRQFlags();
}
if(bitRead(value, 6) == 0) { // while FIFO not empty
byte data = sx1278.readRegister(REG_FIFO);
//Serial.printf("%02x",data);
processM10data(data);
value = sx1278.readRegister(REG_IRQ_FLAGS2);
} else {
if(headerDetected) {
t0 = millis(); // restart timer... don't time out if header detected...
headerDetected = 0;
}
if(haveNewFrame) {
Serial.printf("M10::receive(): new frame complete after %ldms\n", millis()-t0);
printRaw(dataptr, M10_FRAMELEN);
int retval = haveNewFrame==1 ? RX_OK: RX_ERROR;
haveNewFrame = 0;
return retval;
}
delay(2);
}
}
Serial.printf("M10::receive() timed out\n");
return RX_TIMEOUT; // TODO RX_OK;
}
#define M10MAXLEN (240)
int M10::waitRXcomplete() {
// called after complete...
#if 0
Serial.printf("decoding frame %d\n", lastFrame);
print_frame(lastFrame==1?data1:data2, 240);
SondeInfo *si = sonde.sondeList+rxtask.receiveSonde;
si->lat = gpx.lat;
si->lon = gpx.lon;
si->alt = gpx.alt;
si->vs = gpx.vU;
si->hs = gpx.vH;
si->dir = gpx.vD;
si->validPos = 0x3f;
memcpy(si->id, gpx.id, 9);
si->validID = true;
int res=0;
uint32_t t0 = millis();
while( rxtask.receiveResult == 0xFFFF && millis()-t0 < 2000) { delay(20); }
if( rxtask.receiveResult<0 || rxtask.receiveResult==RX_TIMEOUT) {
res = RX_TIMEOUT;
} else if ( rxtask.receiveResult==0) {
res = RX_OK;
} else {
res = RX_ERROR;
}
rxtask.receiveResult = 0xFFFF;
Serial.printf("M10::waitRXcomplete returning %d (%s)\n", res, RXstr[res]);
return res;
#endif
return 0;
}
#if 0
int oldwaitRXcomplete() {
Serial.println("M10: receive frame...\n");
sx1278receiveData = true;
delay(6000); // done in other task....
//sx1278receiveData = false;
#if 0
//sx1278.setPayloadLength(518-8); // Expect 320-8 bytes or 518-8 bytes (8 byte header)
//sx1278.setPayloadLength(0); // infinite for now...
////// test code for continuous reception
// sx1278.receive(); /// active FSK RX mode -- already done above...
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2);
unsigned long previous = millis();
byte ready=0;
uint32_t wait = 8000;
// while not yet done or FIFO not yet empty
// bit 6: FIFO Empty
// bit 2 payload ready
int by=0;
while( (!ready || bitRead(value,6)==0) && (millis() - previous < wait) )
{
if( bitRead(value, 7) ) { Serial.println("FIFO full"); }
if( bitRead(value, 4) ) { Serial.println("FIFO overflow"); }
if( bitRead(value,2)==1 ) ready=1;
if( bitRead(value, 6) == 0 ) { // FIFO not empty
byte data = sx1278.readRegister(REG_FIFO);
process8N1data(data);
by++;
#if 0
if(di==1) {
int rssi=getRSSI();
int fei=getFEI();
int afc=getAFC();
Serial.print("Test: RSSI="); Serial.println(rssi);
Serial.print("Test: FEI="); Serial.println(fei);
Serial.print("Test: AFC="); Serial.println(afc);
sonde.si()->rssi = rssi;
sonde.si()->afc = afc;
}
if(di>520) {
// TODO
Serial.println("TOO MUCH DATA");
break;
}
previous = millis(); // reset timeout after receiving data
#endif
}
value = sx1278.readRegister(REG_IRQ_FLAGS2);
}
Serial.printf("processed %d bytes before end/timeout\n", by);
#endif
/////
#if 0
int e = sx1278.receivePacketTimeout(1000, data+8);
if(e) { Serial.println("TIMEOUT"); return RX_TIMEOUT; } //if timeout... return 1
printRaw(data, M10MAXLEN);
//for(int i=0; i<M10MAXLEN; i++) { data[i] = reverse(data[i]); }
//printRaw(data, MAXLEN);
//for(int i=0; i<M10MAXLEN; i++) { data[i] = data[i] ^ scramble[i&0x3F]; }
//printRaw(data, MAXLEN);
//int res = decode41(data, M10MAXLEN);
#endif
int res=0;
return res==0 ? RX_OK : RX_ERROR;
}
#endif
M10 m10 = M10();

Wyświetl plik

@ -0,0 +1,623 @@
/* M10 and M20 decoder functions */
#include "M10M20.h"
#include "SX1278FSK.h"
#include "rsc.h"
#include "Sonde.h"
#include <SPIFFS.h>
#define M10M20_DEBUG 1
#if M10M20_DEBUG
#define M10M20_DBG(x) x
#else
#define M10M20_DBG(x)
#endif
static byte data1[512];
static byte *dataptr=data1;
static uint8_t rxbitc;
static uint16_t rxbyte;
static int rxp=0;
static int haveNewFrame = 0;
//static int lastFrame = 0;
static int headerDetected = 0;
int M10M20::setup(float frequency)
{
M10M20_DBG(Serial.println("Setup sx1278 for M10/M20 sonde"));;
if(sx1278.ON()!=0) {
M10M20_DBG(Serial.println("Setting SX1278 power on FAILED"));
return 1;
}
// setFSK: switches to FSK standby mode
if(sx1278.setFSK()!=0) {
M10M20_DBG(Serial.println("Setting FSK mode FAILED"));
return 1;
}
Serial.print("M10/M20: setting RX frequency to ");
Serial.println(frequency);
int res = sx1278.setFrequency(frequency);
if(sx1278.setAFCBandwidth(sonde.config.m10m20.agcbw)!=0) {
M10M20_DBG(Serial.printf("Setting AFC bandwidth %d Hz FAILED", sonde.config.m10m20.agcbw));
return 1;
}
if(sx1278.setRxBandwidth(sonde.config.m10m20.rxbw)!=0) {
M10M20_DBG(Serial.printf("Setting RX bandwidth to %d Hz FAILED", sonde.config.m10m20.rxbw));
return 1;
}
/// TODO: Maybe do this conditionally? -- maybe skip if afc if agcbw set to 0 or -1?
//// Step 1: Tentative AFC mode
sx1278.clearIRQFlags();
// preamble detector + AFC + AGC on
// wait for preamble interrupt within 2sec
sx1278.setBitrate(4800);
// DetectorOn=1, Preamble detector size 01, preamble tol 0x0A (10)
sx1278.setPreambleDetect(0x80 | 0x20 | 0x0A);
// Manual start RX, Enable Auto-AFC, Auto-AGC, RX Trigger (AGC+AFC)by preamble
sx1278.setRxConf(0x20 | 0x10 | 0x08 | 0x06);
// Packet config 1: fixed len, no mancecer, no crc, no address filter
// Packet config 2: packet mode, no home ctrl, no beackn, msb(packetlen)=0)
if(sx1278.setPacketConfig(0x08, 0x40)!=0) {
M10M20_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
// enable RX
sx1278.setPayloadLength(0);
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
unsigned long t0 = millis();
M10M20_DBG(Serial.printf("M10M20::setup() AFC preamble search start at %ld\n",t0));
while( millis() - t0 < 1000 ) {
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS1);
if(value & 2) {
int32_t afc = sx1278.getAFC();
int16_t rssi = sx1278.getRSSI();
Serial.printf("M10M20::setup: preamble: AFC is %d, RSSI is %.1f\n", afc, rssi/2.0);
sonde.sondeList[rxtask.currentSonde].rssi = rssi;
sonde.sondeList[rxtask.currentSonde].afc = afc;
break;
}
yield();
}
if( millis() - t0 >= 1000) {
Serial.println("Preamble scan for AFC: TIMEOUT\n");
return 1; // no preamble, so we may fail fast....
}
//// Step 2: Real reception
// FSK standby mode, seems like otherweise baudrate cannot be changed?
sx1278.setFSK();
if(sx1278.setBitrate(9600)!=0) {
M10M20_DBG(Serial.println("Setting bitrate 9600bit/s FAILED"));
return 1;
}
M10M20_DBG(Serial.printf("Exact bitrate is %f\n", sx1278.getBitrate()));
// Probably not necessary, as this was set before
if(sx1278.setAFCBandwidth(sonde.config.m10m20.agcbw)!=0) {
M10M20_DBG(Serial.printf("Setting AFC bandwidth %d Hz FAILED", sonde.config.m10m20.agcbw));
return 1;
}
if(sx1278.setRxBandwidth(sonde.config.m10m20.rxbw)!=0) {
M10M20_DBG(Serial.printf("Setting RX bandwidth to %d Hz FAILED", sonde.config.m10m20.rxbw));
return 1;
}
///// Enable auto-AFC, auto-AGC, RX Trigger by preamble
///if(sx1278.setRxConf(0x1E)!=0) {
// Disable auto-AFC, auto-AGC, RX Trigger by preamble
if(sx1278.setRxConf(0x00)!=0) {
M10M20_DBG(Serial.println("Setting RX Config FAILED"));
return 1;
}
// version 1, working with continuous RX
const char *SYNC="\x66\x66";
if(sx1278.setSyncConf(0x70, 1, (const uint8_t *)SYNC)!=0) {
M10M20_DBG(Serial.println("Setting SYNC Config FAILED"));
return 1;
}
// Preamble detection off (+ size 1 byte, maximum tolerance; should not matter for "off"?)
if(sx1278.setPreambleDetect(0x00 | 0x00 | 0x1F)!=0) {
M10M20_DBG(Serial.println("Setting PreambleDetect FAILED"));
return 1;
}
// Packet config 1: fixed len, no mancecer, no crc, no address filter
// Packet config 2: packet mode, no home ctrl, no beackn, msb(packetlen)=0)
if(sx1278.setPacketConfig(0x08, 0x40)!=0) {
M10M20_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
// enable RX
sx1278.setPayloadLength(0); // infinite for now...
//sx1278.setPayloadLength(292);
sx1278.setRxConf(0x20);
uint16_t afc = sx1278.getRawAFC();
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
delay(50);
sx1278.setRawAFC(afc);
delay(50);
Serial.printf("after RX_MODE: AFC is %d\n", sx1278.getAFC());
#if M10M20_DEBUG
M10M20_DBG(Serial.println("Setting SX1278 config for M10 finished\n"); Serial.println());
#endif
return res;
}
M10M20::M10M20() {
}
#define M10_FRAMELEN 101
#define M10_CRCPOS 99
#define M20_FRAMELEN 88
#define M20_CRCPOSB 22
void M10M20::printRaw(uint8_t *data, int len)
{
char buf[3];
int i;
for(i=0; i<len; i++) {
snprintf(buf, 3, "%02X ", data[i]);
Serial.print(buf);
}
Serial.println();
}
static uint16_t update_checkM10M20(int c, uint8_t b) {
int c0, c1, t, t6, t7, s;
c1 = c & 0xFF;
// B
b = (b >> 1) | ((b & 1) << 7);
b ^= (b >> 2) & 0xFF;
// A1
t6 = ( c & 1) ^ ((c >> 2) & 1) ^ ((c >> 4) & 1);
t7 = ((c >> 1) & 1) ^ ((c >> 3) & 1) ^ ((c >> 5) & 1);
t = (c & 0x3F) | (t6 << 6) | (t7 << 7);
// A2
s = (c >> 7) & 0xFF;
s ^= (s >> 2) & 0xFF;
c0 = b ^ t ^ s;
return ((c1 << 8) | c0) & 0xFFFF;
}
static uint16_t crc_M10M20(int len, uint8_t *msg) {
uint16_t cs = 0;
for (int i = 0; i < len; i++) {
cs = update_checkM10M20(cs, msg[i]);
}
return cs;
}
static bool checkM10M20crc(int crcpos, uint8_t *msg) {
uint16_t cs, cs1;
cs = crc_M10M20(crcpos, msg);
cs1 = (msg[crcpos] << 8) | msg[crcpos+1];
return (cs1 == cs);
}
typedef uint32_t SET256[8];
static SET256 sondeudp_VARSET = {0x03BBBBF0UL,0x80600000UL,0x06A001A0UL,
0x0000001CUL,0x00000000UL,0x00000000UL,0x00000000UL,
0x00000000UL};
// VARSET=SET256{4..9,11..13,15..17,19..21,23..25,53..54,63,69,71,72,85,87,89,90,98..100};
static SET256 sondeudp_VARSETM20 = {0xF3E27F54UL,0x0000000FUL,0x00000030UL,
0x00000000UL, 0x00444C39UL, 0x53445A00UL, 0x00000000UL,
0x00000000UL};
// VARSET=SET256{2,4,6,8..10,11..14,17,21..25,28..35,68,69}; (* known as variable *)
static uint8_t fixcnt[M10_FRAMELEN];
static uint8_t fixbytes[M10_FRAMELEN];
static int32_t getint32(uint8_t *data) {
return (int32_t)( data[3]|(data[2]<<8)|(data[1]<<16)|(data[0]<<24) );
}
static int32_t getint24(uint8_t *data) {
return (int32_t)(data[2]|(data[1]<<8)|(data[0]<<16) );
}
static int16_t getint16(uint8_t *data) {
return (int16_t)(data[1]|((uint16_t)data[0]<<8));
}
static int16_t getint16_r(uint8_t *data) {
return (int16_t)(((uint16_t)data[1]<<8) |data[0]);
}
static char dez(uint8_t nr) {
nr = nr%10;
return '0'+nr;
}
static char hex(uint8_t nr) {
nr = nr&0x0f;
if(nr<10) return '0'+nr;
else return 'A'+nr-10;
}
const static float DEGMUL = 1.0/0xB60B60;
#define VMUL 0.005
#define VMUL_M20 0.01
#ifndef PI
#define PI (3.1415926535897932384626433832795)
#endif
#define RAD (PI/180)
// ret: 1=frame ok; 2=frame with errors; 0=ignored frame (m10dop-alternativ)
int M10M20::decodeframeM10(uint8_t *data) {
int repairstep = 16;
int repl = 0;
bool crcok;
// error correction, inspired by oe5dxl's sondeudp
do {
crcok = checkM10M20crc(M10_CRCPOS, data);
if(crcok || repairstep==0) break;
repl = 0;
for(int i=0; i<M10_CRCPOS; i++) {
if( ((sondeudp_VARSET[i/32]&(1<<(i%32))) == 0) && (fixcnt[i]>=repairstep) ) {
repl++;
data[i] = fixbytes[i];
}
}
repairstep >>= 1;
} while(true);
if(crcok) {
for(int i=0; i<M10_CRCPOS; i++) {
if(fixbytes[i]==data[i] &&fixcnt[i]<255) fixcnt[i]++;
else { fixcnt[i]=0; fixbytes[i]=data[i]; }
}
}
Serial.println(crcok?"CRC OK":"CRC NOT OK");
Serial.printf(" repair: %d/%d\n", repl, repairstep);
if(data[1]==0x9F && data[2]==0x20) {
Serial.println("Decoding...");
// Its a M10
// getid...
char ids[11];
ids[0] = 'M';
ids[1] = 'E';
ids[2] = hex(data[95]/16);
ids[3] = hex(data[95]);
ids[4] = hex(data[93]);
uint32_t id = data[96] + data[97]*256;
ids[5] = hex(id/4096);
ids[6] = hex(id/256);
ids[7] = hex(id/16);
ids[8] = hex(id);
ids[9] = 0;
strncpy(sonde.si()->id, ids, 10);
ids[0] = hex(data[95]/16);
ids[1] = dez((data[95]&0x0f)/10);
ids[2] = dez((data[95]&0x0f));
ids[3] = dez(data[93]);
ids[4] = dez(id>>13);
id &= 0x1fff;
ids[5] = dez(id/1000);
ids[6] = dez((id/100)%10);
ids[7] = dez((id/10)%10);
ids[8] = dez(id%10);
strncpy(sonde.si()->ser, ids, 10);
sonde.si()->validID = true;
Serial.printf("ID is %s [%02x %02x %d]\n", ids, data[95], data[93], id);
// ID printed on sonde is ...-.-abbbb, with a=id>>13, bbbb=id&0x1fff in decimal
// position data
sonde.si()->lat = getint32(data+14) * DEGMUL;
sonde.si()->lon = getint32(data+18) * DEGMUL;
sonde.si()->alt = getint32(data+22) * 0.001;
float ve = getint16(data+4)*VMUL;
float vn = getint16(data+6)*VMUL;
sonde.si()->vs = getint16(data+8) * VMUL;
sonde.si()->hs = sqrt(ve*ve+vn*vn);
float dir = atan2(vn, ve)*(1.0/RAD);
if(dir<0) dir+=360;
sonde.si()->dir = dir;
sonde.si()->validPos = 0x3f;
uint32_t gpstime = getint32(data+10);
uint16_t gpsweek = getint16(data+32);
// UTC is GPSTIME - 18s (24*60*60-18 = 86382)
// one week = 7*24*60*60 = 604800 seconds
// unix epoch starts jan 1st 1970 0:00
// gps time starts jan 6, 1980 0:00. thats 315964800 epoch seconds.
// subtracting 86400 yields 315878400UL
sonde.si()->time = (gpstime/1000) + 86382 + gpsweek*604800 + 315878400UL;
sonde.si()->validTime = true;
} else {
Serial.printf("data is %02x %02x %02x\n", data[0], data[1], data[2]);
return 0;
}
return crcok?1:2;
}
static uint32_t rxdata;
static bool rxsearching=true;
static bool isM20=false;
// search for
// //101001100110011010011010011001100110100110101010100110101001
// //1010011001100110100110100110 0110.0110 1001.1010 1010.1001 1010.1001 => 0x669AA9A9
void M10M20::processM10data(uint8_t dt)
{
for(int i=0; i<8; i++) {
uint8_t d = (dt&0x80)?1:0;
dt <<= 1;
rxdata = (rxdata<<1) | d;
if( (rxbitc&1)==0 ) {
// "bit1"
rxbyte = (rxbyte<<1) | d;
} else {
// "bit2" ==> 01 or 10 => 1, otherweise => 0
rxbyte = rxbyte ^ d;
}
//
if(rxsearching) {
if( rxdata == 0xcccca64c || rxdata == 0x333359b3 ) {
rxsearching = false;
rxbitc = 0;
rxp = 0;
isM20 = false;
headerDetected = 1;
#if 1
int rssi=sx1278.getRSSI();
int fei=sx1278.getFEI();
int afc=sx1278.getAFC();
Serial.print("Test: RSSI="); Serial.print(rssi);
Serial.print(" FEI="); Serial.print(fei);
Serial.print(" AFC="); Serial.println(afc);
sonde.si()->rssi = rssi;
sonde.si()->afc = afc;
#endif
}
} else {
rxbitc = (rxbitc+1)%16; // 16;
if(rxbitc == 0) { // got 8 data bit
//Serial.printf("%03x ",rxbyte);
dataptr[rxp++] = rxbyte&0xff; // (rxbyte>>1)&0xff;
// detect type of sonde:
// 64 9F 20 => M10
// 64 49 0x => M10 (?) -- not used here
// 45 20 7x => M20
if(rxp==2 && dataptr[0]==0x45 && dataptr[1]==0x20) { isM20 = true; }
if(isM20) {
memcpy(sonde.si()->typestr, "M20 ", 5);
if(rxp>=M20_FRAMELEN) {
rxsearching = true;
haveNewFrame = decodeframeM20(dataptr);
}
} else {
memcpy(sonde.si()->typestr, "M10 ", 5);
if(rxp>=M10_FRAMELEN) {
rxsearching = true;
haveNewFrame = decodeframeM10(dataptr);
}
}
}
}
}
}
int M10M20::receive() {
unsigned long t0 = millis();
Serial.printf("M10M20::receive() start at %ld\n",t0);
while( millis() - t0 < 1100 ) {
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2);
if ( bitRead(value, 7) ) {
Serial.println("FIFO full");
}
if ( bitRead(value, 4) ) {
Serial.println("FIFO overflow");
}
if ( bitRead(value, 2) == 1 ) {
Serial.println("FIFO: ready()");
sx1278.clearIRQFlags();
}
if(bitRead(value, 6) == 0) { // while FIFO not empty
byte data = sx1278.readRegister(REG_FIFO);
//Serial.printf("%02x:",data);
processM10data(data);
value = sx1278.readRegister(REG_IRQ_FLAGS2);
} else {
if(headerDetected) {
t0 = millis(); // restart timer... don't time out if header detected...
headerDetected = 0;
}
if(haveNewFrame) {
Serial.printf("M10M20::receive(): new frame complete after %ldms\n", millis()-t0);
printRaw(dataptr, M10_FRAMELEN);
int retval = haveNewFrame==1 ? RX_OK: RX_ERROR;
haveNewFrame = 0;
return retval;
}
delay(2);
}
}
int32_t afc = sx1278.getAFC();
int16_t rssi = sx1278.getRSSI();
Serial.printf("receive: AFC is %d, RSSI is %.1f\n", afc, rssi/2.0);
Serial.printf("M10M20::receive() timed out\n");
return RX_TIMEOUT; // TODO RX_OK;
}
#define M10MAXLEN (240)
int M10M20::waitRXcomplete() {
return 0;
}
#if 0
static bool checkM20crc(uint8_t *msg, int crcpos) {
int i, cs, cs1;
cs = 0;
for (i = 0; i < crcpos; i++) {
cs = update_checkM10(cs, msg[i]); // same for M10 and M20
}
cs = cs & 0xFFFF;
cs1 = (msg[crcpos] << 8) | msg[crcpos+1];
return (cs1 == cs);
}
#endif
// ret: 1=frame ok; 2=frame with errors; 0=ignored frame (m20dop-alternativ)
int M10M20::decodeframeM20(uint8_t *data) {
int repairstep = 16;
int frl;
int repl = 0;
bool crcok = false;
bool crcbok = false;
// error correction, inspired by oe5dxl's sondeudp
// check first block
uint8_t s[200];
s[0] = 0x16;
for(int i=1; i<=M20_CRCPOSB-1; i++) { s[i] = data[i+1]; }
crcbok = (crc_M10M20(M20_CRCPOSB-1, s) ==
((data[M20_CRCPOSB] << 8) | data[M20_CRCPOSB+1]));
frl = data[0] + 1; // frame len? (0x45+1 => 70)
if(frl>M20_FRAMELEN) { frl = M20_FRAMELEN; }
do {
crcok = checkM10M20crc(frl-2, data);
if(crcok || repairstep == 0) break;
repl = 0;
for(int i=crcbok?M20_CRCPOSB+2:0; i<frl-2; i++) {
if( ((sondeudp_VARSETM20[i/32]&(1<<(i%32))) == 0) && (fixcnt[i]>=repairstep) ) {
repl++;
data[i] = fixbytes[i];
}
}
repairstep >>= 1;
} while(true);
if(crcbok) {
int oklen = crcok ? frl-2 : 21;
for(int i=0; i<oklen; i++) {
if(fixbytes[i]==data[i]) { if(fixcnt[i]<255) fixcnt[i]++; }
else { fixcnt[i]=0; fixbytes[i]=data[i]; }
}
}
Serial.println(crcok?"CRC OK":"CRC NOT OK");
Serial.printf(" repair: %d/%d\n", repl, repairstep);
Serial.println("Decoding...");
// Its a M20
// getid...
// TODO: Adjust ID calculation and serial number reconstruction
char ids[11]={'M','E','0','0','0','0','0','0','0','0','0'};
ids[0] = 'M';
ids[1] = 'E';
uint32_t id = getint16(data+18);
ids[2] = hex(id/16);
ids[3] = hex(id);
//
id = getint16_r(data+19)/4;
ids[4] = (char)((id/10000)%10+48);
ids[5] = (char)((id/1000)%10+48);
ids[6] = (char)((id/100)%10+48);
ids[7] = (char)((id/10)%10+48);
ids[8] = (char)(id%10+48);
// TODO
strncpy(sonde.si()->ser, ids, 10);
if(crcok) {
sonde.si()->validID = true;
//Serial.printf("ID is %s [%02x %02x %d]\n", ids, data[95], data[93], id);
// ID printed on sonde is ...-.-abbbb, with a=id>>13, bbbb=id&0x1fff in decimal
// position data
// 0x1C 4 byte
sonde.si()->lat = getint32(data+28) * 1e-6;
//0x20 4 byte
sonde.si()->lon = getint32(data+32) * 1e-6;
//0x08 3 byte
sonde.si()->alt = getint24(data+8) * VMUL_M20;
//0x0B 2 byte
//VMUL_M20 specific
float ve = getint16(data+11)*VMUL_M20;
//0x0D 2 byte
float vn = getint16(data+13)*VMUL_M20;
//0x18 2 byte
sonde.si()->vs = getint16(data+24) * VMUL_M20;
sonde.si()->hs = sqrt(ve*ve+vn*vn);
float dir = atan2(vn, ve)*(1.0/RAD);
if(dir<0) dir+=360;
sonde.si()->dir = dir;
sonde.si()->validPos = 0x3f;
//0x0F 3 byte
uint32_t tow = getint24(data+15);
uint16_t week = getint16(data+26);
sonde.si()->time = (tow+week*604800+315964800)-18;
sonde.si()->validTime = true;
}
return crcok?1:2;
}
#if 0
//// same as for M10
// search for
// //101001100110011010011010011001100110100110101010100110101001
// //1010011001100110100110100110 0110.0110 1001.1010 1010.1001 1010.1001 => 0x669AA9A9
void M10M20::processM20data(uint8_t dt)
{
for(int i=0; i<8; i++) {
uint8_t d = (dt&0x80)?1:0;
dt <<= 1;
rxdata = (rxdata<<1) | d;
//uint8_t value = ((rxdata>>1)^rxdata)&0x01;
//if((rxbitc&1)==1) { rxbyte = (rxbyte>>1) + ((value)<<8); } // mancester decoded data
//rxbyte = (rxbyte>>1) | (d<<8);
if( (rxbitc&1)==0 ) {
// "bit1"
rxbyte = (rxbyte<<1) | d;
} else {
// "bit2" ==> 01 or 10 => 1, otherweise => 0
rxbyte = rxbyte ^ d;
}
//
if(rxsearching) {
if( rxdata == 0xcccca64c || rxdata == 0x333359b3 ) {
rxsearching = false;
rxbitc = 0;
rxp = 0;
#if 1
int rssi=sx1278.getRSSI();
int fei=sx1278.getFEI();
int afc=sx1278.getAFC();
Serial.print("Test: RSSI="); Serial.print(rssi);
Serial.print(" FEI="); Serial.print(fei);
Serial.print(" AFC="); Serial.println(afc);
sonde.si()->rssi = rssi;
sonde.si()->afc = afc;
#endif
}
} else {
rxbitc = (rxbitc+1)%16; // 16;
if(rxbitc == 0) { // got 8 data bit
//Serial.printf("%03x ",rxbyte);
dataptr[rxp++] = rxbyte&0xff; // (rxbyte>>1)&0xff;
#if 0
if(rxp==7 && dataptr[6] != 0x65) {
Serial.printf("wrong start: %02x\n",dataptr[6]);
rxsearching = true;
}
#endif
if(rxp>=M20_FRAMELEN) {
rxsearching = true;
haveNewFrame = decodeframeM20(dataptr);
}
}
}
}
}
#endif
M10M20 m10m20 = M10M20();

Wyświetl plik

@ -1,13 +1,13 @@
/*
* M10.h
* Functions for decoding Meteomodem M10 sondes with SX127x chips
* M10M20.h
* Functions for decoding Meteomodem M10M20 sondes with SX127x chips
* Copyright (C) 2019 Hansi Reiser, dl9rdz
*
* SPDX-License-Identifier: GPL-2.0+
*/
#ifndef M10_h
#define M10_h
#ifndef M10M20_h
#define M10M20_h
#include <stdlib.h>
#include <stdint.h>
@ -16,45 +16,14 @@
#include <inttypes.h>
#endif
#if 0
struct CONTEXTR9 {
char calibdata[512];
uint32_t calibok;
char mesok;
char posok;
char framesent;
double lat;
double lon;
double heig;
double speed;
double dir;
double climb;
double lastlat;
double laslong;
double lastalt;
double lastspeed;
double lastdir;
double lastclb;
float hrmsc;
float vrmsc;
double hp;
double hyg;
double temp;
double ozontemp;
double ozon;
uint32_t goodsats;
uint32_t timems;
uint32_t framenum;
};
#endif
/* Main class */
class M10
class M10M20
{
private:
void printRaw(uint8_t *data, int len);
void processM10data(uint8_t data);
int decodeframeM10(uint8_t *data);
int decodeframeM20(uint8_t *data);
#if 0
void stobyte92(uint8_t byte);
void dogps(const uint8_t *sf, int sf_len,
@ -83,7 +52,7 @@ private:
#endif
public:
M10();
M10M20();
int setup(float frequency);
int receive();
int waitRXcomplete();
@ -91,6 +60,6 @@ public:
//int use_ecc = 1;
};
extern M10 m10;
extern M10M20 m10m20;
#endif

Wyświetl plik

@ -356,7 +356,7 @@ static void posrs41(const byte b[], uint32_t b_len, uint32_t p)
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;
sonde.si()->hs = sqrt((float)(vn*vn+ve*ve));
Serial.print(sonde.si()->hs);
Serial.print("km/h ");
Serial.print(dir);

Wyświetl plik

@ -164,20 +164,23 @@ void SX1278FSK::writeRegister(byte address, byte data)
*/
void SX1278FSK::clearIRQFlags()
{
#if 0
byte st0;
// Save the previous status
st0 = readRegister(REG_OP_MODE);
// Stdby mode to write in registers
writeRegister(REG_OP_MODE, FSK_STANDBY_MODE);
#endif
// FSK mode flags1 register
writeRegister(REG_IRQ_FLAGS1, 0xFF);
// FSK mode flags2 register
writeRegister(REG_IRQ_FLAGS2, 0xFF);
#if 0
// Getting back to previous status
if(st0 != FSK_STANDBY_MODE) {
writeRegister(REG_OP_MODE, st0);
}
#endif
#if (SX1278FSK_debug_mode > 1)
Serial.println(F("## FSK flags cleared ##"));
#endif
@ -194,7 +197,7 @@ uint8_t SX1278FSK::setFSK()
{
uint8_t state = 2;
byte st0;
byte config1;
//byte config1;
#if (SX1278FSK_debug_mode > 1)
Serial.println();
@ -563,6 +566,13 @@ int32_t SX1278FSK::getAFC()
AFC = (int32_t)(regval * SX127X_FSTEP);
return AFC;
}
uint16_t SX1278FSK::getRawAFC() {
return (readRegister(REG_AFC_MSB)<<8) | readRegister(REG_AFC_LSB);
}
void SX1278FSK::setRawAFC(uint16_t afc) {
writeRegister(REG_AFC_MSB, afc>>8);
writeRegister(REG_AFC_LSB, afc&0xFF);
}
/*
Function: Gets the current supply limit of the power amplifier, protecting battery chemistries.
@ -719,7 +729,6 @@ uint8_t SX1278FSK::receivePacketTimeout(uint32_t wait, byte *data)
// It's a bit of a hack.... get RSSI and AFC (a) at beginning of packet and
// for RS41 after about 0.5 sec. It might be more logical to put this decoder-specific
// code into RS41.cpp instead of this file... (maybe TODO?)
if(di==1 || di==290 ) {
int rssi=getRSSI();
int afc=getAFC();

Wyświetl plik

@ -240,6 +240,8 @@ public:
// Get current AFC value
int32_t getAFC();
uint16_t getRawAFC();
void setRawAFC(uint16_t afc);
// Get the maximum current supply by the module.
int getMaxCurrent();

Wyświetl plik

@ -18,10 +18,12 @@ struct scancfg {
int SMPL_PIX; // Frequency steps per pixel
int NCHAN; // number of channels to scan, PLOT_W * SMPL_PIX
int SMOOTH;
int ADDWAIT;
};
struct scancfg scanLCD={ 121, 7, 120/6, 120/6/4, 6000.0/120.0/10.0, 10, 120*10, 2 };
struct scancfg scanTFT={ 210, 16, 210/6, 210/6/5, 6000.0/210.0/10.0, 10, 210*10, 1 };
//struct scancfg scanLCD={ 121, 7, 120/6, 120/6/4, 6000.0/120.0/20.0, 20, 120*20, 1 };
struct scancfg scanLCD={ 121, 7, 120/6, 120/6/4, 6000.0/120.0/10.0, 10, 120*10, 2, 40 };
struct scancfg scanTFT={ 210, 16, 210/6, 210/6/5, 6000.0/210.0/10.0, 10, 210*10, 1, 0 };
struct scancfg &scanconfig = scanTFT;
@ -30,7 +32,8 @@ struct scancfg &scanconfig = scanTFT;
//#define STARTF 401000000
// max of 120*5 and 210*3
#define MAXN 210*10
//#define MAXN 210*10
#define MAXN 120*20
// max of 120 and 210 (ceil(210/8)*8))
#define MAXDISP 216
@ -60,11 +63,14 @@ void Scanner::fillTiles(uint8_t *row, int value) {
* Currently we use 210 * (6000/120)kHz channels, i.e. 28.5714kHz
*/
///// unused???? uint8_t tiles[16] = { 0x0f,0x0f,0x0f,0x0f,0xf0,0xf0,0xf0,0xf0, 1, 3, 7, 15, 31, 63, 127, 255};
// type 0: lcd, 1: tft, 2: lcd(sh1106)
#define ISTFT (sonde.config.disptype==1)
void Scanner::plotResult()
{
int yofs = 0;
char buf[30];
if(sonde.config.disptype != 0) {
if(ISTFT) {
yofs = 2;
if (sonde.config.marker != 0) {
itoa((sonde.config.startfreq), buf, 10);
@ -92,14 +98,14 @@ void Scanner::plotResult()
if( ((i+j)%scanconfig.TICK2)==0) { row[j] |= 0x01; }
}
for(int y=0; y<scanconfig.PLOT_H8; y++) {
if(sonde.config.marker && y==1 && sonde.config.disptype==0 ) {
if(sonde.config.marker && y==1 && !ISTFT ) {
// don't overwrite MHz marker text
if(i<3*8 || (i>=7*8&&i<10*8) || i>=13*8) continue;
}
disp.rdis->drawTile(i/8, y+yofs, 1, row+8*y);
}
}
if(sonde.config.disptype != 0) { // large TFT
if(ISTFT) { // large TFT
sprintf(buf, "Peak: %03.3f MHz", peakf*0.000001);
disp.rdis->drawString(0, (yofs+scanconfig.PLOT_H8+1)*8, buf);
} else {
@ -110,7 +116,7 @@ void Scanner::plotResult()
void Scanner::scan()
{
if(sonde.config.disptype==0) { // LCD small
if(!ISTFT) { // LCD small
scanconfig = scanLCD;
} else {
scanconfig = scanTFT;
@ -128,10 +134,11 @@ void Scanner::scan()
unsigned long start = millis();
uint32_t lastfrf= STARTF * (1<<19) / SX127X_CRYSTAL_FREQ;
float freq;
int wait = 20 + 1000*(1<<(scanconfig.SMOOTH+1))/4/(0.001*CHANBW);
for(int iter=0; iter<3; iter++) { // two interations, to catch all RS41 transmissions
delayMicroseconds(20000);
float freq = STARTF;
int wait = scanconfig.ADDWAIT + 20 + 1000*(1<<(scanconfig.SMOOTH+1))/4/(0.001*CHANBW);
Serial.print("wait time (us) is: "); Serial.println(wait);
for(int iter=0; iter<3; iter++) { // three interations, to catch all RS41 transmissions
delayMicroseconds(20000); yield();
for(int i=0; i<scanconfig.PLOT_W*scanconfig.SMPL_PIX; i++) {
freq = STARTF + 1000.0*i*scanconfig.CHANSTEP;
//freq = 404000000 + 100*i*scanconfig.CHANSTEP;
@ -152,6 +159,7 @@ void Scanner::scan()
}
}
}
yield();
unsigned long duration = millis()-start;
Serial.print("wait: ");
Serial.println(wait);
@ -162,9 +170,11 @@ void Scanner::scan()
int peakidx=-1;
int peakres=-9999;
for(int i=0; i<scanconfig.PLOT_W; i+=1) {
scandisp[i]=scanresult[i*scanconfig.SMPL_PIX];
int r=scanresult[i*scanconfig.SMPL_PIX];
if(r>peakres+1) { peakres=r; peakidx=i*scanconfig.SMPL_PIX; }
scandisp[i] = r;
for(int j=1; j<scanconfig.SMPL_PIX; j++) {
int r = scanresult[i*scanconfig.SMPL_PIX+j];
r = scanresult[i*scanconfig.SMPL_PIX+j];
scandisp[i]+=r;
if(r>peakres+1) { peakres=r; peakidx=i*scanconfig.SMPL_PIX+j; }
}

Wyświetl plik

@ -5,12 +5,12 @@
#include "RS41.h"
#include "RS92.h"
#include "DFM.h"
#include "M10.h"
#include "M10M20.h"
#include "SX1278FSK.h"
#include "Display.h"
#include <Wire.h>
extern SX1278FSK sx1278;
uint8_t debug = 255-8-16;
RXTask rxtask = { -1, -1, -1, 0xFFFF, 0 };
@ -19,19 +19,25 @@ const char *evstring[]={"NONE", "KEY1S", "KEY1D", "KEY1M", "KEY1L", "KEY2S", "KE
const char *RXstr[]={"RX_OK", "RX_TIMEOUT", "RX_ERROR", "RX_UNKNOWN"};
int fingerprintValue[]={ 17, 31, 64, 4, 55, 48, 23, 128+23, -1 };
int fingerprintValue[]={ 17, 31, 64, 4, 55, 48, 23, 128+23, 119, 128+119, -1 };
const char *fingerprintText[]={
"TTGO T-Beam (new version 1.0), I2C not working after powerup, assuming 0.9\" OLED@21,22",
"TTGO LORA32 v2.1_1.6 (0.9\" OLED@21,22)",
"TTGO LORA v1.0 (0.9\" OLED@4,15)",
"Heltec v1/v2 (0.9\"OLED@4,15)",
"TTGO T-Beam (old version), 0.9\" OLED@21,22",
"TTGO T-Beam (old version), SPI TFT@4,21,22",
"TTGO T-Beam (new version 1.0), 0.9\" OLED@21,22",
"TTGO T-Beam (new version 1.0), SPI TFT@4,13,14",
"TTGO T-Beam (V0.7), 0.9\" OLED@21,22",
"TTGO T-Beam (V0.7), SPI TFT@4,21,22",
"TTGO T-Beam (V1.0), 0.9\" OLED@21,22",
"TTGO T-Beam (V1.0), SPI TFT@4,13,14",
"TTGO T-Beam (V1.1), 0.9\" OLED@21,22",
"TTGO T-Beam (V1.1), SPI TFT@4,13,14",
};
int getKeyPressEvent(); /* in RX_FSK.ino */
/* global variables from RX_FSK.ino */
int getKeyPressEvent();
int handlePMUirq();
extern bool pmu_irq;
extern SX1278FSK sx1278;
/* Task model:
* There is a background task for all SX1278 interaction.
@ -41,7 +47,7 @@ int getKeyPressEvent(); /* in RX_FSK.ino */
* - Periodically it calls Sonde::receive(), which calls the current decoder's receive()
* function. It should return control to the SX1278 main loop at least once per second.
* It will also set the internal variable receiveResult. The decoder's receive function
* must make sure that there are no FIFI overflows in the SX1278.
* must make sure that there are no FIFO overflows in the SX1278.
* - the Arduino main loop will call the waitRXcomplete function, which should return as
* soon as there is some new data to display, or no later than after 1s, returning the
* value of receiveResult (or timeout, if receiveResult was not set within 1s). It
@ -80,6 +86,7 @@ void Sonde::defaultConfig() {
config.tft_orient = 1;
config.button2_axp = 0;
config.norx_timeout = 20;
config.screenfile = 1;
if(initlevels[16]==0) {
config.oled_sda = 4;
config.oled_scl = 15;
@ -92,8 +99,15 @@ void Sonde::defaultConfig() {
config.oled_sda = 21;
config.oled_scl = 22;
if(initlevels[17]==0) { // T-Beam
if(initlevels[12]==0) { // T-Beam v1.0
int tbeam=7;
if(initlevels[12]==0) {
tbeam = 10;
Serial.println("Autoconfig: looks like T-Beam 1.0 board");
} else if ( initlevels[4]==1 && initlevels[12]==1 ) {
tbeam = 11;
Serial.println("Autoconfig: looks like T-Beam 1.1 board");
}
if(tbeam == 10 || tbeam == 11) { // T-Beam v1.0 or T-Beam v1.1
config.button_pin = 38;
config.button2_pin = 15 + 128; //T4 + 128; // T4 = GPIO13
// Maybe in future use as default only PWR as button2?
@ -120,6 +134,7 @@ void Sonde::defaultConfig() {
config.tft_rs = 2;
config.tft_cs = 0;
config.spectrum = -1; // no spectrum for now on large display
config.screenfile = 2;
} else {
// OLED display, pins 21,22 ok...
config.disptype = 0;
@ -140,6 +155,7 @@ void Sonde::defaultConfig() {
config.tft_rs = 2;
config.tft_cs = 0;
config.spectrum = -1; // no spectrum for now on large display
config.screenfile = 2;
}
}
} else {
@ -171,6 +187,8 @@ void Sonde::defaultConfig() {
config.rs92.alt2d=480;
config.dfm.agcbw=20800;
config.dfm.rxbw=10400;
config.m10m20.agcbw=20800;
config.m10m20.rxbw=12500;
config.udpfeed.active = 1;
config.udpfeed.type = 0;
strcpy(config.udpfeed.host, "192.168.42.20");
@ -186,6 +204,14 @@ void Sonde::defaultConfig() {
config.tcpfeed.highrate = 10;
config.tcpfeed.idformat = ID_DFMDXL;
config.kisstnc.active = 0;
strcpy(config.ephftp,"igs.bkg.bund.de/IGS/BRDC/");
config.mqtt.active = 0;
strcpy(config.mqtt.id, "rdz_sonde_server");
config.mqtt.port = 1883;
strcpy(config.mqtt.username, "/0");
strcpy(config.mqtt.password, "/0");
strcpy(config.mqtt.prefix, "rdz_sonde_server/");
}
void Sonde::setConfig(const char *cfg) {
@ -246,6 +272,8 @@ void Sonde::setConfig(const char *cfg) {
config.wifiap = atoi(val);
} else if(strcmp(cfg,"mdnsname")==0) {
strncpy(config.mdnsname, val, 14);
} else if(strcmp(cfg,"screenfile")==0) {
config.screenfile = atoi(val);
} else if(strcmp(cfg,"display")==0) {
int i = 0;
char *ptr;
@ -275,12 +303,18 @@ void Sonde::setConfig(const char *cfg) {
config.rs41.agcbw = atoi(val);
} else if(strcmp(cfg,"rs41.rxbw")==0) {
config.rs41.rxbw = atoi(val);
} else if(strcmp(cfg,"m10m20.agcbw")==0) {
config.m10m20.agcbw = atoi(val);
} else if(strcmp(cfg,"m10m20.rxbw")==0) {
config.m10m20.rxbw = atoi(val);
} else if(strcmp(cfg,"dfm.agcbw")==0) {
config.dfm.agcbw = atoi(val);
} else if(strcmp(cfg,"dfm.rxbw")==0) {
config.dfm.rxbw = atoi(val);
} else if(strcmp(cfg,"rs92.alt2d")==0) {
config.rs92.alt2d= atoi(val);
} else if(strcmp(cfg,"ephftp")==0) {
strncpy(config.ephftp, val, 40);
} else if(strcmp(cfg,"kisstnc.active")==0) {
config.kisstnc.active = atoi(val);
} else if(strcmp(cfg,"kisstnc.idformat")==0) {
@ -311,6 +345,22 @@ void Sonde::setConfig(const char *cfg) {
config.tcpfeed.highrate = atoi(val);
} else if(strcmp(cfg,"tcp.idformat")==0) {
config.tcpfeed.idformat = atoi(val);
} else if(strcmp(cfg,"mqtt.active")==0) {
config.mqtt.active = atoi(val)>0;
} else if(strcmp(cfg,"mqtt.id")==0) {
strncpy(config.mqtt.id, val, 63);
} else if(strcmp(cfg,"mqtt.host")==0) {
strncpy(config.mqtt.host, val, 63);
} else if(strcmp(cfg,"mqtt.port")==0) {
config.mqtt.port = atoi(val);
} else if(strcmp(cfg,"mqtt.username")==0) {
strncpy(config.mqtt.username, val, 63);
} else if(strcmp(cfg,"mqtt.password")==0) {
strncpy(config.mqtt.password, val, 63);
} else if(strcmp(cfg,"mqtt.prefix")==0) {
strncpy(config.mqtt.prefix, val, 63);
} else {
Serial.printf("Invalid config option '%s'=%s \n", cfg, val);
}
@ -331,6 +381,7 @@ void Sonde::addSonde(float frequency, SondeType type, int active, char *launchsi
}
Serial.printf("Adding %f - %d - %d - %s\n", frequency, type, active, launchsite);
sondeList[nSonde].type = type;
sondeList[nSonde].typestr[0] = 0;
sondeList[nSonde].freq = frequency;
sondeList[nSonde].active = active;
strncpy(sondeList[nSonde].launchsite, launchsite, 17);
@ -399,21 +450,26 @@ void Sonde::setup() {
case STYPE_RS41:
rs41.setup(sondeList[rxtask.currentSonde].freq * 1000000);
break;
case STYPE_DFM06:
case STYPE_DFM09:
dfm.setup( sondeList[rxtask.currentSonde].freq * 1000000, sondeList[rxtask.currentSonde].type==STYPE_DFM06?0:1 );
case STYPE_DFM06_OLD:
case STYPE_DFM09_OLD:
case STYPE_DFM:
dfm.setup( sondeList[rxtask.currentSonde].freq * 1000000, sondeList[rxtask.currentSonde].type );
break;
case STYPE_RS92:
rs92.setup( sondeList[rxtask.currentSonde].freq * 1000000);
break;
case STYPE_M10:
m10.setup( sondeList[rxtask.currentSonde].freq * 1000000);
case STYPE_M20:
m10m20.setup( sondeList[rxtask.currentSonde].freq * 1000000);
break;
}
// debug
float afcbw = sx1278.getAFCBandwidth();
float rxbw = sx1278.getRxBandwidth();
Serial.printf("AFC BW: %f RX BW: %f\n", afcbw, rxbw);
// reset rxtimer / norxtimer state
sonde.sondeList[sonde.currentSonde].lastState = -1;
}
extern void flashLed(int ms);
@ -429,10 +485,12 @@ void Sonde::receive() {
res = rs92.receive();
break;
case STYPE_M10:
res = m10.receive();
case STYPE_M20:
res = m10m20.receive();
break;
case STYPE_DFM06:
case STYPE_DFM09:
case STYPE_DFM06_OLD:
case STYPE_DFM09_OLD:
case STYPE_DFM:
res = dfm.receive();
break;
}
@ -462,24 +520,29 @@ void Sonde::receive() {
int event = getKeyPressEvent();
if (!event) event = timeoutEvent(si);
int action = (event==EVT_NONE) ? ACT_NONE : disp.layout->actions[event];
Serial.printf("event %x: action is %x\n", event, action);
if(action!=ACT_NONE) { Serial.printf("event %x: action is %x\n", event, action); }
// If action is to move to a different sonde index, we do update things here, set activate
// to force the sx1278 task to call sonde.setup(), and pass information about sonde to
// main loop (display update...)
if(action == ACT_NEXTSONDE || action==ACT_PREVSONDE || (action>64&&action<128) ) {
if(action == ACT_DISPLAY_SCANNER || action == ACT_NEXTSONDE || action==ACT_PREVSONDE || (action>64&&action<128) ) {
// handled here...
if(action==ACT_NEXTSONDE||action==ACT_PREVSONDE)
nextRxSonde();
else
nextRxFreq( action-64 );
action = ACT_SONDE(rxtask.currentSonde);
if(action==ACT_DISPLAY_SCANNER) {
// nothing to do here, be re-call setup() for M10/M20 for repeating AFC
}
else {
if(action==ACT_NEXTSONDE||action==ACT_PREVSONDE)
nextRxSonde();
else
nextRxFreq( action-64 );
action = ACT_SONDE(rxtask.currentSonde);
}
if(rxtask.activate==-1) {
// race condition here. maybe better use mutex. TODO
rxtask.activate = action;
rxtask.activate = ACT_SONDE(rxtask.currentSonde);
}
}
res = (action<<8) | (res&0xff);
Serial.printf("receive Result is %04x\n", res);
Serial.printf("receive(): Result is %04x (action %d, res %d)\n", res, action, res&0xff);
// let waitRXcomplete resume...
rxtask.receiveResult = res;
}
@ -489,10 +552,14 @@ uint16_t Sonde::waitRXcomplete() {
uint16_t res=0;
uint32_t t0 = millis();
rxloop:
while( rxtask.receiveResult==0xFFFF && millis()-t0 < 3000) { delay(50); }
while( !pmu_irq && rxtask.receiveResult==0xFFFF && millis()-t0 < 3000) { delay(50); }
if( pmu_irq ) {
handlePMUirq();
goto rxloop;
}
if( rxtask.receiveResult == RX_UPDATERSSI ) {
rxtask.receiveResult = 0xFFFF;
Serial.print("RSSI update: ");
Serial.printf("RSSI update: %d/2\n", sonde.si()->rssi);
disp.updateDisplayRSSI();
goto rxloop;
}
@ -515,10 +582,12 @@ rxloop:
rs92.waitRXcomplete();
break;
case STYPE_M10:
m10.waitRXcomplete();
case STYPE_M20:
m10m20.waitRXcomplete();
break;
case STYPE_DFM06:
case STYPE_DFM09:
case STYPE_DFM06_OLD:
case STYPE_DFM09_OLD:
case STYPE_DFM:
dfm.waitRXcomplete();
break;
}
@ -530,12 +599,11 @@ rxloop:
uint8_t Sonde::timeoutEvent(SondeInfo *si) {
uint32_t now = millis();
#if 1
Serial.printf("Timeout check: %d - %d vs %d; %d - %d vs %d; %d - %d vs %d\n",
Serial.printf("Timeout check: %d - %d vs %d; %d - %d vs %d; %d - %d vs %d; lastState: %d\n",
now, si->viewStart, disp.layout->timeouts[0],
now, si->rxStart, disp.layout->timeouts[1],
now, si->norxStart, disp.layout->timeouts[2]);
now, si->norxStart, disp.layout->timeouts[2], si->lastState);
#endif
Serial.printf("lastState is %d\n", si->lastState);
if(disp.layout->timeouts[0]>=0 && now - si->viewStart >= disp.layout->timeouts[0]) {
Serial.println("View timer expired");
return EVT_VIEWTO;
@ -643,9 +711,7 @@ void Sonde::updateDisplayIP() {
void Sonde::updateDisplay()
{
int t = millis();
disp.updateDisplay();
Serial.printf("updateDisplay took %d ms\n", (int)(millis()-t));
}
void Sonde::clearDisplay() {

Wyświetl plik

@ -2,6 +2,13 @@
#ifndef Sonde_h
#define Sonde_h
enum DbgLevel { DEBUG_OFF=0, DEBUG_INFO=1, DEBUG_SPARSER=16, DEBUG_DISPLAY=8 }; // to be extended for configuring serial debug output
extern uint8_t debug;
#define DebugPrint(l,x) if(debug&l) { Serial.print(x); }
#define DebugPrintln(l,x) if(debug&l) { Serial.println(x); }
#define DebugPrintf(l,...) if(debug&l) { Serial.printf(__VA_ARGS__); }
// RX_TIMEOUT: no header detected
// RX_ERROR: header detected, but data not decoded (crc error, etc.)
// RX_OK: header and data ok
@ -46,9 +53,14 @@ extern const char *RXstr[];
// 01000000 => goto sonde -1
// 01000001 => goto sonde +1
#define NSondeTypes 5
enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41, STYPE_RS92, STYPE_M10 };
#define NSondeTypes 7
enum SondeType { STYPE_DFM, STYPE_DFM09_OLD, STYPE_RS41, STYPE_RS92, STYPE_M10, STYPE_M20, STYPE_DFM06_OLD };
extern const char *sondeTypeStr[NSondeTypes];
extern const char *sondeTypeLongStr[NSondeTypes];
extern const char sondeTypeChar[NSondeTypes];
#define TYPE_IS_DFM(t) ( (t)==STYPE_DFM || (t)==STYPE_DFM09_OLD || (t)==STYPE_DFM06_OLD )
#define TYPE_IS_METEO(t) ( (t)==STYPE_M10 || (t)==STYPE_M20 )
typedef struct st_sondeinfo {
// receiver configuration
@ -56,6 +68,7 @@ typedef struct st_sondeinfo {
SondeType type;
float freq;
// decoded ID
char typestr[5]; // decoded type (use type if *typestr==0)
char id[10];
char ser[12];
bool validID;
@ -64,8 +77,8 @@ typedef struct st_sondeinfo {
float lat; // latitude
float lon; // longitude
float alt; // altitude
float vs; // vertical speed
float hs; // horizontal speed
float vs; // vertical speed in m/s
float hs; // horizontal speed in m/s
float dir; // 0..360
uint8_t sats; // number of sats
uint8_t validPos; // bit pattern for validity of above 7 fields; 0x80: position is old
@ -121,6 +134,10 @@ struct st_dfmconfig {
int agcbw;
int rxbw;
};
struct st_m10m20config {
int agcbw;
int rxbw;
};
enum IDTYPE { ID_DFMDXL, ID_DFMGRAW, ID_DFMAUTO };
@ -144,6 +161,15 @@ struct st_kisstnc {
int idformat;
};
struct st_mqtt {
int active;
char id[64];
char host[64];
int port;
char username[64];
char password[64];
char prefix[64];
};
typedef struct st_rdzconfig {
// hardware configuration
@ -166,6 +192,7 @@ typedef struct st_rdzconfig {
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 screenfile;
int8_t display[30]; // list of display mode (0:scanner, 1:default, 2,... additional modes)
int startfreq; // spectrum display start freq (400, 401, ...)
int channelbw; // spectrum channel bandwidth (valid: 5, 10, 20, 25, 50, 100 kHz)
@ -181,6 +208,8 @@ typedef struct st_rdzconfig {
struct st_rs41config rs41; // configuration options specific for RS41 receiver
struct st_rs92config rs92;
struct st_dfmconfig dfm;
struct st_m10m20config m10m20;
char ephftp[40];
// data feed configuration
// for now, one feed for each type is enough, but might get extended to more?
char call[10]; // APRS callsign
@ -188,6 +217,7 @@ typedef struct st_rdzconfig {
struct st_feedinfo udpfeed; // target for AXUDP messages
struct st_feedinfo tcpfeed; // target for APRS-IS TCP connections
struct st_kisstnc kisstnc; // target for KISS TNC (via TCP, mainly for APRSdroid)
struct st_mqtt mqtt;
} RDZConfig;

Wyświetl plik

@ -1344,7 +1344,7 @@ uint16_t TFT22_ILI9225::drawGFXChar(int16_t x, int16_t y, unsigned char c, uint1
}
// Write a character to a bitmap
uint16_t TFT22_ILI9225::drawGFXcharBM(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t *bm, int bmwd) {
uint16_t TFT22_ILI9225::drawGFXcharBM(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t *bm, int bmwidth, int bmheight) {
c -= (uint8_t)pgm_read_byte(&gfxFont->first);
GFXglyph *glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c]);
uint8_t *bitmap = (uint8_t *)pgm_read_pointer(&gfxFont->bitmap);
@ -1356,17 +1356,15 @@ uint16_t TFT22_ILI9225::drawGFXcharBM(int16_t x, int16_t y, unsigned char c, uin
int8_t xo = pgm_read_byte(&glyph->xOffset),
yo = pgm_read_byte(&glyph->yOffset);
uint8_t xx, yy, bits = 0, bit = 0;
for(yy=0; yy<h; yy++) {
if(y+yo+yy>=bmwd) continue;
if(y+yo+yy>=bmheight) continue;
if(y+yo+yy<0) continue; // yo can be negative
for(xx=0; xx<w; xx++) {
if(x+xo+xx>=bmwd) continue;
if(!(bit++ & 7)) {
bits = pgm_read_byte(&bitmap[bo++]);
}
if(bits & 0x80) {
bm[x+xo+xx + bmwd*(y+yo+yy)] = color;
if( (bits & 0x80) && (x+xo+xx<bmwidth) ) {
bm[x+xo+xx + bmwidth*(y+yo+yy)] = color;
}
bits <<= 1;
}

Wyświetl plik

@ -389,7 +389,7 @@ class TFT22_ILI9225 {
/// @return width of character in display pixels
uint16_t drawGFXChar(int16_t x, int16_t y, unsigned char c, uint16_t color);
uint16_t drawGFXcharBM(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t *bm, int bmwd);
uint16_t drawGFXcharBM(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t *bm, int bmwidth, int bmheight);
void getGFXCharExtent(uint8_t c, int16_t *gw, int16_t *gh, int16_t *xa);

Wyświetl plik

@ -204,7 +204,7 @@ extern int aprsstr_mon2raw(const char *mon, char raw[], int raw_len)
--n;
}
aprsstr_appcrc(raw, raw_len, p);
fprintf(stderr,"results in %s\n",raw);
//fprintf(stderr,"results in %s\n",raw);
return p+2;
} /* end mon2raw() */
@ -317,7 +317,7 @@ char *aprs_senddata(SondeInfo *s, const char *usercall, const char *sym) {
char comm[100];
snprintf(comm, 100, "Clb=%.1fm/s %.3fMHz Type=%s", s->vs, s->freq, sondeTypeStr[s->type]);
strcat(b, comm);
if(s->type==STYPE_M10||s->type==STYPE_DFM06||s->type==STYPE_DFM09) {
if( TYPE_IS_DFM(s->type) || TYPE_IS_METEO(s->type) ) {
snprintf(comm, 100, " ser=%s", s->ser);
strcat(b, comm);
}

Wyświetl plik

@ -30,6 +30,15 @@ TTGO T-Beam 1.0 with OLED display => fingerprint 0010111 => 23
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:1 16:1 17:0 18:0 19:0 20:0 21:1 22:1 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
0:4 1:4 2:0 3:4 4:0 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:0 13:0 14:4 15:4 16:4 17:0 18:0 19:0 20:0 21:4 22:4 23:4 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (before setup)
TTGO T-Team 1.0 with IL9225 TFT => fingerprint 23
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:1 16:1 17:0 18:0 19:0 20:0 21:1 22:1 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
0:1 1:1 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:1 16:1 17:0 18:0 19:0 20:0 21:1 22:1 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (before setup)
vs 0010111
T-Beam 1.1 seems to be different: 1110111
GPIO4 = 1 (additional pullup) => +64
GPIO12 = 1 (maybe additional pullup) => +32
1
Fingerprint GPIOs: 4, 12, 16, 17, 21, 22, 23,

Wyświetl plik

@ -6,11 +6,11 @@
#include <inttypes.h>
#include <WiFi.h>
#include "Display.h"
#include "Sonde.h"
extern WiFiClient client;
static const char *ftpserver = "www.ngs.noaa.gov";
//static const char *ftpserver = "www.ngs.noaa.gov";
char outbuf[128];
uint8_t getreply() {
@ -72,31 +72,32 @@ void geteph() {
Serial.printf("now: %s, existing: %s => updating\n", nowstr, tsstr);
}
status.close();
disp.rdis->clear();
disp.rdis->setFont(FONT_SMALL);
disp.rdis->drawString(0, 0, "FTP ngs.noaa.gov");
// fetch rinex from server
File fh = SPIFFS.open("/brdc.gz","w");
if(!fh) {
Serial.println("cannot open file\n");
return;
}
char buf[252];
snprintf(buf, 128, "/cors/rinex/%04d/%03d/brdc%03d0.%02dn.gz", year, day, day, year-2000);
char host[252];
strcpy(host, sonde.config.ephftp);
char *buf = strchr(host, '/');
if(!buf) { Serial.println("Invalid FTP host config"); return; }
*buf = 0;
buf++;
uint8_t dispw, disph, dispxs, dispys;
disp.rdis->getDispSize(&disph, &dispw, &dispxs, &dispys);
disp.rdis->clear();
disp.rdis->setFont(FONT_SMALL);
disp.rdis->drawString(0, 0, host);
// fetch rinex from server
char *ptr = buf + strlen(buf);
snprintf(ptr, 128, "%04d/%03d/brdc%03d0.%02dn.gz", year, day, day, year-2000);
Serial.println("running geteph\n");
disp.rdis->drawString(0, 1, buf+21);
disp.rdis->drawString(0, 1*dispys, ptr+9);
if(!client.connect(ftpserver, 21)) {
Serial.println("FTP connection to www.ngs.noaa.gov failed");
if(!client.connect(host, 21)) {
Serial.printf("FTP connection to %s failed\n", host);
return;
}
#if 0
while(!client.available()) delay(1);
while(client.available()) {
String s = client.readStringUntil('\n');
Serial.println(s);
}
#endif
if(getreply()>='4') { Serial.println("connected failed"); return; }
client.print("USER anonymous\r\n");
if(getreply()>='4') { Serial.println("USER failed"); return; }
@ -121,8 +122,8 @@ void geteph() {
}
uint16_t port = (array_pasv[4]<<8) | (array_pasv[5]&0xff);
WiFiClient dclient;
Serial.printf("connecting to %s:%d\n", ftpserver,port);
dclient.connect(ftpserver, port);
Serial.printf("connecting to %s:%d\n", host, port);
dclient.connect(host, port);
if(!dclient) {
Serial.println("data connection failed");
return;
@ -136,18 +137,22 @@ void geteph() {
int len=0;
while(dclient.connected()) {
while(dclient.available()) {
char c = dclient.read();
fh.write(c);
len++;
int c = dclient.read();
if(c==-1) {
Serial.println("dclient.read() returned -1 inspite of available() being true?!");
} else {
fh.write(c);
len++;
}
}
}
Serial.printf("fetched %d bytes\n", len);
fh.close();
snprintf(buf, 16, "Fetched %d B ",len);
buf[16]=0;
disp.rdis->drawString(0,2,buf);
disp.rdis->drawString(0,2*dispys,buf);
disp.rdis->drawString(0,4,"Decompressing...");
disp.rdis->drawString(0,4*dispys,"Decompressing...");
// decompression
tinfl_decompressor *decomp = (tinfl_decompressor *)malloc(sizeof(tinfl_decompressor));
tinfl_init(decomp);
@ -215,7 +220,7 @@ void geteph() {
status.close();
snprintf(buf, 16, "Done: %d B ",total);
buf[16]=0;
disp.rdis->drawString(0,5,buf);
disp.rdis->drawString(0,5*dispys,buf);
delay(1000);
free(obuf);

Wyświetl plik

@ -0,0 +1,11 @@
{
"dependencies":
[
{
"owner": "olikraus",
"name": "U8g2",
"version": "^2.28.8"
}
]
}

Wyświetl plik

@ -0,0 +1,126 @@
#include <Arduino.h>
#include "mqtt.h"
#include <WiFi.h>
#include <AsyncMqttClient.h>
#include <ESPmDNS.h>
TimerHandle_t mqttReconnectTimer;
void mqttCallback(char* topic, byte* payload, unsigned int length) {
Serial.print("Message arrived [");
Serial.print(topic);
Serial.print("] ");
for (int i=0;i<length;i++) {
Serial.print((char)payload[i]);
}
Serial.println();
}
void MQTT::init(const char* host, uint16_t port, const char* id, const char *username, const char *password, const char *prefix)
{
WiFi.hostByName(host, this->ip);
this->port = port;
this->username = username;
this->password = password;
this->prefix = prefix;
char buffer[20];
snprintf(buffer, 20, "%s%6ld", id, random(0, 1000));
this->id = buffer;
Serial.println("[MQTT] pubsub client");
mqttClient.setServer(ip, port);
mqttClient.setClientId(id);
if (strlen(password) > 0) {
mqttClient.setCredentials(username, password);
}
}
void MQTT::connectToMqtt() {
Serial.println("Connecting to MQTT...");
mqttClient.connect();
}
void MQTT::publishUptime()
{
mqttClient.connect(); // ensure we've got connection
Serial.println("[MQTT] writing");
char payload[12];
snprintf(payload, 12, "%lu", millis());
char topic[128];
snprintf(topic, 128, "%s%s", this->prefix, "uptime");
mqttClient.publish(topic, 1, 1, payload);
}
void MQTT::publishPacket(SondeInfo *s)
{
mqttClient.connect(); // ensure we've got connection
char payload[1024];
snprintf(payload, 1024, "{"
"\"active\": %d,"
"\"freq\": %.2f,"
"\"id\": \"%s\","
"\"ser\": \"%s\","
"\"validId\": %d,"
"\"launchsite\": \"%s\","
"\"lat\": %.5f,"
"\"lon\": %.5f,"
"\"alt\": %.1f,"
"\"vs\": %.1f,"
"\"hs\": %.1f,"
"\"dir\": %.1f,"
"\"sats\": %d,"
"\"validPos\": %d,"
"\"time\": %d,"
"\"sec\": %d,"
"\"frame\": %d,"
"\"validTime\": %d,"
"\"rssi\": %d,"
"\"afc\": %d,"
"\"rxStat\": \"%s\","
"\"rxStart\": %d,"
"\"norxStart\": %d,"
"\"viewStart\": %d,"
"\"lastState\": %d,"
"\"launchKT\": %d,"
"\"burstKT\": %d,"
"\"countKT\": %d,"
"\"crefKT\": %d"
"}",
(int)s->active,
s->freq,
s->id,
s->ser,
(int)s->validID,
s->launchsite,
s->lat,
s->lon,
s->alt,
s->vs,
s->hs,
s->dir,
s->sats,
s->validPos,
s->time,
s->sec,
s->frame,
(int)s->validTime,
s->rssi,
s->afc,
s->rxStat,
s->rxStart,
s->norxStart,
s->viewStart,
s->lastState,
s->launchKT,
s->burstKT,
s->countKT,
s->crefKT
);
char topic[128];
snprintf(topic, 128, "%s%s", this->prefix, "packet");
mqttClient.publish(topic, 1, 1, payload);
}

Wyświetl plik

@ -0,0 +1,28 @@
#ifndef MQTT_h
#define MQTT_h
#include <WiFi.h>
#include <AsyncMqttClient.h>
#include "Sonde.h"
class MQTT
{
public:
WiFiClient mqttWifiClient;
AsyncMqttClient mqttClient;
TimerHandle_t mqttReconnectTimer;
IPAddress ip;
uint16_t port;
const char *id;
const char *username;
const char *password;
const char *prefix;
void init(const char *host, uint16_t port, const char *id, const char *username, const char *password, const char *prefix);
void publishPacket(SondeInfo *s);
void publishUptime();
private:
void connectToMqtt();
};
#endif

35
platformio.ini 100644
Wyświetl plik

@ -0,0 +1,35 @@
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[platformio]
src_dir = RX_FSK
lib_dir = libraries
data_dir = RX_FSK/data
[extra]
lib_deps_builtin =
SondeLib
lib_deps_external =
olikraus/U8g2 @ ^2.28.8
AXP202X_Library
stevemarple/MicroNMEA @ ^2.0.5
; nkawu/TFT 22 ILI9225 @ ^1.4.4
me-no-dev/ESP Async WebServer @ ^1.2.3
https://github.com/dx168b/async-mqtt-client
[env:ttgo-lora32]
;platform = espressif32
platform = https://github.com/platformio/platform-espressif32.git
board = ttgo-lora32-v1
framework = arduino
monitor_speed = 115200
lib_deps =
${extra.lib_deps_builtin}
${extra.lib_deps_external}