Merge branch 'dl9rdz:devel' into devel

pull/170/head
Michael Carter 2021-09-16 10:36:53 +01:00 zatwierdzone przez GitHub
commit cadfc9dd97
Nie znaleziono w bazie danych klucza dla tego podpisu
ID klucza GPG: 4AEE18F83AFDEB23
58 zmienionych plików z 1131 dodań i 1735 usunięć

Wyświetl plik

@ -7,9 +7,9 @@ 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.13-linux64.tar.xz
- tar xf arduino-1.8.13-linux64.tar.xz
- sudo mv arduino-1.8.13 /usr/local/share/arduino
- wget https://downloads.arduino.cc/arduino-1.8.16-linux64.tar.xz
- tar xf arduino-1.8.16-linux64.tar.xz
- sudo mv arduino-1.8.16 /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
@ -40,7 +40,7 @@ before_install:
- sudo iptables -A INPUT -m conntrack --ctstate ESTABLISHED,RELATED -j ACCEPT
install:
- arduino --pref "boardsmanager.additional.urls=https://dl.espressif.com/dl/package_esp32_index.json" --save-prefs
- arduino --pref "boardsmanager.additional.urls=https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json" --save-prefs
- arduino --pref "build.verbose=true" --save-prefs
- arduino --pref "custom_FlashFreq=ttgo-lora32-v1_80" --save-prefs
- mkdir -p $PWD/build

Wyświetl plik

@ -33,7 +33,8 @@ SondeHub integration has mainly been tested with RS41 and DFM.
Support for other radiosondes that use AFSK modulation is not feasible with the TTGO hardware.
In particular, decoding iMet radiosondes is not practical.
In particular, decoding iMet-1/iMet-4 radiosondes is not practical (iMet-5x seems to use FSK,
so should be feasible to implement).
Adding support for LMS6 (see issue #48) and ims100 (see branch ims100) could be feasible,
but currently I don't have plans to do add this myself. Well-tested pull requests will of

Wyświetl plik

@ -1,32 +1,32 @@
#include <axp20x.h>
#include "features.h"
#include "version.h"
#include "axp20x.h"
#include <WiFi.h>
#include <WiFiUdp.h>
#include <ESPAsyncWebServer.h>
#include <SPIFFS.h>
//#include <U8x8lib.h>
//#include <U8g2lib.h>
#include <SPI.h>
#include <Update.h>
#include <ESPmDNS.h>
#include <MicroNMEA.h>
#include <Ticker.h>
#include <SX1278FSK.h>
#include <Sonde.h>
#include <Display.h>
#include <Scanner.h>
#include <aprs.h>
#include "version.h"
#include "geteph.h"
#include "rs92gps.h"
#if FEATURE_MQTT
#include "mqtt.h"
#endif
#include "esp_heap_caps.h"
#include "src/SX1278FSK.h"
#include "src/Sonde.h"
#include "src/Display.h"
#include "src/Scanner.h"
#include "src/geteph.h"
#include "src/rs92gps.h"
#include "src/aprs.h"
#if FEATURE_MQTT
#include "src/mqtt.h"
#endif
//#define ESP_MEM_DEBUG 1
int e;
//int e;
enum MainState { ST_DECODER, ST_SPECTRUM, ST_WIFISCAN, ST_UPDATE, ST_TOUCHCALIB };
static MainState mainState = ST_WIFISCAN; // ST_WIFISCAN;
@ -60,7 +60,7 @@ WiFiClient client;
WiFiClient shclient; // Sondehub v2
unsigned long time_last_update = 0;
/* SH_LOC_OFF: never send position information to SondeHub
SH_LOC_FIXED: send fixed position (if specified in config) or GPS position (if there is a GPS fix) as fixed station position (no chase mode) to sondehub
SH_LOC_FIXED: send fixed position (if specified in config) to sondehub
SH_LOC_CHASE: always activate chase mode and send GPS position (if available)
SH_LOC_AUTO: if there is no valid GPS position, or GPS position < MIN_LOC_AUTO_DIST away from known fixed position: use FIXED mode
otherwise, i.e. if there is a valid GPS position and (either no fixed position in config, or GPS position is far away from fixed position), use CHASE mode.
@ -159,6 +159,9 @@ String processor(const String& var) {
snprintf(tmpstr, 128, "Fingerprint %d (%s)", sonde.fingerprint, fpstr);
return String(tmpstr);
}
if (var == "EPHSTATE") {
return String(ephtxt[ephstate]);
}
return String();
}
@ -211,13 +214,7 @@ void setupChannelList() {
} else if (space[1] == 'R') {
type = STYPE_RS92;
}
else if (space[1] == '9') {
type = STYPE_DFM09_OLD;
}
else if (space[1] == '6') {
type = STYPE_DFM06_OLD;
}
else if (space[1] == 'D') {
else if (space[1] == 'D' || space[1] == '9' || space[1] == '6') {
type = STYPE_DFM;
}
else if (space[1] == 'M') {
@ -262,32 +259,6 @@ const char *createQRGForm() {
char *ptr = message;
strcpy(ptr, HTMLHEAD);
strcat(ptr, "<script src=\"rdz.js\"/> <script> window.onload = prep; </script></head>");
/*
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>");
*/
HTMLBODY(ptr, "qrg.html");
//strcat(ptr, "<body><form class=\"wrapper\" action=\"qrg.html\" method=\"post\"><div class=\"content\"><table><tr><th>ID</th><th>Active</th><th>Freq</th><th>Launchsite</th><th>Mode</th></tr>");
strcat(ptr, "<table><tr><th>ID</th><th>Active</th><th>Freq</th><th>Launchsite</th><th>Mode</th></tr>");
@ -349,6 +320,7 @@ const char *handleQRGPost(AsyncWebServerRequest *request) {
const char *fstr = fstring.c_str();
const char *tstr = tstring.c_str();
const char *sstr = sstring.c_str();
if (*tstr == '6' || *tstr == '9') tstr = "D";
Serial.printf("Processing a=%s, f=%s, t=%s, site=%s\n", active ? "YES" : "NO", fstr, tstr, sstr);
char typech = tstr[0];
file.printf("%3.3f %c %c %s\n", atof(fstr), typech, active ? '+' : '-', sstr);
@ -498,8 +470,8 @@ void addSondeStatus(char *ptr, int i)
sprintf(ptr + strlen(ptr), "</td></tr><tr><td>QTH: %.6f,%.6f h=%.0fm</td></tr>\n", s->lat, s->lon, s->alt);
const time_t t = s->time;
ts = *gmtime(&t);
sprintf(ptr + strlen(ptr), "<tr><td>Frame# %d, Sats=%d, %04d-%02d-%02d %02d:%02d:%02d</td></tr>",
s->frame, s->sats, ts.tm_year + 1900, ts.tm_mon + 1, ts.tm_mday, ts.tm_hour, ts.tm_min, ts.tm_sec + s->sec);
sprintf(ptr + strlen(ptr), "<tr><td>Frame# %u, Sats=%d, %04d-%02d-%02d %02d:%02d:%02d</td></tr>",
s->frame, s->sats, ts.tm_year + 1900, ts.tm_mon + 1, ts.tm_mday, ts.tm_hour, ts.tm_min, ts.tm_sec);
if (s->type == STYPE_RS41) {
sprintf(ptr + strlen(ptr), "<tr><td>Burst-KT=%d Launch-KT=%d Countdown=%d (vor %ds)</td></tr>\n",
s->burstKT, s->launchKT, s->countKT, ((uint16_t)s->frame - s->crefKT));
@ -578,13 +550,6 @@ void setupConfigData() {
}
struct st_configitems {
const char *name;
const char *label;
int type; // 0: numeric; i>0 string of length i; -1: separator; -2: type selector
void *data;
};
struct st_configitems config_list[] = {
/* General config settings */
{"", "Software configuration", -5, NULL},
@ -616,7 +581,7 @@ struct st_configitems config_list[] = {
{"", "Data feed configuration", -5, NULL},
/* APRS settings */
{"call", "Call", 8, sonde.config.call},
{"passcode", "Passcode", 8, sonde.config.passcode},
{"passcode", "Passcode", 0, &sonde.config.passcode},
/* KISS tnc settings */
{"kisstnc.active", "KISS TNC (port 14590) (needs reboot)", 0, &sonde.config.kisstnc.active},
{"kisstnc.idformat", "KISS TNC ID Format", -2, &sonde.config.kisstnc.idformat},
@ -663,6 +628,7 @@ struct st_configitems config_list[] = {
{"led_pout", "LED output port", 0, &sonde.config.led_pout},
{"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},
{"batt_adc", "Battery measurement pin", 0, &sonde.config.batt_adc},
#if 1
{"sx1278_ss", "SX1278 SS", 0, &sonde.config.sx1278_ss},
{"sx1278_miso", "SX1278 MISO", 0, &sonde.config.sx1278_miso},
@ -685,7 +651,7 @@ struct st_configitems config_list[] = {
{"sondehub.email", "SondeHub email (optional, only used to contact in case of upload errors)", 63, &sonde.config.sondehub.email},
#endif
};
const static int N_CONFIG = (sizeof(config_list) / sizeof(struct st_configitems));
const int N_CONFIG = (sizeof(config_list) / sizeof(struct st_configitems));
void addConfigStringEntry(char *ptr, int idx, const char *label, int len, char *field) {
sprintf(ptr + strlen(ptr), "<tr><td>%s</td><td><input name=\"CFG%d\" type=\"text\" value=\"%s\"/></td></tr>\n",
@ -751,6 +717,7 @@ const char *createConfigForm() {
HTMLBODY(ptr, "config.html");
strcat(ptr, "<table><tr><th>Option</th><th>Value</th></tr>");
for (int i = 0; i < N_CONFIG; i++) {
Serial.printf("%d: %s -- %d\n", i, config_list[i].label, strlen(ptr));
switch (config_list[i].type) {
case -5: // Heading
addConfigHeading(ptr, config_list[i].label);
@ -758,7 +725,7 @@ const char *createConfigForm() {
case -6: // List of int8 values
addConfigInt8List(ptr, i, config_list[i].label, (int8_t *)config_list[i].data);
break;
case -3: // in/offt
case -3: // on/off
addConfigOnOffEntry(ptr, i, config_list[i].label, (int *)config_list[i].data);
break;
case -2: // DFM format
@ -1062,6 +1029,7 @@ const char *handleEditPost(AsyncWebServerRequest *request) {
return "";
}
// will be removed. its now in data/upd.html (for GET; POST to update.html still handled here)
const char *createUpdateForm(boolean run) {
char *ptr = message;
strcpy(ptr, "<html><head><link rel=\"stylesheet\" type=\"text/css\" href=\"style.css\"></head><body><form action=\"update.html\" method=\"post\">");
@ -1118,7 +1086,7 @@ void addSondeStatusKML(char *ptr, int i)
return;
}
sprintf(ptr + strlen(ptr), "<Placemark id=\"%s\"><name>%s</name><Point><coordinates>%.6f,%.6f,%.0f</coordinates></Point><description>%3.3f MHz, Type: %s, h=%.0fm</description></Placemark>",
sprintf(ptr + strlen(ptr), "<Placemark id=\"%s\"><name>%s</name><Point><altitudeMode>absolute</altitudeMode><coordinates>%.6f,%.6f,%.0f</coordinates></Point><description>%3.3f MHz, Type: %s, h=%.0fm</description></Placemark>",
s->id, s->id,
s->lon, s->lat, s->alt,
s->freq, sondeTypeStr[s->type], s->alt);
@ -1754,9 +1722,9 @@ void IRAM_ATTR button2ISR() {
int getKeyPress() {
KeyPress p = button1.pressed;
button1.pressed = KP_NONE;
//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);
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;
}
@ -1935,7 +1903,7 @@ void setup()
Serial.println("AXP192 Begin FAIL");
}
axp.setPowerOutPut(AXP192_LDO2, AXP202_ON);
if(sonde.config.type == TYPE_M5_CORE2) {
if (sonde.config.type == TYPE_M5_CORE2) {
// Display backlight on M5 Core2
axp.setPowerOutPut(AXP192_DCDC3, AXP202_ON);
axp.setDCDC3Voltage(3300);
@ -1964,6 +1932,9 @@ void setup()
delay(500);
}
}
if (sonde.config.batt_adc >= 0) {
pinMode(sonde.config.batt_adc, INPUT);
}
if (sonde.config.power_pout >= 0) { // for a heltec v2, pull GPIO21 low for display power
pinMode(sonde.config.power_pout & 127, OUTPUT);
digitalWrite(sonde.config.power_pout & 127, sonde.config.power_pout & 128 ? 1 : 0);
@ -2059,11 +2030,11 @@ void setup()
#if 1
if(sonde.config.type == TYPE_M5_CORE2) {
// Core2 uses Pin 38 for MISO
SPI.begin(18, 38, 23, -1);
if (sonde.config.type == TYPE_M5_CORE2) {
// Core2 uses Pin 38 for MISO
SPI.begin(18, 38, 23, -1);
} else {
SPI.begin();
SPI.begin();
}
//Set most significant bit first
SPI.setBitOrder(MSBFIRST);
@ -2072,24 +2043,23 @@ void setup()
//Set data mode
SPI.setDataMode(SPI_MODE0);
sx1278.setup(globalLock);
sx1278.setup(globalLock);
uint8_t state = 2;
int i=0;
while(++i<3) {
delay(500);
// == check the radio chip by setting default frequency =========== //
sx1278.ON();
if (sx1278.setFrequency(402700000) == 0) {
Serial.println(F("Setting freq: SUCCESS "));
} else {
Serial.println(F("Setting freq: ERROR "));
int i = 0;
while (++i < 3) {
delay(500);
// == check the radio chip by setting default frequency =========== //
sx1278.ON();
if (sx1278.setFrequency(402700000) == 0) {
Serial.println(F("Setting freq: SUCCESS "));
} else {
Serial.println(F("Setting freq: ERROR "));
}
float f = sx1278.getFrequency();
Serial.print("Frequency set to ");
Serial.println(f);
// == check the radio chip by setting default frequency =========== //
}
float f = sx1278.getFrequency();
Serial.print("Frequency set to ");
Serial.println(f);
// == check the radio chip by setting default frequency =========== //
}
#endif
//sx1278.setLNAGain(-48);
@ -2328,7 +2298,7 @@ void loopDecoder() {
#endif
#if FEATURE_MQTT
// send to MQTT if enabled
// send to MQTT if enabledson
if (connected && mqttEnabled) {
Serial.println("Sending sonde info via MQTT");
mqttclient.publishPacket(s);
@ -2376,7 +2346,6 @@ void loopDecoder() {
"\"sats\": %d,"
"\"validPos\": %d,"
"\"time\": %d,"
"\"sec\": %d,"
"\"frame\": %d,"
"\"validTime\": %d,"
"\"rssi\": %d,"
@ -2404,7 +2373,6 @@ void loopDecoder() {
s->sats,
s->validPos,
s->time,
s->sec,
s->frame,
(int)s->validTime,
s->rssi,
@ -2525,7 +2493,7 @@ void enableNetwork(bool enable) {
SetupAsyncServer();
udp.begin(WiFi.localIP(), LOCALUDPPORT);
MDNS.addService("http", "tcp", 80);
MDNS.addService("kisstnc", "tcp", 14580);
MDNS.addService("kiss-tnc", "tcp", 14580);
MDNS.addService("jsonrdz", "tcp", 14570);
if (sonde.config.kisstnc.active) {
tncserver.begin();
@ -2876,6 +2844,7 @@ void loopWifiScan() {
}
if (hasRS92) {
geteph();
if(ephstate==EPH_PENDING) ephstate=EPH_ERROR;
get_eph("/brdc");
}
delay(3000);
@ -2897,17 +2866,25 @@ void execOTA() {
int contentLength = 0;
bool isValidContentType = false;
sonde.clearDisplay();
disp.rdis->setFont(FONT_SMALL);
disp.rdis->drawString(0, 0, "C:");
String dispHost = updateHost.substring(0, 14);
disp.rdis->drawString(2, 0, dispHost.c_str());
uint8_t dispxs, dispys;
if( ISOLED(sonde.config) ) {
disp.rdis->setFont(FONT_SMALL);
dispxs = dispys = 1;
} else {
disp.rdis->setFont(5);
dispxs = 18;
dispys = 20;
}
String dispHost = updateHost.substring(0, 16);
disp.rdis->drawString(0, 0, dispHost.c_str());
Serial.println("Connecting to: " + updateHost);
// Connect to Update host
if (client.connect(updateHost.c_str(), updatePort)) {
// Connection succeeded, fecthing the bin
Serial.println("Fetching bin: " + String(*updateBin));
disp.rdis->drawString(0, 1, "Fetching update");
disp.rdis->drawString(0, 1 * dispys, "Fetching update");
// Get the contents of the bin file
client.print(String("GET ") + *updateBin + " HTTP/1.1\r\n" +
@ -3000,22 +2977,22 @@ void execOTA() {
// Check what is the contentLength and if content type is `application/octet-stream`
Serial.println("contentLength : " + String(contentLength) + ", isValidContentType : " + String(isValidContentType));
disp.rdis->drawString(0, 2, "Len: ");
disp.rdis->drawString(0, 2 * dispys, "Len: ");
String cls = String(contentLength);
disp.rdis->drawString(5, 2, cls.c_str());
disp.rdis->drawString(5 * dispxs, 2 * dispys, cls.c_str());
// check contentLength and content type
if (contentLength && isValidContentType) {
// Check if there is enough to OTA Update
bool canBegin = Update.begin(contentLength);
disp.rdis->drawString(0, 4, "Starting update");
disp.rdis->drawString(0, 4 * dispys, "Starting update");
// If yes, begin
if (canBegin) {
Serial.println("Begin OTA. This may take 2 - 5 mins to complete. Things might be quite for a while.. Patience!");
// No activity would appear on the Serial monitor
// So be patient. This may take 2 - 5mins to complete
disp.rdis->drawString(0, 5, "Please wait!");
disp.rdis->drawString(0, 5 * dispys, "Please wait!");
size_t written = Update.writeStream(client);
if (written == contentLength) {
@ -3030,7 +3007,7 @@ void execOTA() {
Serial.println("OTA done!");
if (Update.isFinished()) {
Serial.println("Update successfully completed. Rebooting.");
disp.rdis->drawString(0, 7, "Rebooting....");
disp.rdis->drawString(0, 7 * dispys, "Rebooting....");
delay(1000);
ESP.restart();
} else {
@ -3153,40 +3130,55 @@ void sondehub_station_update(WiFiClient *client, struct st_sondehub *conf) {
"{"
"\"software_name\": \"%s\","
"\"software_version\": \"%s\","
"\"uploader_callsign\": \"%s\","
"\"uploader_contact_email\": \"%s\",",
version_name, version_id, conf->callsign, conf->email);
"\"uploader_callsign\": \"%s\",",
version_name, version_id, conf->callsign);
w += strlen(w);
// We send GPS position: (a) in CHASE mode, (b) in FIXED mode if no fixed location has been specified in config
if (chase == SH_LOC_CHASE || (chase == SH_LOC_FIXED && (isnan(conf->lat) || isnan(conf->lon)) ) ) {
// Only send email if provided
if (strlen(conf->email) != 0) {
sprintf(w,
"\"uploader_contact_email\": \"%s\",",
conf->email);
w += strlen(w);
}
// Only send antenna if provided
if (strlen(conf->antenna) != 0) {
sprintf(w,
"\"uploader_antenna\": \"%s\",",
conf->antenna);
w += strlen(w);
}
// We send GPS position: (a) in CHASE mode, (b) in AUTO mode if no fixed location has been specified in config
if (chase == SH_LOC_CHASE) {
if (gpsPos.valid && gpsPos.lat != 0 && gpsPos.lon != 0) {
sprintf(w,
"\"uploader_position\": [%.6f,%.6f,%d],"
"\"uploader_antenna\": \"%s\","
"\"mobile\": true"
"}",
gpsPos.lat, gpsPos.lon, gpsPos.alt, conf->antenna);
"\"mobile\": true",
gpsPos.lat, gpsPos.lon, gpsPos.alt);
} else {
sprintf(w, "\"uploader_position\": [null,null,null]");
}
w += strlen(w);
}
// Otherweise, in FIXED mode we send the fixed position from config (if specified)
else if (chase == SH_LOC_FIXED) {
if ((!isnan(conf->lat)) && (!isnan(conf->lon))) {
sprintf(w,
"\"uploader_position\": [%.6f,%.6f,%s],"
"\"uploader_antenna\": \"%s\""
"}",
conf->lat, conf->lon, conf->alt[0] ? conf->alt : "null", conf->antenna);
"\"uploader_position\": [%.6f,%.6f,%s]",
conf->lat, conf->lon, conf->alt[0] ? conf->alt : "null");
} else {
sprintf(w, "\"uploader_position\": [null,null,null]");
}
w += strlen(w);
} else {
sprintf(w, "\"uploader_position\": [null,null,null]");
w += strlen(w);
}
else {
// otherwise (in SH_LOC_NONE mode) we dont include any position info
sprintf(w,
"\"uploader_position\": [null,null,null],"
"\"uploader_antenna\": \"%s\""
"}",
conf->antenna);
}
// otherwise (in SH_LOC_NONE mode) we dont include any position info
sprintf(w, "}");
client->println("PUT /listeners HTTP/1.1");
client->print("Host: ");
@ -3214,8 +3206,8 @@ enum SHState { SH_DISCONNECTED, SH_CONNECTING, SH_CONN_IDLE, SH_CONN_APPENDING,
SHState shState = SH_DISCONNECTED;
time_t shStart = 0;
/* Sonde.h: enum SondeType { STYPE_DFM, STYPE_DFM09_OLD, STYPE_RS41, STYPE_RS92, STYPE_M10, STYPE_M20, STYPE_DFM06_OLD, STYPE_MP3H }; */
const char *sondeTypeStrSH[NSondeTypes] = { "DFM", "DFM", "RS41", "RS92", "M10", "M20", "DFM", "MRZ" };
/* Sonde.h: enum SondeType { STYPE_DFM,, STYPE_RS41, STYPE_RS92, STYPE_M10, STYPE_M20, STYPE_MP3H }; */
const char *sondeTypeStrSH[NSondeTypes] = { "DFM", "RS41", "RS92", "M10", "M20", "MRZ" };
const char *dfmSubtypeStrSH[16] = { NULL, NULL, NULL, NULL, NULL, NULL,
"DFM06", // 0x06
"PS15", // 0x07
@ -3242,15 +3234,23 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub *
struct tm ts;
uint8_t realtype = s->type;
// config setting M10 and M20 will both decode both types, so use the real type that was decoded
if(TYPE_IS_METEO(realtype)) { realtype = s->subtype==1 ? STYPE_M10 : STYPE_M20; }
if (TYPE_IS_METEO(realtype)) {
realtype = s->subtype == 1 ? STYPE_M10 : STYPE_M20;
}
// For DFM, s->time is data from subframe DAT8 (gps date/hh/mm), and sec is from DAT1 (gps sec/usec)
// For all others, sec should always be 0 and time the exact time in seconds
time_t t = s->time + s->sec;
time_t t = s->time;
int chase = conf->chase;
// automatically decided if CHASE or FIXED mode is used (for config AUTO)
if (chase == SH_LOC_AUTO) {
if (SH_LOC_AUTO_IS_CHASE) chase = SH_LOC_CHASE; else chase = SH_LOC_FIXED;
}
while (client->available() > 0) {
// data is available from remote server, process it...
int cnt = client->readBytesUntil('\n', rs_msg, MSG_SIZE);
int cnt = client->readBytesUntil('\n', rs_msg, MSG_SIZE - 1);
rs_msg[cnt] = 0;
Serial.println(rs_msg);
// If something that looks like a valid HTTP response is received, we are ready to send the next data item
@ -3318,46 +3318,31 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub *
"\"manufacturer\": \"%s\","
"\"serial\": \"%s\","
"\"datetime\": \"%04d-%02d-%02dT%02d:%02d:%02d.000Z\","
"\"lat\": %.6f,"
"\"lon\": %.6f,"
"\"alt\": %.3f,"
"\"lat\": %.5f,"
"\"lon\": %.5f,"
"\"alt\": %.5f,"
"\"frequency\": %.3f,"
"\"vel_h\": %.3f,"
"\"vel_v\": %.3f,"
"\"heading\": %.3f,"
"\"rssi\": %.1f,",
"\"vel_h\": %.5f,"
"\"vel_v\": %.5f,"
"\"heading\": %.5f,"
"\"rssi\": %.1f,"
"\"frame\": %d,"
"\"type\": \"%s\",",
version_name, version_id, conf->callsign,
timeinfo.tm_year + 1900, timeinfo.tm_mon + 1, timeinfo.tm_mday, timeinfo.tm_hour, timeinfo.tm_min, timeinfo.tm_sec,
manufacturer_string[realtype], s->ser,
ts.tm_year + 1900, ts.tm_mon + 1, ts.tm_mday, ts.tm_hour, ts.tm_min, ts.tm_sec + s->sec,
ts.tm_year + 1900, ts.tm_mon + 1, ts.tm_mday, ts.tm_hour, ts.tm_min, ts.tm_sec,
(float)s->lat, (float)s->lon, (float)s->alt, (float)s->freq, (float)s->hs, (float)s->vs,
(float)s->dir, -((float)s->rssi / 2)
(float)s->dir, -((float)s->rssi / 2), s->vframe, sondeTypeStrSH[realtype]
);
w += strlen(w);
// Only send sats if not M20
if (realtype != STYPE_M20) {
sprintf(w, "\"sats\": %d,", (int)s->sats);
w += strlen(w);
}
if ( TYPE_IS_DFM(realtype) || TYPE_IS_METEO(realtype) || realtype == STYPE_MP3H ) {
// send frame as gps timestamp for these sonde, identical to autorx
// For M10, this is real GPS time (seconds since Jqn 6 1980, without adjusting for leap seconds)
// DFM and MP3H send real UTC (with leap seconds considered), so for them the frame number actually
// is gps time plus number of leap seconds since the beginning of GPS time.
int frame = (int)(t - 315964800);
if (realtype == STYPE_M10) {
frame += 18;
};
sprintf(w, "\"frame\": %d,", frame);
} else {
sprintf(w, "\"frame\": %d,", s->frame);
}
w += strlen(w);
sprintf(w, "\"type\": \"%s\",", sondeTypeStrSH[realtype]);
w += strlen(w);
/* if there is a subtype (DFM only) */
if ( TYPE_IS_DFM(s->type) && s->subtype > 0 && s->subtype < 16 ) {
const char *t = dfmSubtypeStrSH[s->subtype];
@ -3367,47 +3352,53 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub *
w += strlen(w);
}
// Only send temp & humidity if provided
if (((int)s->temperature != 0) && ((int)s->relativeHumidity != 0)) {
sprintf(w,
"\"temp\": %.1f,"
"\"humidity\": %.1f,",
"\"temp\": %.3f,"
"\"humidity\": %.3f,",
float(s->temperature), float(s->relativeHumidity)
);
w += strlen(w);
}
if ((conf->chase == 0) && (!isnan(conf->lat)) && (!isnan(conf->lon))) {
if (conf->alt[0] != '\0') {
// Only send antenna if provided
if (strlen(conf->antenna) != 0) {
sprintf(w,
"\"uploader_antenna\": \"%s\",",
conf->antenna);
w += strlen(w);
}
// We send GPS position: (a) in CHASE mode, (b) in AUTO mode if no fixed location has been specified in config
if (chase == SH_LOC_CHASE) {
if (gpsPos.valid && gpsPos.lat != 0 && gpsPos.lon != 0) {
sprintf(w,
"\"uploader_position\": [%.6f,%.6f,%s],"
"\"uploader_antenna\": \"%s\""
"}",
conf->lat, conf->lon, conf->alt, conf->antenna
);
"\"uploader_position\": [%.6f,%.6f,%d]",
gpsPos.lat, gpsPos.lon, gpsPos.alt);
} else {
sprintf(w,
"\"uploader_position\": [%.6f,%.6f,null],"
"\"uploader_antenna\": \"%s\""
"}",
conf->lat, conf->lon, conf->antenna
);
sprintf(w, "\"uploader_position\": [null,null,null]");
}
w += strlen(w);
}
else if (gpsPos.valid && gpsPos.lat != 0 && gpsPos.lon != 0) {
sprintf(w,
"\"uploader_position\": [%.6f,%.6f,%d],"
"\"uploader_antenna\": \"%s\""
"}",
gpsPos.lat, gpsPos.lon, gpsPos.alt, conf->antenna
);
}
else {
sprintf(w,
"\"uploader_antenna\": \"%s\""
"}",
conf->antenna
);
// Otherweise, in FIXED mode we send the fixed position from config (if specified)
else if (chase == SH_LOC_FIXED) {
if ((!isnan(conf->lat)) && (!isnan(conf->lon))) {
sprintf(w,
"\"uploader_position\": [%.6f,%.6f,%s]",
conf->lat, conf->lon, conf->alt[0] ? conf->alt : "null");
} else {
sprintf(w, "\"uploader_position\": [null,null,null]");
}
w += strlen(w);
} else {
sprintf(w, "\"uploader_position\": [null,null,null]");
w += strlen(w);
}
// otherwise (in SH_LOC_NONE mode) we dont include any position info
sprintf(w, "}");
if (shState != SH_CONN_APPENDING) {
sondehub_send_header(client, s, conf);
sondehub_send_next(client, s, conf, rs_msg, strlen(rs_msg), 1);

Wyświetl plik

@ -121,7 +121,7 @@ mqtt.prefix=rdz_sonde_server/
#-------------------------------#
# Sondehub v2 DB settings
sondehub.active=0
sondehub.chase=0
sondehub.chase=3
sondehub.host=api.v2.sondehub.org
sondehub.callsign=CHANGEME_RDZTTGO
sondehub.lat=

Wyświetl plik

@ -10,16 +10,18 @@
<body>
<div class="wrapper"><div class="header">
<h2>rdzTTGOSonde Server</h2>
<div class="tab">
<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="document.location.href='livemap.html'">LiveMap</button>
<button class="tablinks" onclick="selTab(event,'Map')">Map</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 class="topnav" id="myTopnav">
<a href="#" onclick="selTab(event,'QRG')" class="tablinks" id="defaultTab">QRG</a>
<a href="#" onclick="selTab(event,'WiFi')" class="tablinks">WiFi</a>
<a href="#" onclick="selTab(event,'Data')" class="tablinks">Data</a>
<a href="#" onclick="document.location.href='livemap.html'" class="tablinks">LiveMap</a>
<a href="#" onclick="selTab(event,'Map')" class="tablinks">Map</a>
<a href="#" onclick="selTab(event,'Config')" class="tablinks">Config</a>
<a href="#" onclick="selTab(event,'Control')" class="tablinks">Control</a>
<a href="#" onclick="selTab(event,'About')" class="tablinks">About</a>
<a href="javascript:void(0);" class="icon" onclick="myFunction()">
<span class="hamburger"></span>
</a>
</div>
</div>
@ -53,7 +55,7 @@
Copyright &copy; 2019-2021 by Hansi Reiser, DL9RDZ<br>
(version %VERSION_ID%)<br><br>
<a href="/update.html">Check for update (requires TTGO internet connection via WiFi)</a><br><br>
<a href="/upd.html">Check for update (requires TTGO internet connection via WiFi)</a><br><br>
with contributions by Vigor and Xavier (M20 support),
<a href="https://github.com/LukePrior">Luke Prior</a> and <a href="https://github.com/oh3bsg">OH3BSG</a> (SondeHub support),
@ -65,6 +67,8 @@
<br>
Autodetect info: %AUTODETECT_INFO%<br>
<br>
RS92 RINEX eph state: %EPHSTATE%<br>
<br>
This program is free software; you can redistribute it and/or
modify it under the terms of the GNU General Public License as
published by the Free Software Foundation; either version 2 of
@ -100,6 +104,17 @@ function selTab(evt, id) {
var iframe = act.getElementsByTagName("iframe")[0];
iframe.setAttribute("src", link);
}
var x = document.getElementById("myTopnav");
x.className = "topnav";
}
/* Toggle between adding and removing the "responsive" class to topnav when the user clicks on the icon */
function myFunction() {
var x = document.getElementById("myTopnav");
if (x.className === "topnav") {
x.className += " responsive";
} else {
x.className = "topnav";
}
}
document.getElementById("defaultTab").click();
</script>

Wyświetl plik

@ -1,3 +1,11 @@
try {
var check = $(document);
} catch (e) {
document.addEventListener("DOMContentLoaded", function(event) {
document.getElementById('map').innerHTML = '<br /><br />In order to use this functionality, there must be an internet connection.<br /><br/><a href="livemap.html">retry</a><br /><br/><a href="index.html">go back</a>';
});
}
$(document).ready(function(){
var map = L.map('map', { attributionControl: false, zoomControl: false });
@ -34,15 +42,15 @@ $(document).ready(function(){
map.setView([51.163361,10.447683], 5); // Mitte DE
var reddot = '<span class="ldot rbg"></span> ';
var yellowdot = '<span class="ldot ybg"></span> ';
var greendot = '<span class="ldot gbg"></span> ';
var reddot = '<span class="ldot rbg"></span>';
var yellowdot = '<span class="ldot ybg"></span>';
var greendot = '<span class="ldot gbg"></span>';
$('#map .leaflet-control-container').append(L.DomUtil.create('div', 'leaflet-top leaflet-center leaflet-header'));
var header = '';
header += '<div id="sonde_main"><b>rdzTTGOSonde LiveMap</b><br />🎈 <b><span id="sonde_id"></span> - <span id="sonde_freq"></span> MHz - <span id="sonde_type"></span></b></div>';
header += '<div id="sonde_detail"><span id="sonde_alt"></span>m | <span id="sonde_climb"></span>m/s | <span id="sonde_speed"></span>km/h</div>';
header += '<div id="sonde_status"><small><span id="sonde_statbar"></span></small></div>';
header += '<div id="sonde_status"><span id="sonde_statbar"></span></div>';
header += '<div id="settings"><br /><b>Prediction-Settings</b><br />';
header += '<label for="burst">Burst at:</label><input type="text" id="burst" maxlength="5" value="..." /> m<br />';
@ -61,7 +69,6 @@ $('.leaflet-footer').append(footer);
var statbar = '';
headtxt = function(data,stat) {
//var staticon = (stat == '1')?'🟢':'🟡';
var staticon = (stat == '1')?greendot:yellowdot;
statbar = staticon + statbar;
if ((statbar.length) > 10*greendot.length) { statbar = statbar.substring(0,10*greendot.length); }
@ -87,7 +94,7 @@ headtxt = function(data,stat) {
map.addControl(new L.Control.Button([ { position: 'topleft', text: '🗺️', href: 'javascript:basemap_change();' } ]));
map.addControl(new L.Control.Button([ { position: 'topright', id: "status", text: '🔴', href: 'javascript:get_data();' } ]));
map.addControl(new L.Control.Button([ { position: 'topright', id: "status", text: '', href: 'javascript:get_data();' } ]));
map.addControl(new L.Control.Button([
{ position:'topright', text: '🎈', href: 'javascript:show(marker,\'marker\');' },
@ -171,18 +178,15 @@ headtxt = function(data,stat) {
dots.push(location);
line.setLatLngs(dots);
storage_write(data);
//$('#status').html('🟢');
$('#status').html(greendot);
stat = 1;
} else {
//$('#status').html('🟡');
$('#status').html(yellowdot);
stat = 0;
}
headtxt(data,stat);
last_data = data;
} else {
//$('#status').html('🟡');
$('#status').html(yellowdot);
headtxt(data,0);
}
@ -225,14 +229,12 @@ headtxt = function(data,stat) {
};
get_data = function() {
//$('#status').html('🔴');
$('#status').html(reddot);
$.ajax({url: 'live.json', success: (function( data ) {
if (typeof data != "object") { data = $.parseJSON(data); }
if (data.sonde) {
draw(data.sonde);
} else {
//setTimeout(function() {$('#status').html('🟡');},100);
setTimeout(function() {$('#status').html(yellowdot);},100);
}
if (data.gps) {
@ -319,7 +321,7 @@ headtxt = function(data,stat) {
var datetime = m.getUTCFullYear() + "-" + az(m.getUTCMonth()+1) + "-" + az(m.getUTCDate()) + "T" +
az(m.getUTCHours()) + ":" + az(m.getUTCMinutes()) + ":" + az(m.getUTCSeconds()) + "Z";
var url = 'https://predict.cusf.co.uk/api/v1/';
url += '?launch_latitude='+data.lat + '&launch_longitude='+data.lon;
url += '?launch_latitude='+data.lat + '&launch_longitude='+fix_lon(data.lon);
url += '&launch_altitude='+data.alt + '&launch_datetime='+datetime;
url += '&ascent_rate='+ascent + '&burst_altitude=' + burst + '&descent_rate='+descent;
@ -331,11 +333,11 @@ headtxt = function(data,stat) {
draw_predict = function(prediction,data) {
var ascending = prediction.prediction[0].trajectory;
var highest = ascending[ascending.length-1];
var highest_location = [highest.latitude,highest.longitude];
var highest_location = [highest.latitude,fix_lon(highest.longitude)];
var descending = prediction.prediction[1].trajectory;
var landing = descending[descending.length-1];
var landing_location = [landing.latitude,landing.longitude];
var landing_location = [landing.latitude,fix_lon(landing.longitude)];
if (!marker_landing) {
marker_landing = L.marker(landing_location,{icon: icon_landing}).addTo(map)
@ -351,7 +353,7 @@ headtxt = function(data,stat) {
dots_predict=[];
if (data.climb > 0) {
ascending.forEach(p => dots_predict.push([p.latitude,p.longitude]));
ascending.forEach(p => dots_predict.push([p.latitude,fix_lon(p.longitude)]));
if (!marker_burst) {
marker_burst = L.marker(highest_location,{icon:icon_burst}).addTo(map).bindPopup(poptxt('burst',highest),{closeOnClick:false, autoPan:false});
@ -363,7 +365,7 @@ headtxt = function(data,stat) {
}
}
descending.forEach(p => dots_predict.push([p.latitude,p.longitude]));
descending.forEach(p => dots_predict.push([p.latitude,fix_lon(p.longitude)]));
line_predict.setLatLngs(dots_predict);
if (data.climb > 0) {
@ -376,6 +378,12 @@ headtxt = function(data,stat) {
clearTimeout(predictor);
predictor = setTimeout(function() {get_predict(last_data);}, predictor_time*1000);
};
fix_lon = function(lon) {
if (lon > 180) { return lon - 360; }
if (lon < 0) { return lon + 360; }
return lon;
};
poptxt = function(t,i) {
var lat_input = (i.id)?i.lat:i.latitude;

Wyświetl plik

@ -1,8 +1,6 @@
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');

Wyświetl plik

@ -4,6 +4,25 @@ body, html {
font-family: Arial;
}
.hamburger {
position: relative;
display: inline-block;
width: 1.25em;
height: 0.8em;
margin-right: 0.3em;
border-top: 0.2em solid #fff;
border-bottom: 0.2em solid #fff;
}
.hamburger:before {
content: "";
position: absolute;
top: 0.3em;
left: 0px;
width: 100%;
border-top: 0.2em solid #fff;
}
.wrapper {
height: 100%;
display: flex;
@ -32,29 +51,6 @@ td#sfreq {
background-color: #ccc;
}
.tab {
overflow: hidden;
border: 1px solid #ccc;
}
.tab button {
background-color: inherit;
float: left;
border: none;
outline: none;
cursor: pointer;
padding: 10px 10px;
width: 12vw;
transition: 0.3s;
}
.tab button:hover {
background-color: #ddd;
}
.tab button.active {
background-color: #ccc;
}
.content {
display: flex;
flex: 1;
@ -244,13 +240,88 @@ p{
}
.ldot {
height: 1em;
width: 1em;
height: 15px;
width: 15px;
margin-top: 8px;
margin-left: -1px;
border-radius: 50%;
display: inline-block;
}
.ybg { background-color: #E0E000; }
.gbg { background-color: green; }
.rbg { background-color: red; }
.ybg {
background-color: orange;
background-image: -webkit-gradient(linear, left top, left bottom, from(yellow), to(orange));
background-image: linear-gradient(top, yellow, orange);
}
.gbg {
background-color: green;
background-image: -webkit-gradient(linear, left top, left bottom, from(lime), to(green));
background-image: linear-gradient(top, lime, green);
}
.rbg {
background-color: red;
background-image: -webkit-gradient(linear, left top, left bottom, from(orange), to(red));
background-image: linear-gradient(top, orange, red);
}
#sonde_statbar .ldot {
margin-right: 3px;
}
/* Add a black background color to the top navigation */
.topnav {
background-color: #333;
overflow: hidden;
}
/* Style the links inside the navigation bar */
.topnav a {
float: left;
display: block;
color: #f2f2f2;
text-align: center;
padding: 14px 16px;
text-decoration: none;
font-size: 17px;
}
/* Change the color of links on hover */
.topnav a:hover {
background-color: #ddd;
color: black;
}
/* Add an active class to highlight the current page */
.topnav a.active {
background-color: #04AA6D;
color: white;
}
/* Hide the link that should open and close the topnav on small screens */
.topnav .icon {
display: none;
}
/* When the screen is less than 600 pixels wide, hide all links, except for the first one ("Home"). Show the link that contains should open and close the topnav (.icon) */
@media screen and (max-width: 600px) {
.topnav a:not(.active) {display: none;}
.topnav a.icon {
float: right;
display: block;
}
}
/* The "responsive" class is added to the topnav with JavaScript when the user clicks on the icon. This class makes the topnav look good on small screens (display the links vertically instead of horizontally) */
@media screen and (max-width: 600px) {
.topnav.responsive {position: relative;}
.topnav.responsive a.icon {
position: absolute;
right: 0;
top: 0;
}
.topnav.responsive a {
float: none;
display: block;
text-align: left;
}
}

Wyświetl plik

@ -0,0 +1,36 @@
<html><head>
<link rel="stylesheet" type="text/css" href="style.css">
</head>
<body>
<form action="update.html" method="post"><p>Currently installed: devel20210908-B14</p>
<p>
Available master: <span id="masterDiv">(...checking...)</span>
<br>
Available devel: <span id="develDiv">(...checking...)</span>
</p>
<input type="submit" name="master" value="Master-Update"></input><br>
<input type="submit" name="devel" value="Devel-Update"><br>
<p>Note: If suffix is the same, update should work fully. If the number is different, update contains changes in the file system. A full re-flash is required to get all new features, but the update should not break anything. If the letter is different, a full re-flash is mandatory, update will not work</p></form>
<script>
const masterInfo = document.getElementById('masterDiv');
const develInfo = document.getElementById('develDiv');
let request = new XMLHttpRequest();
request.open('GET', 'http://rdzsonde.mooo.com/master/update-info.html');
request.onload = function() {
masterInfo.innerHTML = request.response.replace(/<[^>]*>/g, '');
}
request.send();
let drequest = new XMLHttpRequest();
drequest.open('GET', 'http://rdzsonde.mooo.com/devel/update-info.html');
drequest.onload = function() {
develInfo.innerHTML= drequest.response.replace(/<[^>]*>/g, '');;
}
drequest.send();
</script>
</body></html>

Wyświetl plik

@ -23,8 +23,11 @@ static struct st_dfmstat {
uint8_t start[50];
uint16_t dat[50*2];
uint8_t cnt[50*2];
uint16_t good;
uint16_t msec;
uint8_t nameregok;
uint8_t nameregtop;
uint8_t lastdat;
} dfmstate;
int DFM::setup(float frequency, int type)
@ -60,36 +63,8 @@ int DFM::setup(float frequency, int type)
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;
}
sx1278.setPayloadLength(33); // Expect 33 bytes (7+13+13 bytes)
} else {
// DFM OLD support has been removed
{
// continuous mode
// Enable auto-AFC, auto-AGC, RX Trigger by preamble ????
if(sx1278.setRxConf(0x1E)!=0) {
@ -349,39 +324,10 @@ void DFM::finddfname(uint8_t *b)
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);
Serial.print("DFM-06 ID: "); Serial.print(lowid, HEX);
snprintf(sonde.si()->id, 10, "%x", lowid);
sonde.si()->validID = true;
}
if((cfg[0]>>4)==0x0A) { // DMF-9 ID
type=9;
if(cfg[3]==1) {
lowid = (cfg[1]<<8) | cfg[2];
idgood |= 1;
} else {
highid = (cfg[1]<<8) | cfg[2];
idgood |= 2;
}
if(idgood==3) {
uint32_t dfmid = (highid<<16) | lowid;
Serial.print("DFM-09 ID: "); Serial.print(dfmid);
snprintf(sonde.si()->ser, 10, "%d", dfmid);
// dxlAPRS sonde number (DF6 (why??) and 5 last digits of serial number as hex number
snprintf(sonde.si()->id, 9, "DF6%05X", dfmid&0xfffff);
sonde.si()->validID = true;
}
}
#endif
}
static int bitCount(int x) {
@ -396,19 +342,26 @@ uint16_t MON[]={0,0,31,59,90,120,151,181,212,243,273,304,334};
void DFM::decodeDAT(uint8_t *dat)
{
SondeInfo *si = sonde.si();
Serial.print(" DAT["); Serial.print(dat[6]); Serial.print("]: ");
// We can have a 8 and 0 subframe in a single frame. So do the reset only for dat>0
if( !(dat[6]==0 && dfmstate.lastdat==8) ) { // if we have DAT8 + DAT0, don't reset before returing the 8 frame...
if(dat[6] < dfmstate.lastdat) dfmstate.good = 0; // next iteration detected
}
dfmstate.lastdat = dat[6];
dfmstate.good |= (1<<dat[6]);
switch(dat[6]) {
case 0:
Serial.print("Packet counter: "); Serial.print(dat[3]);
sonde.si()->frame = dat[3];
si->frame = dat[3];
break;
case 1:
{
int val = (((uint16_t)dat[4])<<8) + (uint16_t)dat[5];
Serial.print("UTC-msec: "); Serial.print(val);
sonde.si()->sec = (val+500)/1000;
dfmstate.msec = val;
uint32_t tmp = ((uint32_t)dat[0]<<24) + ((uint32_t)dat[1]<<16) + ((uint32_t)dat[2]<<8) + ((uint32_t)dat[3]);
sonde.si()->sats = bitCount(tmp); // maybe!?!?!?
si->sats = bitCount(tmp);
}
break;
case 2:
@ -418,9 +371,9 @@ void DFM::decodeDAT(uint8_t *dat)
vh = ((uint16_t)dat[4]<<8) + dat[5];
Serial.print("GPS-lat: "); Serial.print(lat*0.0000001);
Serial.print(", hor-V: "); Serial.print(vh*0.01);
sonde.si()->lat = lat*0.0000001;
sonde.si()->hs = vh*0.01;
sonde.si()->validPos |= 0x11;
si->lat = lat*0.0000001;
si->hs = vh*0.01;
si->validPos |= 0x11;
}
break;
case 3:
@ -430,9 +383,9 @@ void DFM::decodeDAT(uint8_t *dat)
dir = ((uint16_t)dat[4]<<8) + dat[5];
Serial.print("GPS-lon: "); Serial.print(lon*0.0000001);
Serial.print(", dir: "); Serial.print(dir*0.01);
sonde.si()->lon = lon*0.0000001;
sonde.si()->dir = dir*0.01;
sonde.si()->validPos |= 0x42;
si->lon = lon*0.0000001;
si->dir = dir*0.01;
si->validPos |= 0x42;
}
break;
case 4:
@ -442,9 +395,9 @@ void DFM::decodeDAT(uint8_t *dat)
vv = (int16_t)( ((int16_t)dat[4]<<8) | dat[5] );
Serial.print("GPS-height: "); Serial.print(alt*0.01);
Serial.print(", vv: "); Serial.print(vv*0.01);
sonde.si()->alt = alt*0.01;
sonde.si()->vs = vv*0.01;
sonde.si()->validPos |= 0x0C;
si->alt = alt*0.01;
si->vs = vv*0.01;
si->validPos |= 0x0C;
}
break;
case 8:
@ -461,7 +414,14 @@ void DFM::decodeDAT(uint8_t *dat)
int tt = (y-1970)*365 + (y-1969)/4; // days since 1970
if(m<=12) { tt += MON[m]; if((y%4)==0 && m>2) tt++; }
tt = (tt+d-1)*(60*60*24) + h*3600 + mi*60;
sonde.si()->time = tt;
si->time = tt + dfmstate.msec/1000;
// Lets be consistent with autorx: the timestamp uses the msec value truncated to seconds,
// whereas the virtual frame number for DFM uses the msec value rounded to full seconds.
// Actually, tt is real UTC, and the transformation to GPS seconds lacks adjusting for leap seconds
si->vframe = tt + (dfmstate.msec+500)/1000 - 315964800;
// maybe TODO: if we missed the type 0 frame, we still might caculate the right seconds from system time.
// but we only send time stamps to external servers (in particular to sondehub), if all
// required frame types have been correctly decoded, so this does not matter much.
}
break;
default:
@ -538,19 +498,11 @@ int DFM::processDFMdata(uint8_t dt) {
}
int DFM::receive() {
if( stype == STYPE_DFM ) {
return receiveNew();
} else {
return receiveOld();
}
}
int rxframes = 5; // UP TO 5 frames, stop at type 8 frame
int DFM::receiveNew() {
int rxframes = 4;
// tentative continuous RX version...
unsigned long t0 = millis();
while( ( millis() - t0 ) < 1000 ) {
while( ( millis() - t0 ) < 1300 ) {
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2);
if ( bitRead(value, 7) ) {
Serial.println("FIFO full");
@ -570,50 +522,30 @@ int DFM::receiveNew() {
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);
Serial.printf("receive newframe: %d, good: %x\n", rxframes, dfmstate.good);
haveNewFrame = 0;
rxframes--;
if(rxframes==0) return RX_OK;
if(dfmstate.good & 0x100) {
if(dfmstate.good & 0x11E) {
dfmstate.good = 0; return RX_OK; // type 8 frame has been received
} else {
dfmstate.good = 0; return RX_ERROR;
}
}
if(rxframes==0) return RX_ERROR;
}
delay(2);
}
}
return rxframes == 4 ? RX_TIMEOUT : RX_OK;
}
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.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
if(!(stype==STYPE_DFM09_OLD)) { for(int i=0; i<33; i++) { data[i]^=0xFF; } }
decodeFrameDFM(data);
}
return RX_OK;
return rxframes == 5 ? RX_TIMEOUT : RX_OK;
}
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);
@ -637,22 +569,6 @@ int DFM::decodeFrameDFM(uint8_t *data) {
// moved to a single function in Sonde(). This function can be used for additional
// processing here, that takes too long for doing in the RX task loop
int DFM::waitRXcomplete() {
#if 0
int res=0;
uint32_t t0 = millis();
while( rxtask.receiveResult < 0 && millis()-t0 < 2000) { delay(50); }
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 = -1;
Serial.printf("waitRXcomplete returning %d\n", res);
return res;
#endif
return 0;
}

Wyświetl plik

@ -1,4 +1,4 @@
#include "../../RX_FSK/features.h"
#include "../features.h"
#include <U8x8lib.h>
#include <U8g2lib.h>
#include <SPIFFS.h>
@ -12,12 +12,13 @@ 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/Terminal11x16.h>
#include "fonts/FreeMono9pt7b.h"
#include "fonts/FreeMono12pt7b.h"
#include "fonts/FreeSans9pt7b.h"
#include "fonts/FreeSans12pt7b.h"
#include "fonts/FreeSans18pt7b.h"
#include "fonts/Picopixel.h"
#include "fonts/Terminal11x16.h"
extern Sonde sonde;
@ -36,10 +37,6 @@ struct GpsPos gpsPos;
//SPIClass spiDisp(HSPI);
const char *sondeTypeStr[NSondeTypes] = { "DFM ", "DFM9", "RS41", "RS92", "M10 ", "M20 ", "DFM6", "MP3H" };
const char *sondeTypeLongStr[NSondeTypes] = { "DFM (all)", "DFM9 (old)", "RS41", "RS92", "M10 ", "M20 ", "DFM6 (old)", "MP3-H1" };
const char sondeTypeChar[NSondeTypes] = { 'D', '9', '4', 'R', 'M', '2', '6', '3' };
byte myIP_tiles[8*11];
static uint8_t ap_tile[8]={0x00,0x04,0x22,0x92, 0x92, 0x22, 0x04, 0x00};
@ -256,11 +253,11 @@ void U8x8Display::getDispSize(uint8_t *height, uint8_t *width, uint8_t *lineskip
if(colskip) *colskip = 1;
}
void U8x8Display::drawString(uint8_t x, uint8_t y, const char *s, int16_t width, uint16_t fg, uint16_t bg) {
void U8x8Display::drawString(uint16_t x, uint16_t y, const char *s, int16_t width, uint16_t fg, uint16_t bg) {
u8x8->drawString(x, y, s);
}
void U8x8Display::drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr) {
void U8x8Display::drawTile(uint16_t x, uint16_t y, uint8_t cnt, uint8_t *tile_ptr) {
u8x8->drawTile(x, y, cnt, tile_ptr);
}
@ -282,7 +279,7 @@ void U8x8Display::welcome() {
}
static String previp;
void U8x8Display::drawIP(uint8_t x, uint8_t y, int16_t width, uint16_t fg, uint16_t bg) {
void U8x8Display::drawIP(uint16_t x, uint16_t y, int16_t width, uint16_t fg, uint16_t bg) {
if(!previp.equals(sonde.ipaddr)) {
// ip address has changed
// create tiles
@ -309,7 +306,7 @@ void U8x8Display::drawIP(uint8_t x, uint8_t y, int16_t width, uint16_t fg, uint1
}
// len must be multiple of 2, size is fixed for u8x8 display
void U8x8Display::drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t /*size*/, uint8_t *stat, uint16_t fg, uint16_t bg) {
void U8x8Display::drawQS(uint16_t x, uint16_t y, uint8_t len, uint8_t /*size*/, uint8_t *stat, uint16_t fg, uint16_t bg) {
for(int i=0; i<len; i+=2) {
uint8_t tile[8];
*(uint32_t *)(&tile[0]) = *(uint32_t *)(&(stattiles[stat[i]]));
@ -325,6 +322,7 @@ const GFXfont *gfl[] = {
&FreeSans9pt7b, // 5
&FreeSans12pt7b, // 6
&Picopixel, // 7
&FreeSans18pt7b, // 8
};
struct gfxoffset_t {
uint8_t yofs, yclear;
@ -338,6 +336,7 @@ const struct gfxoffset_t gfxoffsets[]={
{ 13, 18 }, // 17+13-12 "j"
{ 17, 23 }, // 23+17-17
{ 4, 6}, // 6+4-4
{ 25, 34 }, // 34 25 -25
};
static int ngfx = sizeof(gfl)/sizeof(GFXfont *);
@ -422,7 +421,7 @@ 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) {
void ILI9225Display::drawString(uint16_t x, uint16_t y, const char *s, int16_t width, uint16_t fg, uint16_t bg) {
int16_t w,h;
boolean alignright=false;
if(width<0) {
@ -540,7 +539,7 @@ void ILI9225Display::drawString(uint8_t x, uint8_t y, const char *s, int16_t wid
SPI_MUTEX_UNLOCK();
}
void ILI9225Display::drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr) {
void ILI9225Display::drawTile(uint16_t x, uint16_t y, uint8_t cnt, uint8_t *tile_ptr) {
int i,j;
SPI_MUTEX_LOCK();
tft->startWrite();
@ -553,20 +552,6 @@ void ILI9225Display::drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_p
}
tft->endWrite();
SPI_MUTEX_UNLOCK();
#if 0
int i,j;
tft->startWrite();
for(int i=0; i<cnt*8; i++) {
uint8_t v = tile_ptr[i];
for(j=0; j<8; j++) {
tft->drawPixel(8*x+i, 8*y+j, (v&0x01) ? COLOR_GREEN:COLOR_BLUE);
v >>= 1;
}
}
tft->endWrite();
//tft->drawBitmap(x*8, y*8, tile_ptr, cnt*8, 8, COLOR_RED, COLOR_BLUE);
//???u8x8->drawTile(x, y, cnt, tile_ptr);
#endif
}
void ILI9225Display::drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color, boolean fill) {
@ -603,7 +588,7 @@ void ILI9225Display::welcome() {
drawString(0, l+2*22, "by Hansi, DL9RDZ");
}
void ILI9225Display::drawIP(uint8_t x, uint8_t y, int16_t width, uint16_t fg, uint16_t bg) {
void ILI9225Display::drawIP(uint16_t x, uint16_t y, int16_t width, uint16_t fg, uint16_t bg) {
char buf[20];
if(sonde.isAP) strcpy(buf, "A "); else *buf=0;
strncat(buf, sonde.ipaddr.c_str(), 16);
@ -611,7 +596,7 @@ void ILI9225Display::drawIP(uint8_t x, uint8_t y, int16_t width, uint16_t fg, ui
}
// size: 3=> 3x5 symbols; 4=> 4x7 symbols
void ILI9225Display::drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg, uint16_t bg) {
void ILI9225Display::drawQS(uint16_t x, uint16_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg, uint16_t bg) {
if(size<3) size=3;
if(size>4) size=4;
const uint16_t width = len*(size+1);
@ -638,7 +623,7 @@ void ILI9225Display::drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t size, uin
#if 1
#else
// TO BE REMOVED
void MY_ILI9225::drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr) {
void MY_ILI9225::drawTile(uint16_t x, uint16_t y, uint8_t cnt, uint8_t *tile_ptr) {
int i,j;
startWrite();
for(i=0; i<cnt*8; i++) {
@ -828,8 +813,9 @@ void Display::parseDispElement(char *text, DispEntry *de)
// IP address / small always uses tiny font on TFT for backward compatibility
// Large font can be used arbitrarily
if(de->fmt==fontsma) de->fmt=0;
de->func = disp.drawIP; break;
de->func = disp.drawIP;
de->extra = strdup(text+1);
break;
case 's':
de->func = disp.drawSite;
de->extra = strdup(text+1);
@ -1082,11 +1068,6 @@ void Display::initFromFile(int index) {
what++;
newlayouts[idx].de[what].func = NULL;
} else {
#if 0
for(int i=0; i<12; i++) {
Serial.printf("action %d: %d\n", i, (int)newlayouts[idx].actions[i]);
}
#endif
what=-1;
}
break;
@ -1562,8 +1543,20 @@ void Display::drawGPS(DispEntry *de) {
void Display::drawBatt(DispEntry *de) {
float val;
char buf[30];
if(!axp192_found) return;
if (!axp192_found) {
if (sonde.config.batt_adc<0) return;
switch (de->extra[0])
{
case 'V':
val = (float)(analogRead(sonde.config.batt_adc)) / 4095 * 2 * 3.3 * 1.1;
snprintf(buf, 30, "%.2f%s", val, de->extra + 1);
break;
default:
*buf = 0;
}
rdis->setFont(de->fmt);
drawString(de, buf);
} else {
xSemaphoreTake( axpSemaphore, portMAX_DELAY );
switch(de->extra[0]) {
case 'S':
@ -1604,6 +1597,7 @@ void Display::drawBatt(DispEntry *de) {
xSemaphoreGive( axpSemaphore );
rdis->setFont(de->fmt);
drawString(de, buf);
}
}
void Display::drawText(DispEntry *de) {

Wyświetl plik

@ -63,13 +63,13 @@ public:
virtual void clear() = 0;
virtual void setFont(uint8_t fontindex) = 0;
virtual void getDispSize(uint8_t *height, uint8_t *width, uint8_t *lineskip, uint8_t *colskip) = 0;
virtual void drawString(uint8_t x, uint8_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0 ) = 0;
virtual void drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr) = 0;
virtual void drawString(uint16_t x, uint16_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0 ) = 0;
virtual void drawTile(uint16_t x, uint16_t y, uint8_t cnt, uint8_t *tile_ptr) = 0;
virtual void drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color, bool fill) = 0;
virtual void drawBitmap(uint16_t x1, uint16_t y1, const uint16_t* bitmap, int16_t w, int16_t h) = 0;
virtual void welcome() = 0;
virtual void drawIP(uint8_t x, uint8_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0 ) = 0;
virtual void drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0) = 0;
virtual void drawIP(uint16_t x, uint16_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0 ) = 0;
virtual void drawQS(uint16_t x, uint16_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0) = 0;
};
class U8x8Display : public RawDisplay {
@ -85,13 +85,13 @@ public:
void clear();
void setFont(uint8_t fontindex);
void getDispSize(uint8_t *height, uint8_t *width, uint8_t *lineskip, uint8_t *colskip);
void drawString(uint8_t x, uint8_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
void drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr);
void drawString(uint16_t x, uint16_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
void drawTile(uint16_t x, uint16_t y, uint8_t cnt, uint8_t *tile_ptr);
void drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color, bool fill);
void drawBitmap(uint16_t x1, uint16_t y1, const uint16_t* bitmap, int16_t w, int16_t h);
void welcome();
void drawIP(uint8_t x, uint8_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
void drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0);
void drawIP(uint16_t x, uint16_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
void drawQS(uint16_t x, uint16_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0);
};
typedef Arduino_GFX MY_ILI9225;
@ -109,13 +109,13 @@ public:
void clear();
void setFont(uint8_t fontindex);
void getDispSize(uint8_t *height, uint8_t *width, uint8_t *lineskip, uint8_t *colskip);
void drawString(uint8_t x, uint8_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
void drawTile(uint8_t x, uint8_t y, uint8_t cnt, uint8_t *tile_ptr);
void drawString(uint16_t x, uint16_t y, const char *s, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
void drawTile(uint16_t x, uint16_t y, uint8_t cnt, uint8_t *tile_ptr);
void drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color, bool fill);
void drawBitmap(uint16_t x1, uint16_t y1, const uint16_t* bitmap, int16_t w, int16_t h);
void welcome();
void drawIP(uint8_t x, uint8_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
void drawQS(uint8_t x, uint8_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0);
void drawIP(uint16_t x, uint16_t y, int16_t width=WIDTH_AUTO, uint16_t fg=0xffff, uint16_t bg=0);
void drawQS(uint16_t x, uint16_t y, uint8_t len, uint8_t size, uint8_t *stat, uint16_t fg=0xffff, uint16_t bg=0);
};
class Display {
@ -137,8 +137,8 @@ private:
static const char *trim(char *s) {
char *ret = s;
while(*ret && isspace(*ret)) { ret++; }
int lastidx;
while(1) {
int lastidx;
lastidx = strlen(ret)-1;
if(lastidx>=0 && isspace(ret[lastidx]))
ret[lastidx] = 0;

Wyświetl plik

@ -280,6 +280,7 @@ int M10M20::decodeframeM10(uint8_t *data) {
if(data[1]==0x9F && data[2]==0x20) {
Serial.println("Decoding...");
SondeInfo *si = sonde.si();
// Its a M10
// getid...
char ids[12];
@ -308,23 +309,23 @@ int M10M20::decodeframeM10(uint8_t *data) {
ids[9] = dez((id/10)%10);
ids[10] = dez(id%10);
ids[11] = 0;
strncpy(sonde.si()->ser, ids, 12);
sonde.si()->validID = true;
strncpy(si->ser, ids, 12);
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;
si->lat = getint32(data+14) * DEGMUL;
si->lon = getint32(data+18) * DEGMUL;
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);
sonde.si()->sats = data[30];
si->vs = getint16(data+8) * VMUL;
si->hs = sqrt(ve*ve+vn*vn);
si->sats = data[30];
float dir = atan2(ve, vn)*(1.0/RAD);
if(dir<0) dir+=360;
sonde.si()->dir = dir;
sonde.si()->validPos = 0x3f;
si->dir = dir;
si->validPos = 0x3f;
uint32_t gpstime = getint32(data+10);
uint16_t gpsweek = getint16(data+32);
@ -333,8 +334,11 @@ int M10M20::decodeframeM10(uint8_t *data) {
// 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;
si->time = (gpstime/1000) + 86382 + gpsweek*604800 + 315878400UL;
// consistent with autorx, vframe is based on GPS time without the -18 seconds adjustment
// for the GPS time / UTC time difference (included in 86382 above)
si->vframe = si->time - 315964800 + 18;
si->validTime = true;
} else {
Serial.printf("data is %02x %02x %02x\n", data[0], data[1], data[2]);
return 0;
@ -460,20 +464,6 @@ int M10M20::waitRXcomplete() {
}
#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) {
@ -482,6 +472,7 @@ int M10M20::decodeframeM20(uint8_t *data) {
int repl = 0;
bool crcok = false;
bool crcbok = false;
SondeInfo *si = sonde.si();
// error correction, inspired by oe5dxl's sondeudp
// check first block
uint8_t s[200];
@ -532,9 +523,9 @@ int M10M20::decodeframeM20(uint8_t *data) {
ids[6] = (char)((id/100)%10+48);
ids[7] = (char)((id/10)%10+48);
ids[8] = (char)(id%10+48);
strncpy(sonde.si()->id, ids, 10);
strncpy(si->id, ids, 10);
// Serial: AAB-C-DDEEE
char *ser = sonde.si()->ser;
char *ser = si->ser;
uint8_t tmp = data[18] & 0x7F;
ser[0] = (tmp/12) + '0';
ser[1] = ((tmp%12 + 1) / 10 ) + '0';
@ -551,96 +542,39 @@ int M10M20::decodeframeM20(uint8_t *data) {
// TODO
if(crcok) {
sonde.si()->validID = true;
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;
si->lat = getint32(data+28) * 1e-6;
//0x20 4 byte
sonde.si()->lon = getint32(data+32) * 1e-6;
si->lon = getint32(data+32) * 1e-6;
//0x08 3 byte
sonde.si()->alt = getint24(data+8) * VMUL_M20;
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);
si->vs = getint16(data+24) * VMUL_M20;
si->hs = sqrt(ve*ve+vn*vn);
float dir = atan2(ve, vn)*(1.0/RAD);
if(dir<0) dir+=360;
sonde.si()->dir = dir;
sonde.si()->validPos = 0x3f;
si->dir = dir;
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;
si->time = (tow+week*604800+315964800)-18;
si->vframe = sonde.si()->time - 315964800;
sonde.si()->validTime = true;
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

@ -62,46 +62,6 @@ int MP3H::setup(float frequency)
return 1;
}
#if 0
/// 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) {
MP3H_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();
MP3H_DBG(Serial.printf("MP3H::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("MP3H::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....
}
#endif
//// Step 2: Real reception
// FSK standby mode, seems like otherweise baudrate cannot be changed?
sx1278.setFSK();
@ -298,6 +258,7 @@ static void getmp3htime(uint8_t *buf) {
}
tt += gpstime;
si->time = tt;
si->vframe = tt - 315964800;
Serial.printf(" mp3h TIMESTAMP: %d\n", tt);
}
@ -358,7 +319,7 @@ int MP3H::decodeframeMP3H(uint8_t *data) {
si->id[7] = hex(n/0x10);
si->id[8] = hex(n);
si->id[9] = 0;
snprintf(si->ser, 12, "%d-%d", mp3hstate.id1, mp3hstate.id2);
snprintf(si->ser, 12, "%u-%u", mp3hstate.id1, mp3hstate.id2);
si->validID = true;
}

Wyświetl plik

@ -17,18 +17,6 @@
static byte data[800];
static int dpos = 0;
#if 0
// subframe is never used?
static byte subframe[51*16]; // 816 subframe bytes
// this is moved to sondeInfo->extra
static bool subframeReceived[51] = { false }; // do we have data for row
static bool subframeComplete = false; // is the subframe complete
// this is needed only locally, use a local variable on stack for that
static bool validExternalTemperature = false; // have received all the calibration frames for the external temperature
static bool validHumidity = false; // have received all the calibration frames for the humidity
static bool validRAExternalTemperature = false; // have received all the calibration frames for the external temperature
static bool validRAHumidity = false; // have received all the calibration frames for the humidity
#endif
// whole 51 row frame as C structure
// taken from https://github.com/einergehtnochrein/ra-firmware
@ -686,7 +674,7 @@ int RS41::decode41(byte *data, int maxlen)
Serial.print("#");
uint16_t fnr = data[p]+(data[p+1]<<8);
Serial.print(fnr);
sonde.si()->frame = fnr;
sonde.si()->vframe = sonde.si()->frame = fnr;
Serial.print("; RS41 ID ");
snprintf(buf, 10, "%.8s ", data+p+2);
Serial.print(buf);
@ -715,13 +703,6 @@ int RS41::decode41(byte *data, int maxlen)
sonde.si()->countKT = cntdown;
sonde.si()->crefKT = fnr;
}
#if 0
// process this subframe
int subframeOffset = 24; // 24 = 0x18, start of subframe data
byte receivedBytes[16];
memcpy( receivedBytes, data+p+subframeOffset, 16);
ProcessSubframe( receivedBytes, calnr );
#endif
ProcessSubframe( data+p+24, calnr );
}
@ -754,9 +735,11 @@ int RS41::decode41(byte *data, int maxlen)
uint32_t tempHumiMain = getint24(data, 560, p+18);
uint32_t tempHumiRef1 = getint24(data, 560, p+21);
uint32_t tempHumiRef2 = getint24(data, 560, p+24);
#if 0
uint32_t pressureMain = getint24(data, 560, p+27);
uint32_t pressureRef1 = getint24(data, 560, p+30);
uint32_t pressureRef2 = getint24(data, 560, p+33);
#endif
#if 0
Serial.printf( "External temp: tempMeasMain = %ld, tempMeasRef1 = %ld, tempMeasRef2 = %ld\n", tempMeasMain, tempMeasRef1, tempMeasRef2 );
Serial.printf( "Rel Humidity: humidityMain = %ld, humidityRef1 = %ld, humidityRef2 = %ld\n", humidityMain, humidityRef1, humidityRef2 );
@ -856,22 +839,6 @@ int RS41::receive() {
int RS41::waitRXcomplete() {
// Currently not used. can be used for additinoal post-processing
// (required for RS92 to avoid FIFO overrun in rx task)
#if 0
int res;
uint32_t t0 = millis();
while(rxtask.receiveResult<0 && millis()-t0 < 3000) { delay(50); }
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 = -1;
Serial.printf("waitRXcomplete returning %d\n", res);
return res;
#endif
return 0;
}

Wyświetl plik

@ -25,6 +25,7 @@ private:
void bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);
int decode41(byte *data, int maxlen);
#if 0
#define B 8
#define S 4
uint8_t hamming_conf[ 7*B]; // 7*8=56
@ -41,6 +42,7 @@ private:
{ 1, 1, 0, 1, 0, 0, 1, 0},
{ 1, 1, 1, 0, 0, 0, 0, 1}};
uint8_t He[8] = { 0x7, 0xB, 0xD, 0xE, 0x8, 0x4, 0x2, 0x1}; // Spalten von H:
#endif
// 1-bit-error-Syndrome
boolean initialized = false;

Wyświetl plik

@ -17,7 +17,6 @@
#define RS92_DBG(x)
#endif
//static uint16_t CRCTAB[256];
uint16_t *CRCTAB = NULL;
#define X2C_DIVR(a, b) ((b) != 0.0f ? (a)/(b) : (a))
@ -39,27 +38,6 @@ static uint32_t X2C_LSH(uint32_t a, int32_t length, int32_t n)
return (a >> -n) & m;
}
#if 0
static double atang2(double x, double y)
{
double w;
if (fabs(x)>fabs(y)) {
w = (double)atan((float)(X2C_DIVL(y,x)));
if (x<0.0) {
if (y>0.0) w = 3.1415926535898+w;
else w = w-3.1415926535898;
}
}
else if (y!=0.0) {
w = (double)(1.5707963267949f-atan((float)(X2C_DIVL(x,
y))));
if (y<0.0) w = w-3.1415926535898;
}
else w = 0.0;
return w;
} /* end atang2() */
#endif
static void Gencrctab(void)
{
uint16_t j;
@ -196,19 +174,6 @@ int RS92::setup(float frequency)
return res;
}
#if 0
int RS92::setFrequency(float frequency) {
Serial.print("RS92: 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
uint32_t RS92::bits2val(const uint8_t *bits, int len) {
uint32_t val = 0;
for (int j = 0; j < len; j++) {
@ -448,34 +413,6 @@ void RS92::printRaw(uint8_t *data, int len)
Serial.println();
}
#if 0
// I guess this is old copy&paste stuff from RS41??
int RS92::bitsToBytes(uint8_t *bits, uint8_t *bytes, int len)
{
int i;
for(i=0; i<len*4; i++) {
bytes[i/8] = (bytes[i/8]<<1) | (bits[i]?1:0);
}
bytes[(i-1)/8] &= 0x0F;
}
static unsigned char lookup[16] = {
0x0, 0x8, 0x4, 0xc, 0x2, 0xa, 0x6, 0xe,
0x1, 0x9, 0x5, 0xd, 0x3, 0xb, 0x7, 0xf, };
static uint8_t reverse(uint8_t n) {
return (lookup[n&0x0f] << 4) | lookup[n>>4];
}
static uint8_t scramble[64] = {150U,131U,62U,81U,177U,73U,8U,152U,50U,5U,89U,
14U,249U,68U,198U,38U,33U,96U,194U,234U,121U,93U,109U,161U,
84U,105U,71U,12U,220U,232U,92U,241U,247U,118U,130U,127U,7U,
153U,162U,44U,147U,124U,48U,99U,245U,16U,46U,97U,208U,188U,
180U,182U,6U,170U,244U,35U,120U,110U,59U,174U,191U,123U,76U,
193U};
#endif
void RS92::stobyte92(uint8_t b)
{
@ -626,102 +563,14 @@ int RS92::waitRXcomplete() {
memcpy(si->id, gpx.id, 9);
memcpy(si->ser, gpx.id, 9);
si->validID = true;
si->frame = gpx.frnr;
si->vframe = si->frame = gpx.frnr;
si->sats = gpx.k;
si->time = (gpx.gpssec/1000) + 86382 + gpx.week*604800 + 315878400UL;
si->validTime = true;
#if 0
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("RS92::waitRXcomplete returning %d (%s)\n", res, RXstr[res]);
return res;
#endif
return 0;
}
#if 0
int oldwaitRXcomplete() {
Serial.println("RS92: 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, RS92MAXLEN);
//for(int i=0; i<RS92MAXLEN; i++) { data[i] = reverse(data[i]); }
//printRaw(data, MAXLEN);
//for(int i=0; i<RS92MAXLEN; i++) { data[i] = data[i] ^ scramble[i&0x3F]; }
//printRaw(data, MAXLEN);
//int res = decode41(data, RS92MAXLEN);
#endif
int res=0;
return res==0 ? RX_OK : RX_ERROR;
}
#endif
RS92 rs92 = RS92();

Wyświetl plik

@ -55,11 +55,6 @@ private:
void process8N1data(uint8_t data);
void stobyte92(uint8_t byte);
void decodeframe92(uint8_t *data);
#if 0
void dogps(const uint8_t *sf, int sf_len,
struct CONTEXTR9 * cont, uint32_t * timems,
uint32_t * gpstime);
#endif
uint32_t bits2val(const uint8_t *bits, int len);
void printRaw(uint8_t *data, int len);
int bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);

Wyświetl plik

@ -11,8 +11,8 @@
#include "SX1278FSK.h"
#include "SPI.h"
#include <Sonde.h>
#include <Display.h>
#include "Sonde.h"
#include "Display.h"
#define SPI_MUTEX_LOCK() \
@ -667,7 +667,7 @@ int8_t SX1278FSK::setMaxCurrent(uint8_t rate)
// Enable Over Current Protection
rate |= B00100000;
state = 1;
//state = 1;
st0 = readRegister(REG_OP_MODE); // Save the previous status
writeRegister(REG_OP_MODE, FSK_STANDBY_MODE); // Set FSK Standby mode to write in registers
writeRegister(REG_OCP, rate); // Modifying maximum current supply

Wyświetl plik

@ -1,7 +1,8 @@
#include "Scanner.h"
#include <SX1278FSK.h>
#include <U8x8lib.h>
#include "SX1278FSK.h"
#include "Sonde.h"
#include "Display.h"

Wyświetl plik

@ -21,7 +21,10 @@ const char *evstring[]={"NONE", "KEY1S", "KEY1D", "KEY1M", "KEY1L", "KEY2S", "KE
const char *RXstr[]={"RX_OK", "RX_TIMEOUT", "RX_ERROR", "RX_UNKNOWN"};
// Dependency to enum SondeType
const char *manufacturer_string[]={"Graw", "Graw", "Vaisala", "Vaisala", "Meteomodem", "Meteomodem", "Graw", "Meteo-Radiy"};
const char *sondeTypeStr[NSondeTypes] = { "DFM ", "RS41", "RS92", "M10 ", "M20 ", "MP3H" };
const char *sondeTypeLongStr[NSondeTypes] = { "DFM (all)", "RS41", "RS92", "M10 ", "M20 ", "MP3-H1" };
const char sondeTypeChar[NSondeTypes] = { 'D', '4', 'R', 'M', '2', '3' };
const char *manufacturer_string[]={"Graw", "Vaisala", "Vaisala", "Meteomodem", "Meteomodem", "Meteo-Radiy"};
int fingerprintValue[]={ 17, 31, 64, 4, 55, 48, 23, 128+23, 119, 128+119, -1 };
const char *fingerprintText[]={
@ -86,6 +89,7 @@ void Sonde::defaultConfig() {
// Seems like on startup, GPIO4 is 1 on v1 boards, 0 on v2.1 boards?
config.gps_rxd = -1;
config.gps_txd = -1;
config.batt_adc = -1;
config.sx1278_ss = SS; // default SS pin, on all TTGOs
config.sx1278_miso = MISO;
config.sx1278_mosi = MOSI;
@ -122,6 +126,11 @@ void Sonde::defaultConfig() {
#define BM8563_ADDRESS 0x51
Wire.beginTransmission(BM8563_ADDRESS);
byte err = Wire.endTransmission();
if(err) { // try again
delay(400);
Wire.beginTransmission(BM8563_ADDRESS);
err = Wire.endTransmission();
}
if(err==0) {
Serial.println("M5stack Core2 board detected\n");
config.type = TYPE_M5_CORE2;
@ -194,20 +203,21 @@ void Sonde::defaultConfig() {
}
}
} else {
// Likely a TTGO V2.1_1.6
config.button_pin = 2 + 128; // GPIO2 / T2
config.button2_pin = 14 + 128; // GPIO14 / T6
config.led_pout = 25;
config.batt_adc = 35;
}
}
//
config.noisefloor = -125;
strcpy(config.call,"NOCALL");
strcpy(config.passcode, "---");
config.passcode = -1;
strcpy(config.mdnsname, "rdzsonde");
config.maxsonde=15;
config.debug=0;
config.wifi=1;
config.wifiap=1;
config.display[0]=0;
config.display[1]=1;
config.display[2]=-1;
@ -250,6 +260,9 @@ void Sonde::defaultConfig() {
strcpy(config.mqtt.prefix, "rdz_sonde_server/");
}
extern struct st_configitems config_list[];
extern const int N_CONFIG;
void Sonde::setConfig(const char *cfg) {
while(*cfg==' '||*cfg=='\t') cfg++;
if(*cfg=='#') return;
@ -259,178 +272,59 @@ void Sonde::setConfig(const char *cfg) {
*s=0; s--;
while(s>cfg && (*s==' '||*s=='\t')) { *s=0; s--; }
Serial.printf("configuration option '%s'=%s \n", cfg, val);
if(strcmp(cfg,"noisefloor")==0) {
config.noisefloor = atoi(val);
if(config.noisefloor==0) config.noisefloor=-130;
} else if(strcmp(cfg,"call")==0) {
strncpy(config.call, val, 9);
config.call[9]=0;
} else if(strcmp(cfg,"passcode")==0) {
strncpy(config.passcode, val, 9);
} else if(strcmp(cfg,"button_pin")==0) {
config.button_pin = atoi(val);
} else if(strcmp(cfg,"button2_pin")==0) {
config.button2_pin = atoi(val);
} else if(strcmp(cfg,"button2_axp")==0) {
config.button2_axp = atoi(val);
} else if(strcmp(cfg,"touch_thresh")==0) {
config.touch_thresh = atoi(val);
} else if(strcmp(cfg,"led_pout")==0) {
config.led_pout = atoi(val);
} else if(strcmp(cfg,"power_pout")==0) {
config.power_pout = atoi(val);
} else if(strcmp(cfg,"disptype")==0) {
config.disptype = atoi(val);
} else if(strcmp(cfg,"oled_sda")==0) {
config.oled_sda = atoi(val);
} else if(strcmp(cfg,"oled_scl")==0) {
config.oled_scl = atoi(val);
} else if(strcmp(cfg,"oled_rst")==0) {
config.oled_rst = atoi(val);
} else if(strcmp(cfg,"tft_rs")==0) {
config.tft_rs = atoi(val);
} else if(strcmp(cfg,"tft_cs")==0) {
config.tft_cs = atoi(val);
} else if(strcmp(cfg,"tft_orient")==0) {
config.tft_orient = atoi(val);
} else if(strcmp(cfg,"tft_spifreq")==0) {
config.tft_spifreq = atoi(val);
} else if(strcmp(cfg,"gps_rxd")==0) {
config.gps_rxd = atoi(val);
} else if(strcmp(cfg,"gps_txd")==0) {
config.gps_txd = atoi(val);
} else if(strcmp(cfg,"sx1278_ss")==0) {
config.sx1278_ss = atoi(val);
} else if(strcmp(cfg,"sx1278_miso")==0) {
config.sx1278_miso = atoi(val);
} else if(strcmp(cfg,"sx1278_mosi")==0) {
config.sx1278_mosi = atoi(val);
} else if(strcmp(cfg,"sx1278_sck")==0) {
config.sx1278_sck = atoi(val);
} else if(strcmp(cfg,"maxsonde")==0) {
config.maxsonde = atoi(val);
if(config.maxsonde>MAXSONDE) config.maxsonde=MAXSONDE;
} else if(strcmp(cfg,"debug")==0) {
config.debug = atoi(val);
} else if(strcmp(cfg,"wifi")==0) {
config.wifi = atoi(val);
} else if(strcmp(cfg,"wifiap")==0) {
config.wifiap = atoi(val);
} else if(strcmp(cfg,"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;
while(val) {
ptr = strchr(val,',');
if(ptr) *ptr = 0;
config.display[i++] = atoi(val);
val = ptr?ptr+1:NULL;
Serial.printf("appending value %d next is %s\n", config.display[i-1], val?val:"");
// new code: use config_list to find config entry...
int i;
for(i=0; i<N_CONFIG; i++) {
if(strcmp(cfg, config_list[i].name)!=0) continue;
if(config_list[i].type>0) { // string with that length
strlcpy((char *)config_list[i].data, val, config_list[i].type+1);
break;
}
switch(config_list[i].type) {
case 0: // integer
case -4: // integer (with "touch button" checkbox in web form)
case -3: // integer (boolean on/off swith in web form)
case -2: // integer (ID type)
*(int *)config_list[i].data = atoi(val);
if(config.maxsonde > MAXSONDE) config.maxsonde = MAXSONDE;
break;
case -7: // double
*(double *)config_list[i].data = *val==0 ? NAN : atof(val);
break;
case -6: // display list
{
int idx = 0;
char *ptr;
while(val) {
ptr = strchr(val,',');
if(ptr) *ptr = 0;
config.display[idx++] = atoi(val);
val = ptr?ptr+1:NULL;
Serial.printf("appending value %d next is %s\n", config.display[idx-1], val?val:"");
}
config.display[idx] = -1;
break;
}
config.display[i] = -1;
} else if (strcmp(cfg, "norx_timeout")==0) {
config.norx_timeout = atoi(val);
} else if(strcmp(cfg,"startfreq")==0) {
config.startfreq = atoi(val);
} else if(strcmp(cfg,"channelbw")==0) {
config.channelbw = atoi(val);
} else if(strcmp(cfg,"spectrum")==0) {
config.spectrum = atoi(val);
} else if(strcmp(cfg,"marker")==0) {
config.marker = atoi(val);
} else if(strcmp(cfg,"freqofs")==0) {
config.freqofs = atoi(val);
} else if(strcmp(cfg,"rs41.agcbw")==0) {
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,"mp3h.agcbw")==0) {
config.mp3h.agcbw = atoi(val);
} else if(strcmp(cfg,"mp3h.rxbw")==0) {
config.mp3h.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) {
config.kisstnc.idformat = atoi(val);
} else if(strcmp(cfg,"rs92.rxbw")==0) {
config.rs92.rxbw = atoi(val);
} else if(strcmp(cfg,"axudp.active")==0) {
config.udpfeed.active = atoi(val)>0;
} else if(strcmp(cfg,"axudp.host")==0) {
strncpy(config.udpfeed.host, val, 63);
} else if(strcmp(cfg,"axudp.port")==0) {
config.udpfeed.port = atoi(val);
} else if(strcmp(cfg,"axudp.symbol")==0) {
strncpy(config.udpfeed.symbol, val, 3);
} else if(strcmp(cfg,"axudp.highrate")==0) {
config.udpfeed.highrate = atoi(val);
} else if(strcmp(cfg,"axudp.idformat")==0) {
config.udpfeed.idformat = atoi(val);
} else if(strcmp(cfg,"tcp.active")==0) {
config.tcpfeed.active = atoi(val)>0;
} else if(strcmp(cfg,"tcp.host")==0) {
strncpy(config.tcpfeed.host, val, 63);
} else if(strcmp(cfg,"tcp.port")==0) {
config.tcpfeed.port = atoi(val);
} else if(strcmp(cfg,"tcp.symbol")==0) {
strncpy(config.tcpfeed.symbol, val, 3);
} else if(strcmp(cfg,"tcp.highrate")==0) {
config.tcpfeed.highrate = atoi(val);
} else if(strcmp(cfg,"tcp.idformat")==0) {
config.tcpfeed.idformat = atoi(val);
} else 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 if(strcmp(cfg, "sondehub.active")==0) {
config.sondehub.active = atoi(val);
} else if(strcmp(cfg,"sondehub.chase")==0) {
config.sondehub.chase = atoi(val);
} else if(strcmp(cfg, "sondehub.host")==0) {
strncpy(config.sondehub.host, val, 63);
} else if(strcmp(cfg, "sondehub.callsign")==0) {
strncpy(config.sondehub.callsign, val, 63);
} else if(strcmp(cfg, "sondehub.lat")==0) {
config.sondehub.lat = *val==0 ? NAN : atof(val);
Serial.printf("lat is %f\n", config.sondehub.lat);
} else if(strcmp(cfg, "sondehub.lon")==0) {
config.sondehub.lon = *val==0 ? NAN : atof(val);
Serial.printf("lon is %f\n", config.sondehub.lon);
} else if(strcmp(cfg, "sondehub.alt")==0) {
strncpy(config.sondehub.alt, val, 19);
} else if(strcmp(cfg, "sondehub.antenna")==0) {
strncpy(config.sondehub.antenna, val, 63);
} else if(strcmp(cfg, "sondehub.email")==0) {
strncpy(config.sondehub.email, val, 63);
} else {
default:
// skipping non-supported types
break;
}
break;
}
if(i==N_CONFIG) {
Serial.printf("Invalid config option '%s'=%s \n", cfg, val);
}
#if 0
// currently not in config_list. Maybe add later.
} else if(strcmp(cfg,"axudp.symbol")==0) {
strncpy(config.udpfeed.symbol, val, 3);
} else if(strcmp(cfg,"tcp.symbol")==0) {
strncpy(config.tcpfeed.symbol, val, 3);
}
#endif
}
void Sonde::setIP(String ip, bool AP) {
@ -447,6 +341,10 @@ void Sonde::addSonde(float frequency, SondeType type, int active, char *launchsi
return;
}
Serial.printf("Adding %f - %d - %d - %s\n", frequency, type, active, launchsite);
// reset all data if type or frequency has changed
if(type != sondeList[nSonde].type || frequency != sondeList[nSonde].freq) {
memset(&sondeList[nSonde], 0, sizeof(SondeInfo));
}
sondeList[nSonde].type = type;
sondeList[nSonde].typestr[0] = 0;
sondeList[nSonde].freq = frequency;
@ -517,8 +415,6 @@ void Sonde::setup() {
case STYPE_RS41:
rs41.setup(sondeList[rxtask.currentSonde].freq * 1000000);
break;
case STYPE_DFM06_OLD:
case STYPE_DFM09_OLD:
case STYPE_DFM:
dfm.setup( sondeList[rxtask.currentSonde].freq * 1000000, sondeList[rxtask.currentSonde].type );
break;
@ -559,8 +455,6 @@ void Sonde::receive() {
case STYPE_M20:
res = m10m20.receive();
break;
case STYPE_DFM06_OLD:
case STYPE_DFM09_OLD:
case STYPE_DFM:
res = dfm.receive();
break;
@ -659,8 +553,6 @@ rxloop:
case STYPE_M20:
m10m20.waitRXcomplete();
break;
case STYPE_DFM06_OLD:
case STYPE_DFM09_OLD:
case STYPE_DFM:
dfm.waitRXcomplete();
break;

Wyświetl plik

@ -53,14 +53,16 @@ extern const char *RXstr[];
// 01000000 => goto sonde -1
// 01000001 => goto sonde +1
#define NSondeTypes 8
enum SondeType { STYPE_DFM, STYPE_DFM09_OLD, STYPE_RS41, STYPE_RS92, STYPE_M10, STYPE_M20, STYPE_DFM06_OLD, STYPE_MP3H };
#define NSondeTypes 6
enum SondeType { STYPE_DFM, STYPE_RS41, STYPE_RS92, STYPE_M10, STYPE_M20, STYPE_MP3H };
extern const char *sondeTypeStr[NSondeTypes];
extern const char *sondeTypeLongStr[NSondeTypes];
extern const char sondeTypeChar[NSondeTypes];
extern const char *manufacturer_string[NSondeTypes];
#define TYPE_IS_DFM(t) ( (t)==STYPE_DFM || (t)==STYPE_DFM09_OLD || (t)==STYPE_DFM06_OLD )
#define ISOLED(cfg) ((cfg).disptype==0 || (cfg).disptype==2)
#define TYPE_IS_DFM(t) ( (t)==STYPE_DFM )
#define TYPE_IS_METEO(t) ( (t)==STYPE_M10 || (t)==STYPE_M20 )
typedef struct st_sondeinfo {
@ -86,8 +88,8 @@ typedef struct st_sondeinfo {
uint8_t validPos; // bit pattern for validity of above 7 fields; 0x80: position is old
// decoded GPS time
uint32_t time;
uint16_t sec;
uint32_t frame;
uint32_t vframe; // vframe==frame if frame is unique/continous, otherweise vframe is derived from gps time
bool validTime;
// RSSI from receiver
int rssi; // signal strength
@ -216,6 +218,7 @@ typedef struct st_rdzconfig {
int tft_spifreq; // SPI transfer speed (default 40M is out of spec for some TFT)
int gps_rxd; // GPS module RXD pin. We expect 9600 baud NMEA data.
int gps_txd; // GPS module TXD pin
int batt_adc; // Pin for ADC battery measurement (GPIO35 on TTGO V2.1_1.6)
int sx1278_ss; // SPI slave select for sx1278
int sx1278_miso; // SPI MISO for sx1278
int sx1278_mosi; // SPI MOSI for sx1278
@ -223,7 +226,6 @@ typedef struct st_rdzconfig {
// software configuration
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, ...)
@ -245,7 +247,7 @@ typedef struct st_rdzconfig {
// data feed configuration
// for now, one feed for each type is enough, but might get extended to more?
char call[10]; // APRS callsign
char passcode[9]; // APRS passcode
int passcode; // APRS passcode
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)
@ -254,6 +256,18 @@ typedef struct st_rdzconfig {
} RDZConfig;
struct st_configitems {
const char *name;
const char *label;
int type; // 0: numeric; i>0 string of length i; -1: separator; -2: type selector
void *data;
};
// defined in RX_FSK.ino
extern struct st_configitems config_list[];
extern const int N_CONFIG;
#define MAXSONDE 99
extern int fingerprintValue[];
@ -287,11 +301,6 @@ public:
void setup();
void receive();
uint16_t waitRXcomplete();
/* old and temp interface */
#if 0
void processRXbyte(uint8_t data);
int receiveFrame();
#endif
SondeInfo *si();

Wyświetl plik

@ -215,6 +215,7 @@ extern int aprsstr_mon2kiss(const char *mon, char raw[], int raw_len)
if(len==0) return 0;
int idx=0;
raw[idx++] = '\xC0';
raw[idx++] = 0; // channel 0
for(int i=0; i<len-2; i++) { // -2: discard CRC, not used in KISS
if(tmp[i]=='\xC0') {
raw[idx++] = '\xDB';
@ -234,28 +235,11 @@ extern int aprsstr_mon2kiss(const char *mon, char raw[], int raw_len)
#define FEET (1.0/0.3048)
#define KNOTS (1.851984)
#define X2C_max_longcard 0xFFFFFFFFUL
static uint32_t X2C_TRUNCC(double x, uint32_t min0, uint32_t max0)
{
uint32_t i;
if (x < (double)min0)
i = (uint32_t)min0;
if (x > (double)max0)
i = (uint32_t)max0;
i = (uint32_t)x;
if ((double)i > x)
--i;
return i;
}
static uint32_t truncc(double r)
{
if (r<=0.0) return 0UL;
else if (r>=2.E+9) return 2000000000UL;
else return (uint32_t)X2C_TRUNCC(r,0UL,X2C_max_longcard);
else return (uint32_t)r;
return 0;
} /* end truncc() */
@ -272,7 +256,7 @@ static uint32_t dao91(double x)
char b[201];
char raw[201];
//char raw[201];
char *aprs_senddata(SondeInfo *s, const char *usercall, const char *sym) {
// float lat, float lon, float alt, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym, const char *comm)
@ -291,7 +275,7 @@ char *aprs_senddata(SondeInfo *s, const char *usercall, const char *sym) {
// time
int i = strlen(b);
int sec = s->time % 86400;
snprintf(b+i, APRS_MAXLEN-1, "%02d%02d%02dz", sec/(60*60), (sec%(60*60))/60, sec%60);
snprintf(b+i, APRS_MAXLEN-1, "%02d%02d%02dh", sec/(60*60), (sec%(60*60))/60, sec%60);
i = strlen(b);
//aprsstr_append_data(time, ds);
int lati = abs((int)s->lat);
@ -309,11 +293,10 @@ char *aprs_senddata(SondeInfo *s, const char *usercall, const char *sym) {
i=strlen(b);
snprintf(b+i, APRS_MAXLEN-i, "/A=%06d", realcard(s->alt*FEET+0.5));
}
int dao=1;
if(dao) {
i=strlen(b);
snprintf(b+i, APRS_MAXLEN-i, "!w%c%c!", 33+dao91(s->lat), 33+dao91(s->lon));
}
// always use DAO
i=strlen(b);
snprintf(b+i, APRS_MAXLEN-i, "!w%c%c!", 33+dao91(s->lat), 33+dao91(s->lon));
strcat(b, "&");
char comm[100];
snprintf(comm, 100, "Clb=%.1fm/s %.3fMHz Type=%s", s->vs, s->freq, sondeTypeStr[s->type]);

Wyświetl plik

@ -0,0 +1,451 @@
const uint8_t FreeSans18pt7bBitmaps[] PROGMEM = {
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE9, 0x20, 0x3F, 0xFC, 0xE3, 0xF1,
0xF8, 0xFC, 0x7E, 0x3F, 0x1F, 0x8E, 0x82, 0x41, 0x00, 0x01, 0xC3, 0x80,
0x38, 0x70, 0x06, 0x0E, 0x00, 0xC1, 0x80, 0x38, 0x70, 0x07, 0x0E, 0x0F,
0xFF, 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE0, 0xE1, 0xC0, 0x1C, 0x38, 0x03,
0x87, 0x00, 0x70, 0xE0, 0x0C, 0x18, 0x3F, 0xFF, 0xF7, 0xFF, 0xFE, 0xFF,
0xFF, 0xC1, 0xC3, 0x80, 0x30, 0x60, 0x06, 0x0C, 0x01, 0xC3, 0x80, 0x38,
0x70, 0x07, 0x0E, 0x00, 0xC1, 0x80, 0x03, 0x00, 0x0F, 0xC0, 0x3F, 0xF0,
0x3F, 0xF8, 0x7B, 0x3C, 0xF3, 0x1C, 0xE3, 0x0E, 0xE3, 0x0E, 0xE3, 0x0E,
0xE3, 0x00, 0xE3, 0x00, 0xF3, 0x00, 0x7B, 0x00, 0x7F, 0x80, 0x1F, 0xF0,
0x07, 0xFC, 0x03, 0x7E, 0x03, 0x0F, 0x03, 0x07, 0xE3, 0x07, 0xE3, 0x07,
0xE3, 0x07, 0xE3, 0x0F, 0x73, 0x3E, 0x7F, 0xFC, 0x3F, 0xF8, 0x0F, 0xE0,
0x03, 0x00, 0x03, 0x00, 0x03, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x78, 0x00,
0xE0, 0x0F, 0xF0, 0x06, 0x00, 0xFF, 0xC0, 0x70, 0x07, 0x0E, 0x07, 0x00,
0x70, 0x38, 0x38, 0x03, 0x00, 0xC3, 0x80, 0x18, 0x06, 0x1C, 0x00, 0xE0,
0x71, 0xC0, 0x03, 0x87, 0x8C, 0x00, 0x1F, 0xF8, 0xE0, 0x00, 0x7F, 0x86,
0x00, 0x01, 0xF8, 0x70, 0x00, 0x00, 0x03, 0x03, 0xC0, 0x00, 0x38, 0x7F,
0x80, 0x01, 0x87, 0xFE, 0x00, 0x1C, 0x38, 0x70, 0x00, 0xC3, 0x81, 0xC0,
0x0E, 0x18, 0x06, 0x00, 0xE0, 0xC0, 0x30, 0x07, 0x07, 0x03, 0x80, 0x70,
0x1C, 0x38, 0x03, 0x80, 0xFF, 0xC0, 0x38, 0x03, 0xFC, 0x01, 0x80, 0x07,
0x80, 0x01, 0xF0, 0x00, 0x7F, 0x80, 0x0F, 0xFC, 0x01, 0xE1, 0xE0, 0x1C,
0x0E, 0x01, 0xC0, 0xE0, 0x1C, 0x0E, 0x01, 0xE1, 0xE0, 0x0E, 0x3C, 0x00,
0x77, 0x80, 0x07, 0xF0, 0x00, 0x7C, 0x00, 0x0F, 0xE0, 0x03, 0xCF, 0x1C,
0x78, 0x79, 0xC7, 0x03, 0xDC, 0xE0, 0x1F, 0x8E, 0x00, 0xF8, 0xE0, 0x0F,
0x0E, 0x00, 0x70, 0xF0, 0x0F, 0x87, 0xC3, 0xFC, 0x7F, 0xFD, 0xC3, 0xFF,
0x0E, 0x0F, 0xC0, 0xF0, 0xFF, 0xFF, 0xFA, 0x40, 0x06, 0x06, 0x0C, 0x0C,
0x18, 0x18, 0x38, 0x30, 0x70, 0x70, 0x70, 0x60, 0xE0, 0xE0, 0xE0, 0xE0,
0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0x60, 0x70, 0x70, 0x70, 0x30, 0x38, 0x18,
0x18, 0x0C, 0x0C, 0x06, 0x03, 0xC0, 0x60, 0x30, 0x30, 0x38, 0x18, 0x1C,
0x0C, 0x0E, 0x0E, 0x0E, 0x06, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07,
0x07, 0x07, 0x06, 0x0E, 0x0E, 0x0E, 0x0C, 0x1C, 0x18, 0x38, 0x30, 0x30,
0x60, 0xC0, 0x0C, 0x03, 0x00, 0xC3, 0xB7, 0xFF, 0xC7, 0x81, 0xE0, 0xEC,
0x73, 0x88, 0x40, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01,
0x80, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0x80, 0x01,
0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0xFF,
0xF6, 0xDA, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0xC0, 0x30, 0x18,
0x06, 0x01, 0x80, 0xC0, 0x30, 0x0C, 0x06, 0x01, 0x80, 0x60, 0x30, 0x0C,
0x03, 0x00, 0xC0, 0x60, 0x18, 0x06, 0x03, 0x00, 0xC0, 0x30, 0x18, 0x06,
0x01, 0x80, 0xC0, 0x30, 0x00, 0x07, 0xE0, 0x0F, 0xF8, 0x1F, 0xFC, 0x3C,
0x3C, 0x78, 0x1E, 0x70, 0x0E, 0x70, 0x0E, 0xE0, 0x07, 0xE0, 0x07, 0xE0,
0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0,
0x07, 0xE0, 0x07, 0xE0, 0x0F, 0x70, 0x0E, 0x70, 0x0E, 0x78, 0x1E, 0x3C,
0x3C, 0x1F, 0xF8, 0x1F, 0xF0, 0x07, 0xE0, 0x03, 0x03, 0x07, 0x0F, 0x3F,
0xFF, 0xFF, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07,
0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0xE0, 0x1F, 0xF8,
0x3F, 0xFC, 0x7C, 0x3E, 0x70, 0x0F, 0xF0, 0x0F, 0xE0, 0x07, 0xE0, 0x07,
0x00, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF8,
0x03, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x70, 0x00,
0x60, 0x00, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0xF0,
0x07, 0xFE, 0x07, 0xFF, 0x87, 0x83, 0xC3, 0x80, 0xF3, 0x80, 0x39, 0xC0,
0x1C, 0xE0, 0x0E, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x7F, 0x00, 0x3F, 0x00,
0x1F, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, 0xF0, 0x01,
0xF8, 0x00, 0xFE, 0x00, 0x77, 0x00, 0x73, 0xE0, 0xF8, 0xFF, 0xF8, 0x3F,
0xF8, 0x07, 0xF0, 0x00, 0x00, 0x38, 0x00, 0x38, 0x00, 0x78, 0x00, 0xF8,
0x00, 0xF8, 0x01, 0xF8, 0x03, 0xB8, 0x03, 0x38, 0x07, 0x38, 0x0E, 0x38,
0x1C, 0x38, 0x18, 0x38, 0x38, 0x38, 0x70, 0x38, 0x60, 0x38, 0xE0, 0x38,
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38,
0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x1F, 0xFF, 0x0F, 0xFF, 0x8F, 0xFF,
0xC7, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x39,
0xF0, 0x3F, 0xFE, 0x1F, 0xFF, 0x8F, 0x83, 0xE7, 0x00, 0xF0, 0x00, 0x3C,
0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xFC, 0x00,
0xEF, 0x00, 0x73, 0xC0, 0xF0, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xE0, 0x00,
0x03, 0xE0, 0x0F, 0xF8, 0x1F, 0xFC, 0x3C, 0x1E, 0x38, 0x0E, 0x70, 0x0E,
0x70, 0x00, 0x60, 0x00, 0xE0, 0x00, 0xE3, 0xE0, 0xEF, 0xF8, 0xFF, 0xFC,
0xFC, 0x3E, 0xF0, 0x0E, 0xF0, 0x0F, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07,
0x60, 0x07, 0x70, 0x0F, 0x70, 0x0E, 0x3C, 0x3E, 0x3F, 0xFC, 0x1F, 0xF8,
0x07, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x06, 0x00, 0x0E,
0x00, 0x1C, 0x00, 0x18, 0x00, 0x38, 0x00, 0x70, 0x00, 0x60, 0x00, 0xE0,
0x00, 0xC0, 0x01, 0xC0, 0x01, 0x80, 0x03, 0x80, 0x03, 0x80, 0x07, 0x00,
0x07, 0x00, 0x07, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00,
0x1C, 0x00, 0x1C, 0x00, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, 0x87, 0x83,
0xC7, 0x80, 0xF3, 0x80, 0x39, 0xC0, 0x1C, 0xE0, 0x0E, 0x78, 0x0F, 0x1E,
0x0F, 0x07, 0xFF, 0x01, 0xFF, 0x03, 0xFF, 0xE3, 0xE0, 0xF9, 0xC0, 0x1D,
0xC0, 0x0F, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0xF7, 0x00,
0x73, 0xE0, 0xF8, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x07, 0xE0,
0x1F, 0xF8, 0x3F, 0xFC, 0x7C, 0x3C, 0x70, 0x0E, 0xF0, 0x0E, 0xE0, 0x06,
0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x0F, 0x70, 0x0F, 0x78, 0x3F,
0x3F, 0xFF, 0x1F, 0xF7, 0x07, 0xC7, 0x00, 0x07, 0x00, 0x06, 0x00, 0x0E,
0x70, 0x0E, 0x70, 0x1C, 0x78, 0x3C, 0x3F, 0xF8, 0x1F, 0xF0, 0x07, 0xC0,
0xFF, 0xF0, 0x00, 0x00, 0x00, 0x07, 0xFF, 0x80, 0xFF, 0xF0, 0x00, 0x00,
0x00, 0x07, 0xFF, 0xB6, 0xD6, 0x00, 0x00, 0x80, 0x03, 0xC0, 0x07, 0xE0,
0x0F, 0xC0, 0x3F, 0x80, 0x7E, 0x00, 0xFC, 0x01, 0xF0, 0x00, 0xE0, 0x00,
0x7C, 0x00, 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x07, 0xF0, 0x00,
0x7E, 0x00, 0x0F, 0x00, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0x80, 0x80, 0x00, 0x70, 0x00, 0x3E, 0x00, 0x0F, 0xE0, 0x00, 0xFC,
0x00, 0x1F, 0xC0, 0x03, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0x80, 0x0F, 0xC0,
0x1F, 0x80, 0x7F, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x01, 0xC0, 0x00,
0x80, 0x00, 0x00, 0x0F, 0xC0, 0x7F, 0xE1, 0xFF, 0xE3, 0xC3, 0xEF, 0x01,
0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0x00, 0x0E, 0x00, 0x38, 0x00, 0xF0,
0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x00, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E,
0x00, 0x1C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xC0, 0x03, 0x80,
0x07, 0x00, 0x0E, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x00,
0x00, 0xFF, 0xFF, 0xC0, 0x01, 0xF8, 0x0F, 0xE0, 0x03, 0xE0, 0x01, 0xF0,
0x07, 0x80, 0x00, 0xF8, 0x0F, 0x00, 0x00, 0x3C, 0x1E, 0x00, 0x00, 0x1E,
0x3C, 0x03, 0xE0, 0x1E, 0x38, 0x0F, 0xF3, 0x8E, 0x78, 0x1E, 0x3F, 0x0F,
0x70, 0x38, 0x1F, 0x07, 0x70, 0x78, 0x0F, 0x07, 0xE0, 0x70, 0x0E, 0x07,
0xE0, 0x70, 0x0E, 0x07, 0xE0, 0xE0, 0x0E, 0x07, 0xE0, 0xE0, 0x1C, 0x07,
0xE0, 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x38, 0x1C,
0xF0, 0x70, 0x78, 0x3C, 0x70, 0x78, 0xFC, 0x78, 0x78, 0x3F, 0xDF, 0xF0,
0x38, 0x1F, 0x0F, 0xC0, 0x3C, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00,
0x0F, 0x80, 0x00, 0x00, 0x07, 0xF0, 0x0E, 0x00, 0x01, 0xFF, 0xFE, 0x00,
0x00, 0x7F, 0xFE, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x03,
0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xDC, 0x00, 0x07, 0x78,
0x00, 0x3C, 0xE0, 0x00, 0xE3, 0x80, 0x03, 0x8F, 0x00, 0x1E, 0x1C, 0x00,
0x70, 0x70, 0x01, 0xC1, 0xE0, 0x0E, 0x03, 0x80, 0x38, 0x0E, 0x00, 0xE0,
0x3C, 0x07, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0xFF, 0xFF, 0x83, 0xC0, 0x0E,
0x0E, 0x00, 0x3C, 0x78, 0x00, 0xF1, 0xE0, 0x01, 0xC7, 0x00, 0x07, 0xBC,
0x00, 0x1E, 0xF0, 0x00, 0x3B, 0x80, 0x00, 0xF0, 0xFF, 0xFC, 0x1F, 0xFF,
0xE3, 0xFF, 0xFE, 0x70, 0x03, 0xCE, 0x00, 0x3D, 0xC0, 0x03, 0xB8, 0x00,
0x77, 0x00, 0x0E, 0xE0, 0x01, 0xDC, 0x00, 0x73, 0x80, 0x1E, 0x7F, 0xFF,
0x8F, 0xFF, 0xF1, 0xFF, 0xFF, 0x38, 0x00, 0xF7, 0x00, 0x0E, 0xE0, 0x00,
0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x03,
0xF8, 0x00, 0xF7, 0xFF, 0xFC, 0xFF, 0xFF, 0x1F, 0xFF, 0x80, 0x00, 0xFF,
0x00, 0x0F, 0xFF, 0x00, 0xFF, 0xFE, 0x07, 0xE0, 0x7C, 0x3E, 0x00, 0x78,
0xF0, 0x00, 0xE7, 0x80, 0x03, 0xDC, 0x00, 0x07, 0x70, 0x00, 0x03, 0x80,
0x00, 0x0E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00,
0x0E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x1D, 0xC0, 0x00, 0x77,
0x00, 0x03, 0xDE, 0x00, 0x0E, 0x3C, 0x00, 0x78, 0xF8, 0x03, 0xC1, 0xF8,
0x1F, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x03, 0xF8, 0x00, 0xFF, 0xF8,
0x0F, 0xFF, 0xE0, 0xFF, 0xFF, 0x0E, 0x00, 0xF8, 0xE0, 0x03, 0xCE, 0x00,
0x1C, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xFE, 0x00, 0x07, 0xE0,
0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E,
0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x0F, 0xE0, 0x00, 0xEE, 0x00, 0x0E,
0xE0, 0x01, 0xEE, 0x00, 0x3C, 0xE0, 0x0F, 0x8F, 0xFF, 0xF0, 0xFF, 0xFE,
0x0F, 0xFF, 0x80, 0xFF, 0xFF, 0xBF, 0xFF, 0xEF, 0xFF, 0xFB, 0x80, 0x00,
0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38,
0x00, 0x0E, 0x00, 0x03, 0xFF, 0xFE, 0xFF, 0xFF, 0xBF, 0xFF, 0xEE, 0x00,
0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00,
0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x0E, 0x00,
0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38,
0x00, 0x1F, 0xFF, 0xCF, 0xFF, 0xE7, 0xFF, 0xF3, 0x80, 0x01, 0xC0, 0x00,
0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00,
0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x00, 0x00, 0x7F,
0x80, 0x03, 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x0F, 0x80, 0xFC, 0x1E, 0x00,
0x3E, 0x3C, 0x00, 0x0E, 0x78, 0x00, 0x0F, 0x70, 0x00, 0x07, 0x70, 0x00,
0x00, 0xE0, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xE0, 0x03,
0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x00, 0x07, 0xF0, 0x00,
0x07, 0x70, 0x00, 0x07, 0x70, 0x00, 0x0F, 0x78, 0x00, 0x0F, 0x3C, 0x00,
0x1F, 0x1E, 0x00, 0x3F, 0x0F, 0xC0, 0xF7, 0x07, 0xFF, 0xE7, 0x03, 0xFF,
0xC3, 0x00, 0xFF, 0x03, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0,
0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0,
0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80,
0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00,
0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1C, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00,
0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0,
0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1F, 0x80, 0x7E,
0x01, 0xF8, 0x07, 0xE0, 0x1F, 0xC0, 0xF7, 0x87, 0x9F, 0xFE, 0x3F, 0xF0,
0x3F, 0x00, 0xE0, 0x01, 0xEE, 0x00, 0x3C, 0xE0, 0x07, 0x8E, 0x00, 0xF0,
0xE0, 0x1E, 0x0E, 0x03, 0xE0, 0xE0, 0x7C, 0x0E, 0x0F, 0x80, 0xE1, 0xF0,
0x0E, 0x1E, 0x00, 0xE3, 0xC0, 0x0E, 0x7C, 0x00, 0xEF, 0xE0, 0x0F, 0xCE,
0x00, 0xF8, 0xF0, 0x0F, 0x07, 0x80, 0xE0, 0x3C, 0x0E, 0x03, 0xC0, 0xE0,
0x1E, 0x0E, 0x00, 0xF0, 0xE0, 0x0F, 0x0E, 0x00, 0x78, 0xE0, 0x03, 0xCE,
0x00, 0x3C, 0xE0, 0x01, 0xEE, 0x00, 0x0F, 0xE0, 0x01, 0xC0, 0x03, 0x80,
0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01,
0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70,
0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00,
0x38, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xF8, 0x00, 0x1F, 0xF8,
0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xFC, 0x00, 0x3F, 0xFC, 0x00, 0x3F, 0xFC,
0x00, 0x3F, 0xEE, 0x00, 0x77, 0xEE, 0x00, 0x77, 0xEE, 0x00, 0x77, 0xE7,
0x00, 0xE7, 0xE7, 0x00, 0xE7, 0xE7, 0x00, 0xE7, 0xE3, 0x81, 0xC7, 0xE3,
0x81, 0xC7, 0xE3, 0x81, 0xC7, 0xE1, 0xC3, 0x87, 0xE1, 0xC3, 0x87, 0xE1,
0xC3, 0x87, 0xE0, 0xE7, 0x07, 0xE0, 0xE7, 0x07, 0xE0, 0xE7, 0x07, 0xE0,
0x7E, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x3C, 0x07, 0xE0,
0x3C, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0xC0, 0x07,
0xFC, 0x00, 0x7F, 0xE0, 0x07, 0xEF, 0x00, 0x7E, 0x70, 0x07, 0xE7, 0x80,
0x7E, 0x3C, 0x07, 0xE1, 0xC0, 0x7E, 0x1E, 0x07, 0xE0, 0xE0, 0x7E, 0x0F,
0x07, 0xE0, 0x78, 0x7E, 0x03, 0x87, 0xE0, 0x3C, 0x7E, 0x01, 0xE7, 0xE0,
0x0E, 0x7E, 0x00, 0xF7, 0xE0, 0x07, 0xFE, 0x00, 0x3F, 0xE0, 0x03, 0xFE,
0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x0F, 0x00, 0x7F, 0x00, 0x01, 0xFF,
0xF0, 0x01, 0xFF, 0xFC, 0x01, 0xF0, 0x1F, 0x01, 0xE0, 0x03, 0xC1, 0xE0,
0x00, 0xF1, 0xE0, 0x00, 0x3C, 0xE0, 0x00, 0x0E, 0x70, 0x00, 0x07, 0x70,
0x00, 0x03, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F,
0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03,
0xB8, 0x00, 0x03, 0x9C, 0x00, 0x01, 0xCF, 0x00, 0x01, 0xE3, 0xC0, 0x01,
0xE0, 0xF0, 0x01, 0xE0, 0x3E, 0x03, 0xE0, 0x0F, 0xFF, 0xE0, 0x03, 0xFF,
0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFF, 0xFC, 0x3F, 0xFF, 0x8F, 0xFF, 0xF3,
0x80, 0x3E, 0xE0, 0x03, 0xF8, 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0,
0x01, 0xF8, 0x00, 0x7E, 0x00, 0x3F, 0x80, 0x1E, 0xFF, 0xFF, 0x3F, 0xFF,
0x8F, 0xFF, 0xC3, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03,
0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0,
0x00, 0x38, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xF0, 0x01, 0xFF,
0xFC, 0x01, 0xF0, 0x1F, 0x01, 0xE0, 0x03, 0xC1, 0xE0, 0x00, 0xF1, 0xE0,
0x00, 0x3C, 0xE0, 0x00, 0x0E, 0x70, 0x00, 0x07, 0x70, 0x00, 0x01, 0xF8,
0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F,
0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xB8, 0x00, 0x03,
0x9C, 0x00, 0x01, 0xCF, 0x00, 0x39, 0xE3, 0xC0, 0x1F, 0xE0, 0xF0, 0x07,
0xE0, 0x3E, 0x03, 0xF0, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xEE, 0x00, 0x3F,
0x83, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x20, 0xFF, 0xFE, 0x0F, 0xFF,
0xF8, 0xFF, 0xFF, 0xCE, 0x00, 0x3C, 0xE0, 0x01, 0xEE, 0x00, 0x0E, 0xE0,
0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x01, 0xCE,
0x00, 0x3C, 0xFF, 0xFF, 0x8F, 0xFF, 0xF0, 0xFF, 0xFF, 0x8E, 0x00, 0x3C,
0xE0, 0x01, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00,
0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xFE, 0x00,
0x0F, 0x03, 0xFC, 0x00, 0xFF, 0xF0, 0x1F, 0xFF, 0x83, 0xE0, 0x7C, 0x38,
0x01, 0xE7, 0x00, 0x0E, 0x70, 0x00, 0xE7, 0x00, 0x00, 0x70, 0x00, 0x07,
0x80, 0x00, 0x3E, 0x00, 0x01, 0xFE, 0x00, 0x0F, 0xFE, 0x00, 0x3F, 0xF8,
0x00, 0x3F, 0xE0, 0x00, 0x3E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0xE0, 0x00,
0x7E, 0x00, 0x07, 0xF0, 0x00, 0x77, 0x80, 0x0E, 0x7C, 0x03, 0xE3, 0xFF,
0xFC, 0x1F, 0xFF, 0x80, 0x3F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0x80, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07,
0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E,
0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C,
0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x38,
0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0xE0, 0x00, 0xFC, 0x00,
0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00,
0x3F, 0x00, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00,
0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00,
0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x1E, 0xF0, 0x07,
0x9F, 0x01, 0xF1, 0xFF, 0xFC, 0x1F, 0xFE, 0x00, 0x7F, 0x00, 0xE0, 0x00,
0x7F, 0x80, 0x03, 0xFC, 0x00, 0x1C, 0xE0, 0x01, 0xE7, 0x80, 0x0F, 0x3C,
0x00, 0x70, 0xE0, 0x07, 0x87, 0x80, 0x3C, 0x1C, 0x01, 0xC0, 0xE0, 0x0E,
0x07, 0x80, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x83, 0x80, 0x1C,
0x1C, 0x00, 0xE0, 0xE0, 0x07, 0x8E, 0x00, 0x1C, 0x70, 0x00, 0xE3, 0x80,
0x07, 0xB8, 0x00, 0x1D, 0xC0, 0x00, 0xEE, 0x00, 0x07, 0xE0, 0x00, 0x1F,
0x00, 0x00, 0xF8, 0x00, 0x03, 0x80, 0x00, 0x70, 0x03, 0xC0, 0x0F, 0x70,
0x03, 0xC0, 0x0F, 0x78, 0x03, 0xE0, 0x0F, 0x78, 0x03, 0xE0, 0x0E, 0x38,
0x07, 0xE0, 0x0E, 0x38, 0x07, 0xF0, 0x1E, 0x3C, 0x07, 0x70, 0x1E, 0x3C,
0x07, 0x70, 0x1C, 0x1C, 0x0E, 0x70, 0x1C, 0x1C, 0x0E, 0x38, 0x3C, 0x1C,
0x0E, 0x38, 0x3C, 0x1E, 0x1E, 0x38, 0x38, 0x0E, 0x1C, 0x38, 0x38, 0x0E,
0x1C, 0x1C, 0x38, 0x0E, 0x1C, 0x1C, 0x78, 0x0F, 0x3C, 0x1C, 0x70, 0x07,
0x38, 0x0E, 0x70, 0x07, 0x38, 0x0E, 0x70, 0x07, 0x38, 0x0E, 0x70, 0x07,
0x70, 0x0E, 0xE0, 0x03, 0xF0, 0x07, 0xE0, 0x03, 0xF0, 0x07, 0xE0, 0x03,
0xF0, 0x07, 0xE0, 0x03, 0xE0, 0x03, 0xC0, 0x01, 0xE0, 0x03, 0xC0, 0x01,
0xE0, 0x03, 0xC0, 0xF0, 0x00, 0x7B, 0xC0, 0x07, 0x8F, 0x00, 0x38, 0x78,
0x03, 0xC1, 0xE0, 0x3C, 0x07, 0x81, 0xC0, 0x3C, 0x1E, 0x00, 0xF1, 0xE0,
0x03, 0x8E, 0x00, 0x1E, 0xF0, 0x00, 0x7F, 0x00, 0x01, 0xF0, 0x00, 0x0F,
0x80, 0x00, 0x7C, 0x00, 0x07, 0xF0, 0x00, 0x3B, 0x80, 0x03, 0xDE, 0x00,
0x3C, 0x78, 0x01, 0xC1, 0xC0, 0x1E, 0x0F, 0x01, 0xE0, 0x3C, 0x0E, 0x00,
0xE0, 0xF0, 0x07, 0x8F, 0x00, 0x1E, 0x70, 0x00, 0xF7, 0x80, 0x03, 0xC0,
0xF0, 0x00, 0x3C, 0xF0, 0x00, 0x78, 0xF0, 0x01, 0xE1, 0xE0, 0x03, 0x81,
0xE0, 0x0F, 0x01, 0xC0, 0x1C, 0x03, 0xC0, 0x78, 0x03, 0xC1, 0xE0, 0x07,
0x83, 0x80, 0x07, 0x8F, 0x00, 0x07, 0x1C, 0x00, 0x0F, 0x78, 0x00, 0x0E,
0xE0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38,
0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80,
0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00,
0x00, 0x70, 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0x80, 0x00,
0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E,
0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0,
0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x7C, 0x00,
0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xF8, 0xE3, 0x8E, 0x38, 0xE3,
0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3,
0x8E, 0x38, 0xE3, 0x8F, 0xFF, 0xFC, 0xC0, 0x30, 0x06, 0x01, 0x80, 0x60,
0x0C, 0x03, 0x00, 0xC0, 0x18, 0x06, 0x01, 0x80, 0x20, 0x0C, 0x03, 0x00,
0x40, 0x18, 0x06, 0x01, 0x80, 0x30, 0x0C, 0x03, 0x00, 0x60, 0x18, 0x06,
0x00, 0xC0, 0x30, 0xFF, 0xFF, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7,
0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7,
0x1C, 0x7F, 0xFF, 0xFC, 0x07, 0x00, 0x78, 0x03, 0xC0, 0x3F, 0x01, 0xD8,
0x0C, 0xE0, 0xE3, 0x06, 0x1C, 0x70, 0xE3, 0x83, 0x18, 0x1D, 0xC0, 0x6C,
0x03, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xF0, 0xF0, 0xE0, 0xE0,
0xE0, 0x07, 0xF0, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0x03, 0xC7, 0x00, 0xE0,
0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0xFE, 0x0F, 0xFF, 0x1F, 0xF3,
0x9F, 0x01, 0xCF, 0x00, 0xE7, 0x00, 0x73, 0x80, 0x79, 0xE0, 0xFC, 0x7F,
0xEF, 0x9F, 0xE3, 0xC7, 0xE1, 0xE0, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00,
0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE3, 0xE0, 0xEF, 0xF8,
0xFF, 0xFC, 0xFC, 0x3E, 0xF8, 0x1E, 0xF0, 0x0E, 0xE0, 0x0F, 0xE0, 0x07,
0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xF0, 0x0E,
0xF8, 0x1E, 0xFC, 0x3C, 0xEF, 0xFC, 0xEF, 0xF8, 0xE3, 0xE0, 0x07, 0xF0,
0x1F, 0xF8, 0x3F, 0xFC, 0x3C, 0x1E, 0x78, 0x0E, 0x70, 0x07, 0xE0, 0x00,
0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x07,
0x70, 0x07, 0x78, 0x0E, 0x7C, 0x1E, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0,
0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00,
0x1C, 0x00, 0x0E, 0x0F, 0xC7, 0x1F, 0xFB, 0x9F, 0xFF, 0xDF, 0x07, 0xEF,
0x01, 0xF7, 0x00, 0x7F, 0x80, 0x3F, 0x80, 0x0F, 0xC0, 0x07, 0xE0, 0x03,
0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x77, 0x00, 0x7B, 0xC0, 0x7D, 0xF0,
0x7E, 0x7F, 0xFB, 0x1F, 0xF9, 0x83, 0xF0, 0xC0, 0x07, 0xE0, 0x1F, 0xF8,
0x3F, 0xFC, 0x7C, 0x1E, 0x70, 0x0E, 0x60, 0x06, 0xE0, 0x07, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0x70, 0x07,
0x78, 0x0E, 0x3C, 0x1E, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, 0x0E, 0x3C,
0xF9, 0xC3, 0x87, 0x0E, 0x7F, 0xFF, 0xFC, 0xE1, 0xC3, 0x87, 0x0E, 0x1C,
0x38, 0x70, 0xE1, 0xC3, 0x87, 0x0E, 0x1C, 0x38, 0x70, 0x07, 0xC7, 0x1F,
0xF7, 0x3F, 0xFF, 0x3C, 0x3F, 0x78, 0x0F, 0x70, 0x0F, 0xE0, 0x07, 0xE0,
0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0x70,
0x0F, 0x78, 0x0F, 0x7C, 0x3F, 0x3F, 0xF7, 0x1F, 0xE7, 0x07, 0xC7, 0x00,
0x07, 0x00, 0x07, 0x00, 0x0E, 0x70, 0x0E, 0x78, 0x1E, 0x3F, 0xFC, 0x1F,
0xF8, 0x07, 0xE0, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00,
0x1C, 0x00, 0x38, 0x00, 0x71, 0xF8, 0xE7, 0xFD, 0xDF, 0xFB, 0xF0, 0xFF,
0xC0, 0xFF, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0,
0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07,
0xE0, 0x0F, 0xC0, 0x1C, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFC, 0x1C, 0x71, 0xC7, 0x00, 0x00, 0x07, 0x1C, 0x71, 0xC7, 0x1C,
0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C,
0x73, 0xFF, 0xFB, 0xC0, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00,
0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x3C, 0xE0, 0x78, 0xE0, 0xF0,
0xE1, 0xE0, 0xE3, 0xC0, 0xE7, 0x80, 0xEF, 0x00, 0xEF, 0x80, 0xFF, 0x80,
0xFB, 0xC0, 0xF1, 0xE0, 0xE0, 0xE0, 0xE0, 0xF0, 0xE0, 0x70, 0xE0, 0x78,
0xE0, 0x3C, 0xE0, 0x1C, 0xE0, 0x1E, 0xE0, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xE3, 0xE0, 0xF8, 0xE7, 0xF1, 0xFE,
0xEF, 0xFB, 0xFE, 0xF8, 0x7F, 0x0F, 0xF0, 0x3E, 0x07, 0xF0, 0x1C, 0x07,
0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07,
0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07,
0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07,
0xE0, 0x1C, 0x07, 0xE3, 0xF1, 0xCF, 0xFB, 0xBF, 0xF7, 0xE1, 0xFF, 0x81,
0xFE, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, 0x1F, 0x80, 0x3F,
0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0,
0x1F, 0x80, 0x38, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, 0x87, 0x83, 0xC7,
0x80, 0xF3, 0x80, 0x3B, 0x80, 0x1F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x01,
0xF8, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0x3B, 0x80, 0x39, 0xE0, 0x3C, 0x78,
0x3C, 0x3F, 0xFE, 0x0F, 0xFE, 0x01, 0xFC, 0x00, 0xE3, 0xE0, 0xE7, 0xF8,
0xEF, 0xFC, 0xFC, 0x3E, 0xF8, 0x1E, 0xF0, 0x0E, 0xE0, 0x0F, 0xE0, 0x07,
0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xF0, 0x0E,
0xF8, 0x1E, 0xFC, 0x3E, 0xFF, 0xFC, 0xEF, 0xF8, 0xE3, 0xE0, 0xE0, 0x00,
0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0x07, 0xE1,
0x8F, 0xFC, 0xCF, 0xFF, 0x67, 0x83, 0xF7, 0x80, 0xFB, 0x80, 0x3F, 0xC0,
0x1F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x7E,
0x00, 0x3B, 0x80, 0x3D, 0xE0, 0x3E, 0xF8, 0x3F, 0x3F, 0xFF, 0x8F, 0xFD,
0xC1, 0xF8, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00,
0x07, 0x00, 0x03, 0x80, 0xE3, 0xF7, 0xFB, 0xFF, 0x8F, 0x07, 0x83, 0x81,
0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70,
0x38, 0x00, 0x0F, 0xC0, 0xFF, 0x87, 0xFF, 0x3C, 0x1E, 0xE0, 0x3B, 0x80,
0x0E, 0x00, 0x3C, 0x00, 0x7F, 0x00, 0xFF, 0x80, 0xFF, 0x80, 0x7F, 0x00,
0x3F, 0x80, 0x7E, 0x01, 0xFC, 0x1F, 0x7F, 0xF8, 0xFF, 0xC1, 0xFC, 0x00,
0x38, 0x70, 0xE1, 0xCF, 0xFF, 0xFF, 0x9C, 0x38, 0x70, 0xE1, 0xC3, 0x87,
0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0xE7, 0xC7, 0x80, 0xE0, 0x0F, 0xC0,
0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07,
0xE0, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x03, 0xFC,
0x0F, 0xFC, 0x3F, 0x7F, 0xEE, 0xFF, 0x9C, 0x7E, 0x38, 0x70, 0x03, 0xB8,
0x03, 0x9C, 0x01, 0xC7, 0x00, 0xE3, 0x80, 0xE1, 0xC0, 0x70, 0x70, 0x38,
0x38, 0x38, 0x1C, 0x1C, 0x07, 0x0E, 0x03, 0x8E, 0x01, 0xC7, 0x00, 0x77,
0x00, 0x3B, 0x80, 0x1D, 0xC0, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00,
0x70, 0x00, 0xF0, 0x1C, 0x03, 0xB8, 0x1F, 0x03, 0xDC, 0x0F, 0x81, 0xCE,
0x07, 0xC0, 0xE7, 0x83, 0xE0, 0x71, 0xC3, 0xB8, 0x70, 0xE1, 0xDC, 0x38,
0x70, 0xEE, 0x1C, 0x1C, 0x63, 0x0E, 0x0E, 0x71, 0xCE, 0x07, 0x38, 0xE7,
0x03, 0x9C, 0x73, 0x80, 0xEC, 0x19, 0x80, 0x7E, 0x0F, 0xC0, 0x3F, 0x07,
0xE0, 0x0F, 0x83, 0xF0, 0x07, 0x80, 0xF0, 0x03, 0xC0, 0x78, 0x01, 0xE0,
0x3C, 0x00, 0x70, 0x07, 0x38, 0x0E, 0x3C, 0x1C, 0x1C, 0x1C, 0x0E, 0x38,
0x0F, 0x70, 0x07, 0x70, 0x03, 0xE0, 0x03, 0xC0, 0x01, 0xC0, 0x03, 0xE0,
0x07, 0xE0, 0x07, 0x70, 0x0E, 0x78, 0x1E, 0x38, 0x1C, 0x1C, 0x38, 0x1E,
0x78, 0x0E, 0x70, 0x07, 0x70, 0x07, 0x38, 0x03, 0x9C, 0x01, 0xC7, 0x01,
0xC3, 0x80, 0xE1, 0xC0, 0x70, 0x70, 0x70, 0x38, 0x38, 0x1C, 0x3C, 0x07,
0x1C, 0x03, 0x8E, 0x01, 0xCE, 0x00, 0x77, 0x00, 0x3B, 0x80, 0x1F, 0x80,
0x07, 0xC0, 0x03, 0xE0, 0x01, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x38,
0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0E, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x0F,
0x00, 0x00, 0x7F, 0xFC, 0xFF, 0xF9, 0xFF, 0xF0, 0x00, 0xE0, 0x03, 0x80,
0x0E, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x1C, 0x00, 0x70,
0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x00, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xF8, 0x07, 0x0F, 0x1F, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C,
0x1C, 0x1C, 0x1C, 0x1C, 0x38, 0xF8, 0xE0, 0xF8, 0x38, 0x1C, 0x1C, 0x1C,
0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1F, 0x0F, 0x07, 0xFF,
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xE0, 0xF0, 0xF8, 0x38,
0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x1C, 0x1F,
0x07, 0x1F, 0x1C, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38,
0x38, 0x38, 0xF8, 0xF0, 0xE0, 0x38, 0x00, 0xFC, 0x03, 0xFC, 0x1F, 0x3E,
0x3C, 0x1F, 0xE0, 0x1F, 0x80, 0x1E, 0x00};
const GFXglyph FreeSans18pt7bGlyphs[] PROGMEM = {
{0, 0, 0, 9, 0, 1}, // 0x20 ' '
{0, 3, 26, 12, 4, -25}, // 0x21 '!'
{10, 9, 9, 12, 1, -24}, // 0x22 '"'
{21, 19, 24, 19, 0, -23}, // 0x23 '#'
{78, 16, 30, 19, 2, -26}, // 0x24 '$'
{138, 29, 25, 31, 1, -24}, // 0x25 '%'
{229, 20, 25, 23, 2, -24}, // 0x26 '&'
{292, 3, 9, 7, 2, -24}, // 0x27 '''
{296, 8, 33, 12, 3, -25}, // 0x28 '('
{329, 8, 33, 12, 1, -25}, // 0x29 ')'
{362, 10, 10, 14, 2, -25}, // 0x2A '*'
{375, 16, 16, 20, 2, -15}, // 0x2B '+'
{407, 3, 9, 10, 3, -3}, // 0x2C ','
{411, 8, 3, 12, 2, -10}, // 0x2D '-'
{414, 3, 4, 9, 3, -3}, // 0x2E '.'
{416, 10, 26, 10, 0, -25}, // 0x2F '/'
{449, 16, 25, 19, 2, -24}, // 0x30 '0'
{499, 8, 25, 19, 4, -24}, // 0x31 '1'
{524, 16, 25, 19, 2, -24}, // 0x32 '2'
{574, 17, 25, 19, 1, -24}, // 0x33 '3'
{628, 16, 25, 19, 1, -24}, // 0x34 '4'
{678, 17, 25, 19, 1, -24}, // 0x35 '5'
{732, 16, 25, 19, 2, -24}, // 0x36 '6'
{782, 16, 25, 19, 2, -24}, // 0x37 '7'
{832, 17, 25, 19, 1, -24}, // 0x38 '8'
{886, 16, 25, 19, 1, -24}, // 0x39 '9'
{936, 3, 19, 9, 3, -18}, // 0x3A ':'
{944, 3, 24, 9, 3, -18}, // 0x3B ';'
{953, 17, 17, 20, 2, -16}, // 0x3C '<'
{990, 17, 9, 20, 2, -12}, // 0x3D '='
{1010, 17, 17, 20, 2, -16}, // 0x3E '>'
{1047, 15, 26, 19, 3, -25}, // 0x3F '?'
{1096, 32, 31, 36, 1, -25}, // 0x40 '@'
{1220, 22, 26, 23, 1, -25}, // 0x41 'A'
{1292, 19, 26, 23, 3, -25}, // 0x42 'B'
{1354, 22, 26, 25, 1, -25}, // 0x43 'C'
{1426, 20, 26, 24, 3, -25}, // 0x44 'D'
{1491, 18, 26, 22, 3, -25}, // 0x45 'E'
{1550, 17, 26, 21, 3, -25}, // 0x46 'F'
{1606, 24, 26, 27, 1, -25}, // 0x47 'G'
{1684, 19, 26, 25, 3, -25}, // 0x48 'H'
{1746, 3, 26, 10, 4, -25}, // 0x49 'I'
{1756, 14, 26, 18, 1, -25}, // 0x4A 'J'
{1802, 20, 26, 24, 3, -25}, // 0x4B 'K'
{1867, 15, 26, 20, 3, -25}, // 0x4C 'L'
{1916, 24, 26, 30, 3, -25}, // 0x4D 'M'
{1994, 20, 26, 26, 3, -25}, // 0x4E 'N'
{2059, 25, 26, 27, 1, -25}, // 0x4F 'O'
{2141, 18, 26, 23, 3, -25}, // 0x50 'P'
{2200, 25, 28, 27, 1, -25}, // 0x51 'Q'
{2288, 20, 26, 25, 3, -25}, // 0x52 'R'
{2353, 20, 26, 23, 1, -25}, // 0x53 'S'
{2418, 19, 26, 22, 1, -25}, // 0x54 'T'
{2480, 19, 26, 25, 3, -25}, // 0x55 'U'
{2542, 21, 26, 23, 1, -25}, // 0x56 'V'
{2611, 32, 26, 33, 0, -25}, // 0x57 'W'
{2715, 21, 26, 23, 1, -25}, // 0x58 'X'
{2784, 23, 26, 24, 0, -25}, // 0x59 'Y'
{2859, 19, 26, 22, 1, -25}, // 0x5A 'Z'
{2921, 6, 33, 10, 2, -25}, // 0x5B '['
{2946, 10, 26, 10, 0, -25}, // 0x5C '\'
{2979, 6, 33, 10, 1, -25}, // 0x5D ']'
{3004, 13, 13, 16, 2, -24}, // 0x5E '^'
{3026, 21, 2, 19, -1, 5}, // 0x5F '_'
{3032, 7, 5, 9, 1, -25}, // 0x60 '`'
{3037, 17, 19, 19, 1, -18}, // 0x61 'a'
{3078, 16, 26, 20, 2, -25}, // 0x62 'b'
{3130, 16, 19, 18, 1, -18}, // 0x63 'c'
{3168, 17, 26, 20, 1, -25}, // 0x64 'd'
{3224, 16, 19, 19, 1, -18}, // 0x65 'e'
{3262, 7, 26, 10, 1, -25}, // 0x66 'f'
{3285, 16, 27, 19, 1, -18}, // 0x67 'g'
{3339, 15, 26, 19, 2, -25}, // 0x68 'h'
{3388, 3, 26, 8, 2, -25}, // 0x69 'i'
{3398, 6, 34, 9, 0, -25}, // 0x6A 'j'
{3424, 16, 26, 18, 2, -25}, // 0x6B 'k'
{3476, 3, 26, 7, 2, -25}, // 0x6C 'l'
{3486, 24, 19, 28, 2, -18}, // 0x6D 'm'
{3543, 15, 19, 19, 2, -18}, // 0x6E 'n'
{3579, 17, 19, 19, 1, -18}, // 0x6F 'o'
{3620, 16, 25, 20, 2, -18}, // 0x70 'p'
{3670, 17, 25, 20, 1, -18}, // 0x71 'q'
{3724, 9, 19, 12, 2, -18}, // 0x72 'r'
{3746, 14, 19, 17, 2, -18}, // 0x73 's'
{3780, 7, 23, 10, 1, -22}, // 0x74 't'
{3801, 15, 19, 19, 2, -18}, // 0x75 'u'
{3837, 17, 19, 17, 0, -18}, // 0x76 'v'
{3878, 25, 19, 25, 0, -18}, // 0x77 'w'
{3938, 16, 19, 17, 0, -18}, // 0x78 'x'
{3976, 17, 27, 17, 0, -18}, // 0x79 'y'
{4034, 15, 19, 17, 1, -18}, // 0x7A 'z'
{4070, 8, 33, 12, 1, -25}, // 0x7B '{'
{4103, 2, 33, 9, 3, -25}, // 0x7C '|'
{4112, 8, 33, 12, 3, -25}, // 0x7D '}'
{4145, 15, 7, 18, 1, -15}}; // 0x7E '~'
const GFXfont FreeSans18pt7b PROGMEM = {(uint8_t *)FreeSans18pt7bBitmaps,
(GFXglyph *)FreeSans18pt7bGlyphs, 0x20,
0x7E, 42};
// Approx. 4831 bytes

Wyświetl plik

@ -12,6 +12,9 @@ extern WiFiClient client;
//static const char *ftpserver = "www.ngs.noaa.gov";
char outbuf[128];
uint8_t ephstate = EPH_NOTUSED;
//enum EPHSTATE { EPH_NOTUSED, EPH_PENDING, EPH_TIMEERR, EPH_ERROR, EPH_EPHERROR, EPH_GOOD };
const char *ephtxt[] = { "Disabled", "Pending", "Time error", "Fetch error", "Read error", "Good" };
uint8_t getreply() {
String s = client.readStringUntil('\n');
@ -45,10 +48,12 @@ void writeFully(File &file, uint8_t *buf, size_t len)
void geteph() {
// Set current time via network...
ephstate = EPH_PENDING;
struct tm tinfo;
configTime(0, 0, "pool.ntp.org");
bool ok = getLocalTime(&tinfo, 2000); // wait max 2 seconds to get current time via ntp
if(!ok) {
ephstate = EPH_TIMEERR;
Serial.println("Failed to get current date/time");
return;
}
@ -66,6 +71,7 @@ void geteph() {
if(tsstr && strlen(tsstr)>=9) {
if(strcmp(nowstr, ts.c_str())<=0) {
Serial.println("local brdc is up to date\n");
ephstate = EPH_GOOD;
return;
}
}
@ -221,6 +227,7 @@ void geteph() {
snprintf(buf, 16, "Done: %d B ",total);
buf[16]=0;
disp.rdis->drawString(0,5*dispys,buf);
ephstate = EPH_GOOD;
delay(1000);
free(obuf);

Wyświetl plik

@ -0,0 +1,11 @@
#include <inttypes.h>
#ifndef GETEPH_H
#define GETEPH_H
void geteph();
enum EPHSTATE { EPH_NOTUSED, EPH_PENDING, EPH_TIMEERR, EPH_ERROR, EPH_EPHERROR, EPH_GOOD };
extern uint8_t ephstate;
extern const char *ephtxt[];
#endif

Wyświetl plik

@ -24,13 +24,11 @@ void MQTT::init(const char* host, uint16_t port, const char* id, const char *use
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);
char buffer[20];
snprintf(buffer, 20, "%s%6ld", id, random(0, 1000));
mqttClient.setClientId(buffer);
if (strlen(password) > 0) {
mqttClient.setCredentials(username, password);
}
@ -73,16 +71,15 @@ void MQTT::publishPacket(SondeInfo *s)
"\"dir\": %.1f,"
"\"sats\": %d,"
"\"validPos\": %d,"
"\"time\": %d,"
"\"sec\": %d,"
"\"frame\": %d,"
"\"time\": %u,"
"\"frame\": %u,"
"\"validTime\": %d,"
"\"rssi\": %d,"
"\"afc\": %d,"
"\"rxStat\": \"%s\","
"\"rxStart\": %d,"
"\"norxStart\": %d,"
"\"viewStart\": %d,"
"\"rxStart\": %u,"
"\"norxStart\": %u,"
"\"viewStart\": %u,"
"\"lastState\": %d,"
"\"launchKT\": %d,"
"\"burstKT\": %d,"
@ -104,7 +101,6 @@ void MQTT::publishPacket(SondeInfo *s)
s->sats,
s->validPos,
s->time,
s->sec,
s->frame,
(int)s->validTime,
s->rssi,

Wyświetl plik

@ -13,7 +13,6 @@ public:
TimerHandle_t mqttReconnectTimer;
IPAddress ip;
uint16_t port;
const char *id;
const char *username;
const char *password;
const char *prefix;

Wyświetl plik

@ -78,174 +78,6 @@ void rotZ(double x1, double y1, double z1, double angle, double *x2, double *y2,
/* ---------------------------------------------------------------------------------------------------- */
#if 0
int read_SEMalmanac(FILE *fp, EPHEM_t *alm) {
int l, j;
char buf[64];
unsigned n, week, toa, ui;
double dbl;
l = fscanf(fp, "%u", &n); if (l != 1) return -1;
l = fscanf(fp, "%s", buf); if (l != 1) return -1;
l = fscanf(fp, "%u", &week); if (l != 1) return -1;
l = fscanf(fp, "%u", &toa); if (l != 1) return -1;
for (j = 1; j <= n; j++) {
//memset(&ephem, 0, sizeof(ephem));
alm[j].week = (uint16_t)week;
alm[j].toa = (uint32_t)toa;
alm[j].toe = (double)toa;
alm[j].toc = alm[j].toe;
l = fscanf(fp, "%u", &ui); if (l != 1) return -1; alm[j].prn = (uint16_t)ui;
l = fscanf(fp, "%u", &ui); if (l != 1) return -2; alm[j].svn = (uint16_t)ui;
l = fscanf(fp, "%u", &ui); if (l != 1) return -3; alm[j].ura = (uint8_t)ui;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -4; alm[j].e = dbl;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -5; alm[j].delta_i = dbl;
alm[j].i0 = (0.30 + alm[j].delta_i) * PI;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -6; alm[j].OmegaDot = dbl * PI;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -7; alm[j].sqrta = dbl;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -6; alm[j].Omega0 = dbl * PI;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -8; alm[j].w = dbl * PI;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -9; alm[j].M0 = dbl * PI;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -10; alm[j].af0 = dbl;
l = fscanf(fp, "%lf", &dbl); if (l != 1) return -11; alm[j].af1 = dbl;
alm[j].af2 = 0;
alm[j].crc = 0;
alm[j].crs = 0;
alm[j].cuc = 0;
alm[j].cus = 0;
alm[j].cic = 0;
alm[j].cis = 0;
alm[j].tgd = 0;
alm[j].idot = 0;
alm[j].delta_n = 0;
l = fscanf(fp, "%u", &ui); if (l != 1) return -12; alm[j].health = (uint8_t)ui;
l = fscanf(fp, "%u", &ui); if (l != 1) return -13; alm[j].conf = (uint8_t)ui;
}
return 0;
}
int read_RNXephemeris(FILE *fp, EPHEM_t eph[][24]) {
int l, i;
char buf[64], str[20];
char buf_header[83];
//buf_data[80]; // 3 + 4*19 = 79
char *pbuf;
unsigned ui;
double dbl;
int c;
EPHEM_t ephem = {};
int hr = 0;
do {
//l = fread(buf_header, 81, 1, fp); // Zeilen in Header sind nicht immer mit Leerzeichen aufgefuellt
pbuf = fgets(buf_header, 82, fp); // max 82-1 Zeichen + '\0'
buf_header[82] = '\0'; // doppelt haelt besser
//l = strlen(buf_header);
} while ( pbuf && !strstr(buf_header, "END OF HEADER") );
//l = fread(buf_data, 80, 1, fp);
//buf_data[79] = '\0';
while (hr < 24) { // brdc/hour-rinex sollte nur Daten von einem Tag enthalten
//memset(&ephem, 0, sizeof(ephem));
l = fread(buf, 3, 1, fp); if (l != 1) break; buf[ 3] = 0; sscanf(buf, "%d", &ui);
ephem.prn = ui;
for (i = 0; i < 16; i++) ephem.epoch[i] = '0';
ephem.epoch[16] = '\0';
l = fread(buf, 19, 1, fp); if (l != 1) break; buf[19] = 0;
for (i = 0; i < 6; i++) {
c = buf[3*i ]; if (c == ' ') c = '0'; str[2*i ] = c;
c = buf[3*i+1]; if (c == ' ') c = '0'; str[2*i+1] = c;
}
str[12] = buf[17];
str[13] = buf[18];
str[14] = '\0';
strncpy(ephem.epoch , "20", 2); // vorausgesetzt 21.Jhd; Datum steht auch im Header
strncpy(ephem.epoch+2, str, 15);
ephem.epoch[16] = '\0';
strncpy(str, buf+9, 2); str[2] = '\0';
hr = atoi(str);
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.af0 = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.af1 = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.af2 = dbl;
if ((c=fgetc(fp)) == EOF) break;
l = fread(buf, 3, 1, fp); if (l != 1) break; buf[ 3] = 0;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.iode = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.crs = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.delta_n = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.M0 = dbl;
if ((c=fgetc(fp)) == EOF) break;
l = fread(buf, 3, 1, fp); if (l != 1) break; buf[ 3] = 0;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.cuc = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.e = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.cus = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.sqrta = dbl;
if ((c=fgetc(fp)) == EOF) break;
l = fread(buf, 3, 1, fp); if (l != 1) break; buf[ 3] = 0;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.toe = dbl;
ephem.toc = ephem.toe;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.cic = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.Omega0 = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.cis = dbl;
if ((c=fgetc(fp)) == EOF) break;
l = fread(buf, 3, 1, fp); if (l != 1) break; buf[ 3] = 0;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.i0 = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.crc = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.w = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.OmegaDot = dbl;
if ((c=fgetc(fp)) == EOF) break;
l = fread(buf, 3, 1, fp); if (l != 1) break; buf[ 3] = 0;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.idot = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.codeL2 = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.gpsweek = (int)dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.iodc = dbl;
if ((c=fgetc(fp)) == EOF) break;
l = fread(buf, 3, 1, fp); if (l != 1) break; buf[ 3] = 0;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.sva = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.health = (uint8_t)(dbl+0.1);
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); ephem.tgd = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.iodc = dbl;
if ((c=fgetc(fp)) == EOF) break;
l = fread(buf, 3, 1, fp); if (l != 1) break; buf[ 3] = 0;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.ttom = dbl;
pbuf = fgets(buf_header, 82, fp);
/* // die letzten beiden Felder (spare) sind manchmal leer (statt 0.00); manchmal fehlt sogar das drittletzte Feld
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.fit = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.spare1 = dbl;
l = fread(buf, 19, 1, fp); if (l != 1) break; if (buf[15] == 'D') buf[15] = 'E'; buf[19] = 0; sscanf(buf, "%lf", &dbl); //ephem.spare2 = dbl;
if ((c=fgetc(fp)) == EOF) break; */
ephem.week = 1; // ephem.gpsweek
eph[ephem.prn][hr] = ephem;
if (pbuf == NULL) break;
}
return 0;
}
#endif
static EPHEM_t *te;
@ -254,17 +86,13 @@ static EPHEM_t *te;
#define fgetc(file) (char)file.read()
//EPHEM_t *read_RNXpephs(FILE *fp) {
EPHEM_t *read_RNXpephs(const char *file) {
int l, i;
//char buffer[86];
char buf[64], str[20];
unsigned ui;
double dbl;
int c;
EPHEM_t ephem = {};
// int count = 0;
//long fpos;
File fp = SPIFFS.open(file, "r");
if(!fp) { Serial.printf("Error opening %s\n", file); }
@ -277,23 +105,7 @@ EPHEM_t *read_RNXpephs(const char *file) {
Serial.printf("Skipping header: %s\n", line.c_str());
} while ( fp.available() && !strstr((const char *)line.c_str(), "END OF HEADER") );
if (!fp.available()) return NULL;
/*
fpos = ftell(fp);
count = 0;
while (count >= 0) { // data-Zeilen: 79 Zeichen
pbuf = fgets(buffer, 84, fp); if (pbuf == 0) break;
strncpy(str, buffer, 3);
str[3] = '\0';
sscanf(str, "%d", &ui);
if (ui < 33) count++;
for (i = 1; i < 8; i++) {
pbuf = fgets(buffer, 84, fp); if (pbuf == 0) break;
}
}
printf("Ephemerides: %d total=%d\n", count, count*sizeof(ephem));
fseek(fp, fpos, SEEK_SET);
*/
if(te) free(te);
te = (EPHEM_t *)calloc( 34, sizeof(ephem) ); // calloc( 1, sizeof(ephem) );
if (te == NULL) return NULL;

Wyświetl plik

@ -41,24 +41,23 @@
*/
#if 1
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <stdint.h>
#endif
#include <SPIFFS.h>
#include "nav_gps_vel.h"
#include "rs92gps.h"
#include "geteph.h"
#include "Sonde.h"
gpx_t gpx;
int option_verbose = 0, // ausfuehrliche Anzeige
const int option_verbose = 0, // ausfuehrliche Anzeige
option_raw = 1, // rohe Frames
option_inv = 0, // invertiert Signal
option_res = 0, // genauere Bitmessung
@ -83,25 +82,6 @@ int almanac = 0,
int exSat = -1;
#if 0
/* --- RS92-SGP: 8N1 manchester --- */
#define BITS (2*(1+8+1)) // 20
#define HEADOFS 40 // HEADOFS+HEADLEN = 120 (bis 0x10)
#define HEADLEN 80 // (HEADOFS+HEADLEN) mod BITS = 0
/*
#define HEADOFS 0 // HEADOFS muss 0 wegen Wiederholung
#define HEADLEN 60 // HEADLEN < 100, (HEADOFS+HEADLEN) mod BITS = 0
*/
#define FRAMESTART ((HEADOFS+HEADLEN)/BITS)
/* 2A 10*/
char header[] = "10100110011001101001"
"10100110011001101001"
"10100110011001101001"
"10100110011001101001"
"1010011001100110100110101010100110101001";
char buf[HEADLEN+1] = "x";
#endif
int bufpos = -1;
@ -143,225 +123,7 @@ int findstr(char *buff, char *str, int pos) {
return i;
}
#if 0
int read_wav_header(FILE *fp) {
char txt[4+1] = "\0\0\0\0";
unsigned char dat[4];
int byte, p=0;
if (fread(txt, 1, 4, fp) < 4) return -1;
if (strncmp(txt, "RIFF", 4)) return -1;
if (fread(txt, 1, 4, fp) < 4) return -1;
// pos_WAVE = 8L
if (fread(txt, 1, 4, fp) < 4) return -1;
if (strncmp(txt, "WAVE", 4)) return -1;
// pos_fmt = 12L
for ( ; ; ) {
if ( (byte=fgetc(fp)) == EOF ) return -1;
txt[p % 4] = byte;
p++; if (p==4) p=0;
if (findstr(txt, "fmt ", p) == 4) break;
}
if (fread(dat, 1, 4, fp) < 4) return -1;
if (fread(dat, 1, 2, fp) < 2) return -1;
if (fread(dat, 1, 2, fp) < 2) return -1;
channels = dat[0] + (dat[1] << 8);
if (fread(dat, 1, 4, fp) < 4) return -1;
memcpy(&sample_rate, dat, 4); //sample_rate = dat[0]|(dat[1]<<8)|(dat[2]<<16)|(dat[3]<<24);
if (fread(dat, 1, 4, fp) < 4) return -1;
if (fread(dat, 1, 2, fp) < 2) return -1;
//byte = dat[0] + (dat[1] << 8);
if (fread(dat, 1, 2, fp) < 2) return -1;
bits_sample = dat[0] + (dat[1] << 8);
// pos_dat = 36L + info
for ( ; ; ) {
if ( (byte=fgetc(fp)) == EOF ) return -1;
txt[p % 4] = byte;
p++; if (p==4) p=0;
if (findstr(txt, "data", p) == 4) break;
}
if (fread(dat, 1, 4, fp) < 4) return -1;
Serial.printf("sample_rate: %d\n", sample_rate);
Serial.printf("bits : %d\n", bits_sample);
Serial.printf("channels : %d\n", channels);
if ((bits_sample != 8) && (bits_sample != 16)) return -1;
samples_per_bit = sample_rate/(float)BAUD_RATE;
Serial.printf("samples/bit: %.2f\n", samples_per_bit);
return 0;
}
#endif
#if 0
#define EOF_INT 0x1000000
#define LEN_movAvg 3
int movAvg[LEN_movAvg];
unsigned long sample_count = 0;
double bitgrenze = 0;
int read_signed_sample(FILE *fp) { // int = i32_t
int byte, i, sample, s=0; // EOF -> 0x1000000
for (i = 0; i < channels; i++) {
// i = 0: links bzw. mono
byte = fgetc(fp);
if (byte == EOF) return EOF_INT;
if (i == 0) sample = byte;
if (bits_sample == 16) {
byte = fgetc(fp);
if (byte == EOF) return EOF_INT;
if (i == 0) sample += byte << 8;
}
}
if (bits_sample == 8) s = sample-128; // 8bit: 00..FF, centerpoint 0x80=128
if (bits_sample == 16) s = (short)sample;
if (option_avg) {
movAvg[sample_count % LEN_movAvg] = s;
s = 0;
for (i = 0; i < LEN_movAvg; i++) s += movAvg[i];
s = (s+0.5) / LEN_movAvg;
}
sample_count++;
return s;
}
int par=1, par_alt=1;
int read_bits_fsk(FILE *fp, int *bit, int *len) {
static int sample;
int n, y0;
float l, x1;
static float x0;
n = 0;
do{
y0 = sample;
sample = read_signed_sample(fp);
if (sample == EOF_INT) return EOF;
//sample_count++; // in read_signed_sample()
par_alt = par;
par = (sample >= 0) ? 1 : -1; // 8bit: 0..127,128..255 (-128..-1,0..127)
n++;
} while (par*par_alt > 0);
if (!option_res) l = (float)n / samples_per_bit;
else { // genauere Bitlaengen-Messung
x1 = sample/(float)(sample-y0); // hilft bei niedriger sample rate
l = (n+x0-x1) / samples_per_bit; // meist mehr frames (nicht immer)
x0 = x1;
}
*len = (int)(l+0.5);
if (!option_inv) *bit = (1+par_alt)/2; // oben 1, unten -1
else *bit = (1-par_alt)/2; // sdr#<rev1381?, invers: unten 1, oben -1
/* Y-offset ? */
return 0;
}
int bitstart = 0;
int read_rawbit(FILE *fp, int *bit) {
int sample;
int n, sum;
sum = 0;
n = 0;
if (bitstart) {
n = 1; // d.h. bitgrenze = sample_count-1 (?)
bitgrenze = sample_count-1;
bitstart = 0;
}
bitgrenze += samples_per_bit;
do {
sample = read_signed_sample(fp);
if (sample == EOF_INT) return EOF;
//sample_count++; // in read_signed_sample()
//par = (sample >= 0) ? 1 : -1; // 8bit: 0..127,128..255 (-128..-1,0..127)
sum += sample;
n++;
} while (sample_count < bitgrenze); // n < samples_per_bit
if (sum >= 0) *bit = 1;
else *bit = 0;
if (option_inv) *bit ^= 1;
return 0;
}
/* ------------------------------------------------------------------------------------ */
// manchester1 1->10,0->01: 1.bit
// manchester2 0->10,1->01: 2.bit
// RS92-SGP: 8N1 manchester2
char manch(char *mbits) {
if ((mbits[0] == 1) && (mbits[1] == 0)) return 0;
else if ((mbits[0] == 0) && (mbits[1] == 1)) return 1;
else return -1;
}
int bits2byte(char bits[]) {
int i, byteval=0, d=1;
int bit8[8];
if (manch(bits+0) != 0) return 0x100;
for (i = 0; i < 8; i++) {
bit8[i] = manch(bits+2*(i+1));
}
if (manch(bits+(2*(8+1))) != 1) return 0x100;
for (i = 0; i < 8; i++) { // little endian
if (bit8[i] == 1) byteval += d;
else if (bit8[i] == 0) byteval += 0;
else return 0x100;
d <<= 1;
}
return byteval;
}
void inc_bufpos() {
bufpos = (bufpos+1) % HEADLEN;
}
int compare() {
int i=0, j = bufpos;
while (i < HEADLEN) {
if (j < 0) j = HEADLEN-1;
if (buf[j] != header[HEADOFS+HEADLEN-1-i]) break;
j--;
i++;
}
return i;
}
#endif
/*
uint8_t xorbyte(int pos) {
return xframe[pos] ^ mask[pos % MASK_LEN];
}
*/
uint8_t framebyte(int pos) {
return frame[pos];
}
@ -698,53 +460,6 @@ void prn12(uint8_t *prn_le, uint8_t prns[12]) {
}
int calc_satpos_alm(EPHEM_t alm[], double t, SAT_t *satp) {
return -1;
#if 0
double X, Y, Z, vX, vY, vZ;
int j;
int week;
double cl_corr, cl_drift;
for (j = 1; j < 33; j++) {
if (alm[j].prn > 0) { // prn==j
// Woche hat 604800 sec
if (t-alm[j].toa > WEEKSEC/2) rollover = +1;
else if (t-alm[j].toa < -WEEKSEC/2) rollover = -1;
else rollover = 0;
week = alm[j].week - rollover;
/*if (j == 1)*/ gpx.week = week + GPS_WEEK1024*1024;
if (option_vel >= 2) {
GPS_SatellitePositionVelocity_Ephem(
week, t, alm[j],
&cl_corr, &cl_drift, &X, &Y, &Z, &vX, &vY, &vZ
);
satp[alm[j].prn].clock_drift = cl_drift;
satp[alm[j].prn].vX = vX;
satp[alm[j].prn].vY = vY;
satp[alm[j].prn].vZ = vZ;
}
else {
GPS_SatellitePosition_Ephem(
week, t, alm[j],
&cl_corr, &X, &Y, &Z
);
}
satp[alm[j].prn].X = X;
satp[alm[j].prn].Y = Y;
satp[alm[j].prn].Z = Z;
satp[alm[j].prn].clock_corr = cl_corr;
}
}
return 0;
#endif
}
int calc_satpos_rnx(EPHEM_t eph[][24], double t, SAT_t *satp) {
double X, Y, Z, vX, vY, vZ;
int j, i, ti;
@ -924,12 +639,10 @@ int get_pseudorange() {
// GPS Sat Pos (& Vel)
//if (almanac) calc_satpos_alm( alm, gpstime/1000.0, sat);
if (ephem) calc_satpos_rnx2(ephs, gpstime/1000.0, sat);
// GPS Sat Pos t -= 1s
if (option_vel == 1) {
//if (almanac) calc_satpos_alm( alm, gpstime/1000.0-1, sat1s);
if (ephem) calc_satpos_rnx2(ephs, gpstime/1000.0-1, sat1s);
}
@ -1115,27 +828,33 @@ int naiv_2Dfix(int N, SAT_t sats[], double alt) {
int get_GPSkoord(int N) {
double lat, lon, alt, rx_cl_bias;
double vH, vD, vU;
double lat1s, lon1s, alt1s,
lat0 , lon0 , alt0 , pos0_ecef[3];
double pos_ecef[3], pos1s_ecef[3], dpos_ecef[3],
double pos_ecef[3], dpos_ecef[3],
vel_ecef[3], dvel_ecef[3];
double gdop, gdop0 = 1000.0;
//double hdop, vdop, pdop;
int i0, i1, i2, i3, j, k, n;
int i0, i1, i2, i3, j;
int nav_ret = 0;
int num = 0;
SAT_t Sat_A[4];
#if 0
int k, n;
double lat1s, lon1s, alt1s,
lat0 , lon0 , alt0 , pos0_ecef[3];
double pos1s_ecef[3];
SAT_t Sat_B[12]; // N <= 12
SAT_t Sat_B1s[12];
SAT_t Sat_C[12]; // 11
double diter = 0;
int exN = -1;
#endif
double diter = 0;
#if 0
if (option_vergps == 8) {
fprintf(stdout, " sats: ");
for (j = 0; j < N; j++) fprintf(stdout, "%02d ", prn[j]);
fprintf(stdout, "\n");
}
#endif
gpx.lat = gpx.lon = gpx.alt = 0;
@ -1166,6 +885,7 @@ int get_GPSkoord(int N) {
for (j=0; j<3; j++) vel_ecef[j] += dvel_ecef[j];
get_GPSvel(lat, lon, vel_ecef, &vH, &vD, &vU);
}
#if 0
if (option_vergps == 8) {
// gdop = sqrt(DOP[0]+DOP[1]+DOP[2]+DOP[3]); // s.o.
//hdop = sqrt(DOP[0]+DOP[1]);
@ -1186,6 +906,7 @@ int get_GPSkoord(int N) {
fprintf(stdout, "\n");
}
}
#endif
}
else gdop = -1;
@ -1209,6 +930,7 @@ int get_GPSkoord(int N) {
}}}}
}
#if 0
if (option_vergps == 8 || option_vergps == 2) {
for (j = 0; j < N; j++) Sat_B[j] = sat[prn[j]];
@ -1335,6 +1057,7 @@ int get_GPSkoord(int N) {
}
}
#endif
return num;
}
@ -1472,264 +1195,10 @@ void get_eph(const char *file) {
if (ephs) {
ephem = 1;
almanac = 0;
}
} else {
ephstate = EPH_EPHERROR;
}
Serial.printf("reading RNX done, result is %d, ephs=%p\n", ephem, ephs);
if (!option_der) d_err = 1000;
}
#if 0
int main(int argc, char *argv[]) {
FILE *fp, *fp_alm = NULL, *fp_eph = NULL;
char *fpname;
char bitbuf[BITS];
int bit_count = 0,
byte_count = FRAMESTART,
header_found = 0,
byte, i;
int bit, len;
char *pbuf = NULL;
#ifdef CYGWIN
_setmode(_fileno(stdin), _O_BINARY);
#endif
setbuf(stdout, NULL);
fpname = argv[0];
++argv;
while ((*argv) && (!fileloaded)) {
if ( (strcmp(*argv, "-h") == 0) || (strcmp(*argv, "--help") == 0) ) {
Serial.printf("%s [options] <file>\n", fpname);
Serial.printf(" file: audio.wav or raw_data\n");
Serial.printf(" options:\n");
Serial.printf(" --vel; --vel1, --vel2 (-g2)\n");
Serial.printf(" -v, -vx, -vv\n");
Serial.printf(" -r, --raw\n");
Serial.printf(" -i, --invert\n");
Serial.printf(" -a, --almanac <almanacSEM>\n");
Serial.printf(" -e, --ephem <ephemperisRinex>\n");
Serial.printf(" -g1 (verbose GPS: 4 sats)\n");
Serial.printf(" -g2 (verbose GPS: all sats)\n");
Serial.printf(" -gg (vverbose GPS)\n");
Serial.printf(" --crc (CRC check GPS)\n");
Serial.printf(" --rawin1,2 (raw_data file)\n");
return 0;
}
else if ( (strcmp(*argv, "--vel") == 0) ) {
option_vel = 4;
}
else if ( (strcmp(*argv, "--vel1") == 0) ) {
option_vel = 1;
if (option_vergps < 1) option_vergps = 2;
}
else if ( (strcmp(*argv, "--vel2") == 0) ) {
option_vel = 2;
if (option_vergps < 1) option_vergps = 2;
}
else if ( (strcmp(*argv, "--iter") == 0) ) {
option_iter = 1;
}
else if ( (strcmp(*argv, "-v") == 0) ) {
option_verbose = 1;
}
else if ( (strcmp(*argv, "-vv") == 0) ) {
option_verbose = 4;
}
else if ( (strcmp(*argv, "-vx") == 0) ) {
option_aux = 1;
}
else if (strcmp(*argv, "--crc") == 0) { option_crc = 1; }
else if ( (strcmp(*argv, "-r") == 0) || (strcmp(*argv, "--raw") == 0) ) {
option_raw = 1;
}
else if ( (strcmp(*argv, "-i") == 0) || (strcmp(*argv, "--invert") == 0) ) {
option_inv = 1;
}
else if ( (strcmp(*argv, "-a") == 0) || (strcmp(*argv, "--almanac") == 0) ) {
++argv;
if (*argv) fp_alm = fopen(*argv, "r"); // txt-mode
else return -1;
if (fp_alm == NULL) Serial.printf("[almanac] %s konnte nicht geoeffnet werden\n", *argv);
}
else if ( (strcmp(*argv, "-e") == 0) || (strncmp(*argv, "--ephem", 7) == 0) ) {
++argv;
if (*argv) fp_eph = fopen(*argv, "rb"); // bin-mode
else return -1;
if (fp_eph == NULL) Serial.printf("[rinex] %s konnte nicht geoeffnet werden\n", *argv);
}
else if ( (strcmp(*argv, "--dop") == 0) ) {
++argv;
if (*argv) {
dop_limit = atof(*argv);
if (dop_limit <= 0 || dop_limit >= 100) dop_limit = 9.9;
}
else return -1;
}
else if ( (strcmp(*argv, "--der") == 0) ) {
++argv;
if (*argv) {
d_err = atof(*argv);
if (d_err <= 0 || d_err >= 100000) d_err = 10000;
else option_der = 1;
}
else return -1;
}
else if ( (strcmp(*argv, "--exsat") == 0) ) {
++argv;
if (*argv) {
exSat = atoi(*argv);
if (exSat < 1 || exSat > 32) exSat = -1;
}
else return -1;
}
else if (strcmp(*argv, "-g1") == 0) { option_vergps = 1; } // verbose1 GPS
else if (strcmp(*argv, "-g2") == 0) { option_vergps = 2; } // verbose2 GPS (bancroft)
else if (strcmp(*argv, "-gg") == 0) { option_vergps = 8; } // vverbose GPS
else if (strcmp(*argv, "--rawin1") == 0) { rawin = 2; } // raw_txt input1
else if (strcmp(*argv, "--rawin2") == 0) { rawin = 3; } // raw_txt input2 (SM)
else if ( (strcmp(*argv, "--avg") == 0) ) {
option_avg = 1;
}
else if (strcmp(*argv, "-b") == 0) { option_b = 1; }
else {
if (!rawin) fp = fopen(*argv, "rb");
else fp = fopen(*argv, "r");
if (fp == NULL) {
Serial.printf("%s konnte nicht geoeffnet werden\n", *argv);
return -1;
}
fileloaded = 1;
}
++argv;
}
if (!fileloaded) fp = stdin;
if (fp_alm) {
i = read_SEMalmanac(fp_alm, alm);
if (i == 0) {
almanac = 1;
}
fclose(fp_alm);
if (!option_der) d_err = 4000;
}
if (fp_eph) {
/* i = read_RNXephemeris(fp_eph, eph);
if (i == 0) {
ephem = 1;
almanac = 0;
}
fclose(fp_eph); */
ephs = read_RNXpephs(fp_eph);
if (ephs) {
ephem = 1;
almanac = 0;
}
fclose(fp_eph);
if (!option_der) d_err = 1000;
}
if (!rawin) {
i = read_wav_header(fp);
if (i) {
fclose(fp);
return -1;
}
while (!read_bits_fsk(fp, &bit, &len)) {
if (len == 0) { // reset_frame();
if (byte_count > pos_SondeID+8) {
if (byte_count < FRAME_LEN-20) err_gps = 1;
print_frame(byte_count);
err_gps = 0;
}
bit_count = 0;
byte_count = FRAMESTART;
header_found = 0;
inc_bufpos();
buf[bufpos] = 'x';
continue; // ...
}
for (i = 0; i < len; i++) {
inc_bufpos();
buf[bufpos] = 0x30 + bit; // Ascii
if (!header_found) {
if (compare() >= HEADLEN) header_found = 1;
}
else {
bitbuf[bit_count] = bit;
bit_count++;
if (bit_count == BITS) {
bit_count = 0;
byte = bits2byte(bitbuf);
frame[byte_count] = byte;
byte_count++;
if (byte_count == FRAME_LEN) {
byte_count = FRAMESTART;
header_found = 0;
//inc_bufpos();
//buf[bufpos] = 'x';
print_frame(FRAME_LEN);
}
}
}
}
if (header_found && option_b) {
bitstart = 1;
while ( byte_count < FRAME_LEN ) {
if (read_rawbit(fp, &bit) == EOF) break;
bitbuf[bit_count] = bit;
bit_count++;
if (bit_count == BITS) {
bit_count = 0;
byte = bits2byte(bitbuf);
frame[byte_count] = byte;
byte_count++;
}
}
header_found = 0;
print_frame(byte_count);
byte_count = FRAMESTART;
}
}
}
else //if (rawin)
{
if (rawin == 3) frameofs = 5;
while (1 > 0) {
pbuf = fgets(buffer_rawin, rawin*FRAME_LEN+4, fp);
if (pbuf == NULL) break;
buffer_rawin[rawin*FRAME_LEN+1] = '\0';
len = strlen(buffer_rawin) / rawin;
if (len > pos_SondeID+8) {
for (i = 0; i < len-frameofs; i++) { //%2x SCNx8=%hhx(inttypes.h)
sscanf(buffer_rawin+rawin*i, "%2hhx", frame+frameofs+i);
// wenn ohne %hhx: sscanf(buffer_rawin+rawin*i, "%2x", &byte); frame[frameofs+i] = (uint8_t)byte;
}
if (len < FRAME_LEN-20) err_gps = 1;
print_frame(len);
err_gps = 0;
}
}
}
free(ephs);
fclose(fp);
return 0;
}
#endif

Wyświetl plik

@ -1,4 +1,4 @@
const char *version_name = "rdzTTGOsonde";
const char *version_id = "devel20210815";
const char *version_id = "devel20210914";
const int SPIFFS_MAJOR=2;
const int SPIFFS_MINOR=14;

Wyświetl plik

@ -0,0 +1,27 @@
RS41, RS92
ID: R1234567 (letter, 7 digits)
ShortID: Same as ID
Serial: Same is ID
DFM:
ID: D12345678 (D + 8 ditis)
ShortID: 12345678 (serial without "D")
Serial: Same as ID
M10:
ID: ME96231F0 (ME + 7 hex digits)
ShortID: M95231F0 (ID without "E")
Serial: 9062104592 (10 numerical digits, as written on sonde)
Serial on Sonde: 810 2 13028
Data in frame:
M10:
APRS: MEAABCCCC, AA=rx[95] in hex, B = rx[93] in hex, CCCC=rx[96:97| in hex
fullID: A0B C DEEEE, A=rx[95]/16, B=rx[95] in hex, C=rx[93] in hex, C= rx[112:113]/8192&7 ; EEEE=rx[96:97]&8191
M20:
APRS: MEAABBBBB, AA=rx[18] in hex, BBBBB=rx[19:20] in decimal
fullID: AAA-B-CCCCC, AAA=rx[18]%128 in decimal, B=1+(rx[18]>>7), CCCCC=rx[19:20] in decimal

Wyświetl plik

@ -1,3 +0,0 @@
void geteph();

Wyświetl plik

@ -10,24 +10,27 @@
[platformio]
src_dir = RX_FSK
lib_dir = libraries
lib_dir = RX_FSK
data_dir = RX_FSK/data
[extra]
lib_deps_builtin =
SondeLib
src
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/moononournation/Arduino_GFX
https://github.com/moononournation/Arduino_GFX#v1.1.5
; most recent has compile error (initialization order wrong)
; https://github.com/moononournation/Arduino_GFX
https://github.com/dx168b/async-mqtt-client
[env:ttgo-lora32]
platform = https://github.com/platformio/platform-espressif32.git
board = ttgo-lora32-v1
; board_build.partitions = partition.csv
framework = arduino
monitor_speed = 115200
lib_deps =

Wyświetl plik

@ -55,6 +55,7 @@ spiproc = subprocess.Popen([MKSPIFFS,'-c',data_dir,'-b','4096','-p','256','-s',s
spiproc.wait();
files_in = [
## for arduino esp32 2.0 ('bootloader', OFFSET_BOOTLOADER, esp32tools+"/sdk/esp32/bin/bootloader_dio_80m.bin"),
('bootloader', OFFSET_BOOTLOADER, esp32tools+"/sdk/bin/bootloader_dio_80m.bin"),
('partitions', OFFSET_PARTITIONS, file_part),
('bootapp0', OFFSET_BOOTAPP0, esp32tools+"/partitions/boot_app0.bin"),