Next master version with a few enhancements:

- Added RS92 support (decoding, ephemeris data download)
- DFM6 is working is well now
- Internal reorganisation: separate Task for SX1276 handling (no lost data in case
  main loop is too slow, important in particular for DFM and RS92)
- Better autodetection of board type
- Touch pins support (should work correctly now)
- Inital support for GPS chip (e.g. on T-Beam), not yet with nice display
pull/22/head
Hansi, dl9rdz 2019-06-08 15:51:36 +02:00
rodzic d8ea59ecdb
commit 46658ad10d
25 zmienionych plików z 6398 dodań i 368 usunięć

Wyświetl plik

@ -30,6 +30,7 @@ install:
- ln -s $PWD/libraries/SondeLib /usr/local/share/arduino/libraries/SondeLib
- ln -s $PWD/libraries/SX1278FSK /usr/local/share/arduino/libraries/SX1278FSK
- arduino --install-library "U8g2"
- arduino --install-library "MicroNMEA"
script:
- arduino --board esp32:esp32:ttgo-lora32-v1 --verify $PWD/RX_FSK/RX_FSK.ino
- find build

Wyświetl plik

@ -26,7 +26,7 @@ generate_website_index() {
done
echo "</ul></section></body></html>" >> download.html
git add download.html
git commit --message "Travis build: $TRAVIS_BUILD_NUMBER"
git commit --amend --message "Travis build: $TRAVIS_BUILD_NUMBER"
}
commit_website_files() {
BRANCH=$TRAVIS_BRANCH
@ -43,7 +43,7 @@ commit_website_files() {
git add ${BRANCH}/${VERSION}-full.bin
cp ${MYPATH}/build/RX_FSK.ino.bin ${BRANCH}/update.ino.bin
git add ${BRANCH}/update.ino.bin
# git commit --message "Travis build: $TRAVIS_BUILD_NUMBER"
git commit --message "Travis build: $TRAVIS_BUILD_NUMBER"
}
upload_files() {
git remote add origin-pages https://${GITHUB_API_KEY}@github.com/dl9rdz/rdz_ttgo_sonde.git > /dev/null 2>&1

Wyświetl plik

@ -7,12 +7,17 @@
#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"
// UNCOMMENT one of the constructor lines below
U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8 = NULL; // initialize later after reading config file
@ -23,12 +28,12 @@ U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8 = NULL; // initialize later after readin
int LORA_LED = 9; // default POUT for LORA LED used as serial monitor
int e;
enum MainState { ST_DECODER, ST_SCANNER, ST_SPECTRUM, ST_WIFISCAN, ST_UPDATE };
enum MainState { ST_DECODER, ST_SPECTRUM, ST_WIFISCAN, ST_UPDATE };
static MainState mainState = ST_WIFISCAN; // ST_WIFISCAN;
AsyncWebServer server(80);
String updateHost = "rdzsonde.my.to";
String updateHost = "rdzsonde.mooo.com";
int updatePort = 80;
String updateBinM = "/master/update.ino.bin";
String updateBinD = "/devel/update.ino.bin";
@ -43,16 +48,22 @@ WiFiClient client;
enum KeyPress { KP_NONE = 0, KP_SHORT, KP_DOUBLE, KP_MID, KP_LONG };
// "doublepress" is now also used to eliminate key glitch on TTGO T-Beam startup (SENSOR_VN/GPIO39)
struct Button {
uint8_t pin;
uint32_t numberKeyPresses;
KeyPress pressed;
unsigned long press_ts;
boolean doublepress;
unsigned long keydownTime;
int8_t doublepress;
bool isTouched;
};
Button button1 = {0, 0, KP_NONE, 0, false};
Button button1 = {0, 0, KP_NONE, 0, -1, false};
Button button2 = {0, 0, KP_NONE, 0, -1, false};
static int lastDisplay = 1;
static int currentDisplay = 1;
// Set LED GPIO
int ledPin = 1;
// Stores LED state
@ -85,7 +96,7 @@ String processor(const String& var) {
const String sondeTypeSelect(int activeType) {
String sts = "";
for (int i = 0; i < 3; i++) {
for (int i = 0; i < 4; i++) {
sts += "<option value=\"";
sts += sondeTypeStr[i];
sts += "\"";
@ -115,7 +126,7 @@ void setupChannelList() {
return;
}
int i = 0;
char launchsite[17];
char launchsite[17] = " ";
sonde.clearSonde();
Serial.println("Reading channel config:");
while (file.available()) {
@ -130,6 +141,8 @@ void setupChannelList() {
SondeType type;
if (space[1] == '4') {
type = STYPE_RS41;
} else if (space[1] == 'R') {
type = STYPE_RS92;
}
else if (space[1] == '9') {
type = STYPE_DFM09;
@ -140,16 +153,13 @@ void setupChannelList() {
else continue;
int active = space[3] == '+' ? 1 : 0;
if (space[4] == ' ') {
sitename = line.substring(12) + " "; // Don't change start of substr(12) !!!!
int str_len = sitename.length() + 1;
sitename.toCharArray(launchsite, 17);
memset(launchsite, ' ', 16);
int str_len = strlen(space + 5);
strncpy(launchsite, space + 5, str_len > 16 ? 16 : str_len);
if (sonde.config.debug == 1) {
Serial.printf("Add %f - sondetype: %d (on/off: %d) - site #%d - name: %s\n ", freq, type, active, i, launchsite);
//Serial.println(sitename);
}
}
sonde.addSonde(freq, type, active, launchsite);
i++;
}
@ -212,7 +222,7 @@ const char *handleQRGPost(AsyncWebServerRequest *request) {
const char *tstr = tstring.c_str();
const char *sstr = sstring.c_str();
Serial.printf("Processing a=%s, f=%s, t=%s, site=%s\n", active ? "YES" : "NO", fstr, tstr, sstr);
char typech = (tstr[2] == '4' ? '4' : tstr[3]); // Ugly TODO
char typech = (tstr[2] == '4' ? '4' : tstr[2] == '9' ? 'R' : tstr[3]); // a bit ugly
file.printf("%3.3f %c %c %s\n", atof(fstr), typech, active ? '+' : '-', sstr);
}
file.close();
@ -221,6 +231,7 @@ const char *handleQRGPost(AsyncWebServerRequest *request) {
Serial.println();
delay(500);
setupChannelList();
return "";
}
@ -313,6 +324,7 @@ const char *handleWIFIPost(AsyncWebServerRequest *request) {
}
f.close();
setupWifiList();
return "";
}
// Show current status
@ -322,7 +334,7 @@ void addSondeStatus(char *ptr, int i)
strcat(ptr, "<table>");
sprintf(ptr + strlen(ptr), "<tr><td id=\"sfreq\">%3.3f MHz, Type: %s</td><tr><td>ID: %s</td></tr><tr><td>QTH: %.6f,%.6f h=%.0fm</td></tr>\n",
s->freq, sondeTypeStr[s->type],
s->validID ? s->id : "<??>",
s->validID ? s->id : "<?""?>",
s->lat, s->lon, s->alt);
sprintf(ptr + strlen(ptr), "<tr><td><a target=\"_empty\" href=\"geo:%.6f,%.6f\">GEO-App</a> - ", s->lat, s->lon);
sprintf(ptr + strlen(ptr), "<a target=\"_empty\" href=\"https://wx.dl2mf.de/?%s\">WX.DL2MF.de</a> - ", s->id);
@ -368,7 +380,9 @@ struct st_configitems config_list[] = {
/* General config settings */
{"wifi", "Wifi mode (0/1/2/3)", 0, &sonde.config.wifi},
{"debug", "Debug mode (0/1)", 0, &sonde.config.debug},
{"maxsonde", "Maxsonde (requires reboot?)", 0, &sonde.config.maxsonde},
{"maxsonde", "Maxsonde", 0, &sonde.config.maxsonde},
{"display", "Display mode (1/2/3)", 0, &sonde.config.display},
{"---", "---", -1, NULL},
/* Spectrum display settings */
{"spectrum", "ShowSpectrum (s)", 0, &sonde.config.spectrum},
{"startfreq", "Startfreq (MHz)", 0, &sonde.config.startfreq},
@ -397,16 +411,24 @@ struct st_configitems config_list[] = {
{"tcp.idformat", "DFM ID Format", -2, &sonde.config.tcpfeed.idformat},
{"tcp.highrate", "Rate limit", 0, &sonde.config.tcpfeed.highrate},
{"---", "---", -1, NULL},
/* RS41 decoder settings */
/* decoder settings */
{"rs41.agcbw", "RS41 AGC bandwidth", 0, &sonde.config.rs41.agcbw},
{"rs41.rxbw", "RS41 RX bandwidth", 0, &sonde.config.rs41.rxbw},
{"rs41.rxbw", "RS41 RX bandwidth", 0, &sonde.config.rs41.rxbw},
{"rs92.rxbw", "RS92 RX (and AGC) bandwidth", 0, &sonde.config.rs92.rxbw},
{"rs92.alt2d", "RS92 2D fix default altitude", 0, &sonde.config.rs92.alt2d},
{"dfm.agcbw", "DFM6/9 AGC bandwidth", 0, &sonde.config.dfm.agcbw},
{"dfm.rxbw", "DFM6/9 RX bandwidth", 0, &sonde.config.dfm.rxbw},
{"---", "---", -1, NULL},
/* Hardware dependeing settings */
{"oled_sda", "OLED SDA (needs reboot)", 0, &sonde.config.oled_sda},
{"oled_scl", "OLED SCL (needs reboot)", 0, &sonde.config.oled_scl},
{"oled_rst", "OLED RST (needs reboot)", 0, &sonde.config.oled_rst},
{"button_pin", "Button input port (needs reboot)", 0, &sonde.config.button_pin},
{"button_pin", "Button input port (needs reboot)", -4, &sonde.config.button_pin},
{"button2_pin", "Button 2 input port (needs reboot)", -4, &sonde.config.button2_pin},
{"touch_thresh", "Touch button threshold (needs reboot)", 0, &sonde.config.touch_thresh},
{"led_pout", "LED output port (needs reboot)", 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},
};
const static int N_CONFIG = (sizeof(config_list) / sizeof(struct st_configitems));
@ -418,6 +440,11 @@ void addConfigNumEntry(char *ptr, int idx, const char *label, int *value) {
sprintf(ptr + strlen(ptr), "<tr><td>%s</td><td><input name=\"CFG%d\" type=\"text\" value=\"%d\"/></td></tr>\n",
label, idx, *value);
}
void addConfigButtonEntry(char *ptr, int idx, const char *label, int *value) {
sprintf(ptr + strlen(ptr), "<tr><td>%s</td><td><input name=\"CFG%d\" type=\"text\" size=\"3\" value=\"%d\"/>",
label, idx, 127 & *value);
sprintf(ptr + strlen(ptr), "<input type=\"checkbox\" name=\"TO%d\"%s> Touch </td></tr>\n", idx, 128 & *value ? " checked" : "");
}
void addConfigTypeEntry(char *ptr, int idx, const char *label, int *value) {
// TODO
}
@ -430,7 +457,6 @@ void addConfigSeparatorEntry(char *ptr) {
const char *createConfigForm() {
char *ptr = message;
char tmp[4];
strcpy(ptr, "<html><head><link rel=\"stylesheet\" type=\"text/css\" href=\"style.css\"></head><body><form action=\"config.html\" method=\"post\"><table><tr><th>Option</th><th>Value</th></tr>");
for (int i = 0; i < N_CONFIG; i++) {
switch (config_list[i].type) {
@ -446,6 +472,9 @@ const char *createConfigForm() {
case 0:
addConfigNumEntry(ptr, i, config_list[i].label, (int *)config_list[i].data);
break;
case -4:
addConfigButtonEntry(ptr, i, config_list[i].label, (int *)config_list[i].data);
break;
default:
addConfigStringEntry(ptr, i, config_list[i].label, config_list[i].type, (char *)config_list[i].data);
break;
@ -457,7 +486,6 @@ const char *createConfigForm() {
const char *handleConfigPost(AsyncWebServerRequest *request) {
char label[10];
// parameters: a_i, f_1, t_i (active/frequency/type)
#if 1
File f = SPIFFS.open("/config.txt", "w");
@ -484,20 +512,33 @@ const char *handleConfigPost(AsyncWebServerRequest *request) {
AsyncWebParameter *value = request->getParam(label, true);
if (!value) continue;
String strvalue = value->value();
if (config_list[idx].type == -4) { // input button port with "touch" checkbox
char tmp[10];
snprintf(tmp, 10, "TO%d", idx);
AsyncWebParameter *touch = request->getParam(tmp, true);
if (touch) {
int i = atoi(strvalue.c_str()) + 128;
strvalue = String(i);
}
}
Serial.printf("Processing %s=%s\n", config_list[idx].name, strvalue.c_str());
f.printf("%s=%s\n", config_list[idx].name, strvalue.c_str());
}
f.close();
setupConfigData();
return "";
}
const char *ctrlid[]={"rx","scan","spec","wifi"};
const char *ctrllabel[]={"Receiver (short keypress)", "Scanner (double keypress)", "Spectrum (medium keypress)", "WiFi (long keypress)"};
const char *ctrlid[] = {"rx", "scan", "spec", "wifi", "rx2", "scan2", "spec2", "wifi2"};
const char *ctrllabel[] = {"Receiver (short keypress)", "Scanner (double keypress)", "Spectrum (medium keypress)", "WiFi (long keypress)",
"Button 2 (short keypress)", "Button 2 (double keypress)", "Button 2 (medium keypress)", "Button 2 (long keypress)"
};
const char *createControlForm() {
char *ptr = message;
char tmp[4];
strcpy(ptr, "<html><head><link rel=\"stylesheet\" type=\"text/css\" href=\"style.css\"></head><body><form action=\"control.html\" method=\"post\">");
for(int i=0; i<4; i++) {
for (int i = 0; i < 8; i++) {
strcat(ptr, "<input type=\"submit\" name=\"");
strcat(ptr, ctrlid[i]);
strcat(ptr, "\" value=\"");
@ -515,30 +556,88 @@ const char *handleControlPost(AsyncWebServerRequest *request) {
for (int i = 0; i < params; i++) {
String param = request->getParam(i)->name();
Serial.println(param.c_str());
if(param.equals("rx")) {
if (param.equals("rx")) {
Serial.println("equals rx");
button1.pressed = KP_SHORT;
}
else if(param.equals("scan")) {
else if (param.equals("scan")) {
Serial.println("equals scan");
button1.pressed = KP_DOUBLE;
}
else if(param.equals("spec")) {
else if (param.equals("spec")) {
Serial.println("equals spec");
button1.pressed = KP_MID;
}
else if(param.equals("wifi")) {
else if (param.equals("wifi")) {
Serial.println("equals wifi");
button1.pressed = KP_LONG;
}
else if (param.equals("rx2")) {
Serial.println("equals rx2");
button2.pressed = KP_SHORT;
}
else if (param.equals("scan2")) {
Serial.println("equals scan2");
button2.pressed = KP_DOUBLE;
}
else if (param.equals("spec2")) {
Serial.println("equals spec2");
button2.pressed = KP_MID;
}
else if (param.equals("wifi2")) {
Serial.println("equals wifi2");
button2.pressed = KP_LONG;
}
}
return "";
}
// bad idea. prone to buffer overflow. use at your own risk...
const char *createEditForm(String filename) {
char *ptr = message;
File file = SPIFFS.open("/" + filename, "r");
if (!file) {
Serial.println("There was an error opening the file '/config.txt' for reading");
return "<html><head><title>File not found</title></head><body>File not found</body></html>";
}
strcpy(ptr, "<html><head><title>Editor ");
strcat(ptr, filename.c_str());
strcat(ptr, "</title></head><body><form action=\"edit.html?file=");
strcat(ptr, filename.c_str());
strcat(ptr, "\" method=\"post\">");
strcat(ptr, "<textarea name=\"text\" cols=\"80\" rows=\"40\">");
while (file.available()) {
String line = file.readStringUntil('\n');
strcat(ptr, line.c_str()); strcat(ptr, "\n");
}
strcat(ptr, "</textarea><input type=\"submit\" value=\"Save\"></input></form></body></html>");
return message;
}
const char *handleEditPost(AsyncWebServerRequest *request) {
Serial.println("Handling post request");
AsyncWebParameter *filep = request->getParam("file");
if (!filep) return NULL;
String filename = filep->value();
AsyncWebParameter *textp = request->getParam("text", true);
if (!textp) return NULL;
String content = textp->value();
File file = SPIFFS.open("/" + filename, "w");
if (!file) {
Serial.println("There was an error opening the file '/" + filename + "'for writing");
return "";
}
file.print(content);
file.close();
return "";
}
const char *createUpdateForm(boolean run) {
char *ptr = message;
char tmp[4];
strcpy(ptr, "<html><head><link rel=\"stylesheet\" type=\"text/css\" href=\"style.css\"></head><body><form action=\"update.html\" method=\"post\">");
if(run) {
if (run) {
strcat(ptr, "<p>Doing update, wait until reboot</p>");
} else {
strcat(ptr, "<input type=\"submit\" name=\"master\" value=\"Master-Update\"></input><br><input type=\"submit\" name=\"devel\" value=\"Devel-Update\">");
@ -553,17 +652,18 @@ const char *handleUpdatePost(AsyncWebServerRequest *request) {
for (int i = 0; i < params; i++) {
String param = request->getParam(i)->name();
Serial.println(param.c_str());
if(param.equals("devel")) {
if (param.equals("devel")) {
Serial.println("equals devel");
updateBin = &updateBinD;
}
else if(param.equals("master")) {
else if (param.equals("master")) {
Serial.println("equals master");
updateBin = &updateBinM;
updateBin = &updateBinM;
}
}
Serial.println("Updating: "+*updateBin);
Serial.println("Updating: " + *updateBin);
enterMode(ST_UPDATE);
return "";
}
@ -606,7 +706,7 @@ void SetupAsyncServer() {
handleConfigPost(request);
request->send(200, "text/html", createConfigForm());
});
server.on("/status.html", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(200, "text/html", createStatusForm());
});
@ -625,7 +725,15 @@ void SetupAsyncServer() {
handleControlPost(request);
request->send(200, "text/html", createControlForm());
});
server.on("/edit.html", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(200, "text/html", createEditForm(request->getParam(0)->value()));
});
server.on("/edit.html", HTTP_POST, [](AsyncWebServerRequest * request) {
handleEditPost(request);
request->send(200, "text/html", createEditForm(request->getParam(0)->value()));
});
// Route to load style.css file
server.on("/style.css", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(SPIFFS, "/style.css", "text/css");
@ -682,18 +790,203 @@ const char *fetchWifiPw(const char *id) {
return NULL;
}
// It is not safe to call millis() in ISR!!!
// millis() does a division int64_t by 1000 for which gcc creates a library call
// on a 32bit system, and the called function has no IRAM_ATTR
// so doing it manually...
// Code adapted for 64 bits from https://www.hackersdelight.org/divcMore.pdf
int64_t IRAM_ATTR divs10(int64_t n) {
int64_t q, r;
n = n + (n >> 63 & 9);
q = (n >> 1) + (n >> 2);
q = q + (q >> 4);
q = q + (q >> 8);
q = q + (q >> 16);
q = q + (q >> 32);
q = q >> 3;
r = n - q * 10;
return q + ((r + 6) >> 4);
// return q + (r > 9);
}
int64_t IRAM_ATTR divs1000(int64_t n) {
return divs10(divs10(divs10(n)));
}
unsigned long IRAM_ATTR my_millis()
{
return divs1000(esp_timer_get_time());
}
void checkTouchStatus();
void touchISR();
void touchISR2();
// ISR won't work for SPI transfer, so forget about the following approach
///// Also initialized timers for sx1278 handling with interruts
///// fastest mode currentily is 4800 bit/s, i.e. 600 bytes/sec
///// 64 byte FIFO will last for at most about 106 ms.
///// lets use a timer every 20ms to handle sx1278 FIFO input, that should be fine.
// Instead create a tast...
Ticker ticker;
#define IS_TOUCH(x) (((x)!=255)&&((x)!=-1)&&((x)&128))
void initTouch() {
if ( !(IS_TOUCH(sonde.config.button_pin) || IS_TOUCH(sonde.config.button2_pin)) ) return; // no touch buttons configured
/*
* ** no. readTouch is not safe to use in ISR!
so now using Ticker
hw_timer_t *timer = timerBegin(0, 80, true);
timerAttachInterrupt(timer, checkTouchStatus, true);
timerAlarmWrite(timer, 300000, true);
timerAlarmEnable(timer);
*/
ticker.attach_ms(300, checkTouchStatus);
if ( IS_TOUCH(sonde.config.button_pin) ) {
touchAttachInterrupt(sonde.config.button_pin & 0x7f, touchISR, 20);
Serial.printf("Initializing touch 1 on pin %d\n", sonde.config.button_pin & 0x7f);
}
if ( IS_TOUCH(sonde.config.button2_pin) ) {
touchAttachInterrupt(sonde.config.button2_pin & 0x7f, touchISR2, 20);
Serial.printf("Initializing touch 2 on pin %d\n", sonde.config.button2_pin & 0x7f);
}
}
char buffer[85];
MicroNMEA nmea(buffer, sizeof(buffer));
void gpsTask(void *parameter) {
while (1) {
while (Serial2.available()) {
char c = Serial2.read();
//Serial.print(c);
if (nmea.process(c)) {
long lat = nmea.getLatitude();
long lon = nmea.getLongitude();
long alt = -1;
bool b = nmea.getAltitude(alt);
bool valid = nmea.isValid();
uint8_t hdop = nmea.getHDOP();
//Serial.printf("\nDecode: valid: %d N %ld E %ld alt %ld (%d) dop:%d", valid?1:0, lat, lon, alt, b, hdop);
}
}
delay(50);
}
}
void initGPS() {
if (sonde.config.gps_rxd < 0) return; // GPS disabled
Serial2.begin(9600, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
xTaskCreate( gpsTask, "gpsTask",
5000, /* stack size */
NULL, /* paramter */
1, /* priority */
NULL); /* task handle*/
}
void sx1278Task(void *parameter) {
/* new strategy:
background tasks handles all interactions with sx1278.
implementation is decoder specific.
This task is a simple infinit loop that
(a) initially and after frequency or mode change calls <decoder>.setup()
(b) then repeatedly calls <decoder>.receive() which should
(1) update data in the Sonde structure (additional updates may be done later in main loop/waitRXcomplete)
(2) set output flag receiveResult (success/error/timeout and keybord events)
*/
while (1) {
if (rxtask.activate >= 128) {
// activating sx1278 background task...
Serial.printf("rx task: activate=%d mainstate=%d\n", rxtask.activate, rxtask.mainState);
rxtask.mainState = ST_DECODER;
rxtask.currentSonde = rxtask.activate & 0x7F;
Serial.println("rx task: calling sonde.setup()");
sonde.setup();
} else if (rxtask.activate != -1) {
Serial.printf("rx task: activate=%d mainstate=%d\n", rxtask.activate, rxtask.mainState);
rxtask.mainState = rxtask.activate;
}
rxtask.activate = -1;
/* only if mainState is ST_DECODER */
if (rxtask.mainState != ST_DECODER) {
delay(100);
continue;
}
sonde.receive();
delay(20);
}
}
void IRAM_ATTR touchISR() {
if (!button1.isTouched) {
unsigned long now = my_millis();
if (now - button1.keydownTime < 500) button1.doublepress = 1;
else button1.doublepress = 0;
button1.keydownTime = now;
button1.isTouched = true;
}
}
void IRAM_ATTR touchISR2() {
if (!button2.isTouched) {
unsigned long now = my_millis();
if (now - button2.keydownTime < 500) button2.doublepress = 1;
else button2.doublepress = 0;
button2.keydownTime = now;
button2.isTouched = true;
}
}
// touchRead in ISR is also a bad idea. Now moved to Ticker task
void checkTouchButton(Button & button) {
if (button.isTouched) {
int tmp = touchRead(button.pin & 0x7f);
if (tmp > sonde.config.touch_thresh) {
button.isTouched = false;
unsigned long elapsed = my_millis() - button.keydownTime;
if (elapsed > 1500) {
if (elapsed < 4000) {
button.pressed = KP_MID;
}
else {
button.pressed = KP_LONG;
}
} else if (button.doublepress) {
button.pressed = KP_DOUBLE;
} else {
button.pressed = KP_SHORT;
}
}
}
}
void checkTouchStatus() {
checkTouchButton(button1);
checkTouchButton(button2);
}
void IRAM_ATTR buttonISR() {
unsigned long now = my_millis();
if (digitalRead(button1.pin) == 0) { // Button down
if (millis() - button1.press_ts < 500) {
if (now - button1.keydownTime < 500) {
// Double press
button1.doublepress = true;
button1.doublepress = 1;
} else {
button1.doublepress = false;
button1.doublepress = 0;
}
button1.press_ts = millis();
button1.keydownTime = now;
} else { //Button up
unsigned int elapsed = millis() - button1.press_ts;
if (button1.doublepress == -1) return; // key was never pressed before, ignore button up
unsigned int elapsed = now - button1.keydownTime;
if (elapsed > 1500) {
if (elapsed < 4000) {
button1.pressed = KP_MID;
@ -706,19 +999,39 @@ void IRAM_ATTR buttonISR() {
else button1.pressed = KP_SHORT;
}
button1.numberKeyPresses += 1;
button1.press_ts = millis();
button1.keydownTime = now;
}
}
int getKeyPress() {
KeyPress p = button1.pressed;
button1.pressed = KP_NONE;
int x = digitalRead(button1.pin);
Serial.printf("button1 press (now:%d): %d at %ld (%d)\n", x, p, button1.keydownTime, button1.numberKeyPresses);
return p;
}
int getKey2Press() {
KeyPress p = button2.pressed;
button2.pressed = KP_NONE;
Serial.printf("button2 press: %d at %ld (%d)\n", p, button2.keydownTime, button2.numberKeyPresses);
return p;
}
int hasKeyPress() {
return button1.pressed;
return button1.pressed || button2.pressed;
}
int getKeyPressEvent() {
int p = getKeyPress();
if (p == KP_NONE) {
p = getKey2Press();
if (p == KP_NONE)
return EVT_NONE;
return p + 4;
}
return p; /* map KP_x to EVT_KEY1_x / EVT_KEY2_x*/
}
extern int initlevels[40];
void setup()
{
char buf[12];
@ -729,6 +1042,11 @@ void setup()
Serial.printf("%d:%d ", i, v);
}
Serial.println("");
for (int i = 0; i < 39; i++) {
Serial.printf("%d:%d ", i, initlevels[i]);
}
Serial.println(" (before setup)");
pinMode(LORA_LED, OUTPUT);
aprs_gencrctab();
@ -741,6 +1059,19 @@ void setup()
setupConfigData(); // configuration must be read first due to OLED ports!!!
LORA_LED = sonde.config.led_pout;
button1.pin = sonde.config.button_pin;
button2.pin = sonde.config.button2_pin;
if (button1.pin != 0xff)
pinMode(button1.pin, INPUT); // configure as input if not disabled
if (button2.pin != 0xff)
pinMode(button2.pin, INPUT); // configure as input if not disabled
// Handle button press
if ( (button1.pin & 0x80) == 0) {
attachInterrupt( button1.pin, buttonISR, CHANGE);
Serial.printf("button1.pin is %d, attaching interrupt\n", button1.pin);
}
initTouch();
u8x8 = new U8X8_SSD1306_128X64_NONAME_SW_I2C(/* clock=*/ sonde.config.oled_scl, /* data=*/ sonde.config.oled_sda, /* reset=*/ sonde.config.oled_rst); // Unbuffered, basic graphics, software I2C
u8x8->begin();
@ -759,8 +1090,6 @@ void setup()
sonde.clearDisplay();
setupWifiList();
button1.pin = sonde.config.button_pin;
pinMode(button1.pin, INPUT);
// == show initial values from config.txt ========================= //
if (sonde.config.debug == 1) {
@ -834,8 +1163,6 @@ void setup()
// }
// xTaskCreate(mainloop, "MainServer", 10240, NULL, 10, NULL);
// Handle button press
attachInterrupt(button1.pin, buttonISR, CHANGE);
// == setup default channel list if qrg.txt read fails =========== //
setupChannelList();
@ -851,47 +1178,95 @@ void setup()
/// not here, done by sonde.setup(): rs41.setup();
// == setup default channel list if qrg.txt read fails =========== //
xTaskCreate( sx1278Task, "sx1278Task",
10000, /* stack size */
NULL, /* paramter */
1, /* priority */
NULL); /* task handle*/
sonde.setup();
initGPS();
WiFi.onEvent(WiFiEvent);
getKeyPress(); // clear key buffer
}
void enterMode(int mode) {
Serial.printf("enterMode(%d)\n", mode);
// Backround RX task should only be active in mode ST_DECODER for now
// (future changes might use RX background task for spectrum display as well)
if (mode != ST_DECODER) {
rxtask.activate = mode;
while (rxtask.activate == mode) {
delay(10); // until cleared by RXtask -- rx task is deactivated
}
}
mainState = (MainState)mode;
if(mainState == ST_SPECTRUM) {
if (mainState == ST_SPECTRUM) {
Serial.println("Entering ST_SPECTRUM mode");
sonde.clearDisplay();
u8x8->setFont(u8x8_font_chroma48medium8_r);
specTimer = millis();
specTimer = millis();
//scanner.init();
} else if (mainState == ST_WIFISCAN) {
sonde.clearDisplay();
}
if (mode == ST_DECODER) {
// trigger activation of background task
// currentSonde should be set before enterMode()
rxtask.activate = ACT_SONDE(sonde.currentSonde);
sonde.clearDisplay();
sonde.updateDisplay();
}
sonde.clearDisplay();
}
void loopDecoder() {
switch (getKeyPress()) {
case KP_SHORT:
sonde.nextConfig();
sonde.updateDisplayRXConfig();
sonde.updateDisplay();
break;
case KP_DOUBLE:
enterMode(ST_SCANNER);
return;
case KP_MID:
enterMode(ST_SPECTRUM);
return;
case KP_LONG:
enterMode(ST_WIFISCAN);
return;
static char text[40];
static const char *action2text(uint8_t action) {
if (action == ACT_DISPLAY_DEFAULT) return "Default Display";
if (action == ACT_DISPLAY_SPECTRUM) return "Spectrum Display";
if (action == ACT_DISPLAY_WIFI) return "Wifi Scan Display";
if (action == ACT_NEXTSONDE) return "Go to next sonde";
if (action == ACT_PREVSONDE) return "presonde (not implemented)";
if (action == ACT_NONE) return "none";
if (action >= 128) {
snprintf(text, 40, "Sonde=%d", action & 127);
} else {
snprintf(text, 40, "Display=%d", action);
}
return text;
}
void loopDecoder() {
// sonde knows the current type and frequency, and delegates to the right decoder
int res = sonde.receiveFrame();
uint16_t res = sonde.waitRXcomplete();
int action, event = 0;
action = (int)(res >> 8);
// TODO: update displayed sonde?
if (res == 0 && connected) {
if (action != ACT_NONE) {
Serial.printf("Loop: triggering action %s (%d)\n", action2text(action), action);
action = sonde.updateState(action);
Serial.printf("Loop: action is %d, sonde index is %d\n", action, sonde.currentSonde);
if (action != 255) {
if (action == ACT_DISPLAY_SPECTRUM) {
enterMode(ST_SPECTRUM);
return;
}
else if (action == ACT_DISPLAY_WIFI) {
enterMode(ST_WIFISCAN);
return;
}
// no... we are already in DECODER mode, so no need to do anything!?
//else if (action == ACT_NEXTSONDE) enterMode(ST_DECODER); // update rx background task
}
Serial.printf("current main is %d, current rxtask is %d\n", sonde.currentSonde, rxtask.currentSonde);
}
if ((res & 0xff) == 0 && connected) {
//Send a packet with position information
// first check if ID and position lat+lonis ok
if (sonde.si()->validID && (sonde.si()->validPos & 0x03 == 0x03)) {
SondeInfo *s = &sonde.sondeList[rxtask.receiveSonde];
if (s->validID && ((s->validPos & 0x03) == 0x03)) {
Serial.println("Sending position via UDP");
SondeInfo *s = sonde.si();
char raw[201];
const char *str = aprs_senddata(s->lat, s->lon, s->alt, s->hs, s->dir, s->vs, sondeTypeStr[s->type], s->id, "TE0ST",
sonde.config.udpfeed.symbol);
@ -905,36 +1280,6 @@ void loopDecoder() {
sonde.updateDisplay();
}
#define SCAN_MAXTRIES 1
void loopScanner() {
sonde.updateDisplayScanner();
static int tries = 0;
switch (getKeyPress()) {
case KP_SHORT:
enterMode(ST_DECODER);
return;
case KP_DOUBLE: break; /* ignored */
case KP_MID:
enterMode(ST_SPECTRUM);
return;
case KP_LONG:
enterMode(ST_WIFISCAN);
return;
}
// receiveFrame returns 0 on success, 1 on timeout
int res = sonde.receiveFrame(); // Maybe instead of receiveFrame, just detect if right type is present? TODO
Serial.print("Scanner: receiveFrame returned: ");
Serial.println(res);
if (res == 0) {
enterMode(ST_DECODER);
return;
}
if (++tries >= SCAN_MAXTRIES && !hasKeyPress()) {
sonde.nextConfig();
tries = 0;
}
}
void loopSpectrum() {
int marker = 0;
@ -947,11 +1292,13 @@ void loopSpectrum() {
return;
case KP_MID: /* restart, TODO */ break;
case KP_LONG:
Serial.println("loopSpectrum: KP_LONG");
enterMode(ST_WIFISCAN);
return;
case KP_DOUBLE:
enterMode(ST_SCANNER);
break;
currentDisplay = 0;
enterMode(ST_DECODER);
return;
default: break;
}
@ -974,7 +1321,8 @@ void loopSpectrum() {
u8x8->drawString(0, 1 + marker, buf);
u8x8->drawString(2, 1 + marker, "Sec.");
if (remaining <= 0) {
enterMode(ST_SCANNER);
currentDisplay = 0;
enterMode(ST_DECODER);
}
}
}
@ -1001,6 +1349,8 @@ String translateEncryptionType(wifi_auth_mode_t encryptionType) {
return "WPA_WPA2_PSK";
case (WIFI_AUTH_WPA2_ENTERPRISE):
return "WPA2_ENTERPRISE";
default:
return "";
}
}
@ -1110,11 +1460,13 @@ void WiFiEvent(WiFiEvent_t event)
case SYSTEM_EVENT_ETH_GOT_IP:
Serial.println("Obtained IP address");
break;
default:
break;
}
}
int wifiConnect(int16_t res) {
void wifiConnect(int16_t res) {
Serial.printf("WLAN scan result: found %d networks\n", res);
// pick best network
@ -1154,7 +1506,7 @@ int wifiConnect(int16_t res) {
static int wifi_cto;
void loopWifiBackground() {
Serial.printf("WifiBackground: state %d\n", wifi_state);
// Serial.printf("WifiBackground: state %d\n", wifi_state);
// handle Wifi station mode in background
if (sonde.config.wifi == 0 || sonde.config.wifi == 2) return; // nothing to do if disabled or access point mode
@ -1210,7 +1562,7 @@ void startAP() {
String myIPstr = myIP.toString();
sonde.setIP(myIPstr.c_str(), true);
sonde.updateDisplayIP();
SetupAsyncServer();
enableNetwork(true);
}
void initialMode() {
@ -1218,7 +1570,8 @@ void initialMode() {
startSpectrumDisplay();
//done in startSpectrumScan(): enterMode(ST_SPECTRUM);
} else {
enterMode(ST_SCANNER);
currentDisplay = 0;
enterMode(ST_DECODER);
}
}
@ -1252,8 +1605,6 @@ void loopWifiScan() {
int line = 0;
int cnt = 0;
int marker = 0;
char buf[5];
WiFi.disconnect(true);
WiFi.mode(WIFI_STA);
@ -1321,6 +1672,14 @@ void loopWifiScan() {
sonde.setIP(localIPstr.c_str(), false);
sonde.updateDisplayIP();
wifi_state = WIFI_CONNECTED;
bool hasRS92 = false;
for (int i = 0; i < MAXSONDE; i++) {
if (sonde.sondeList[i].type == STYPE_RS92) hasRS92 = true;
}
if (hasRS92) {
geteph();
get_eph("/brdc");
}
delay(3000);
}
enableNetwork(true);
@ -1330,7 +1689,8 @@ void loopWifiScan() {
//startSpectrumDisplay();
enterMode(ST_SPECTRUM);
} else {
enterMode(ST_SCANNER);
currentDisplay = 0;
enterMode(ST_DECODER);
}
}
@ -1342,16 +1702,16 @@ String getHeaderValue(String header, String headerName) {
return header.substring(strlen(headerName.c_str()));
}
// OTA Logic
// OTA Logic
void execOTA() {
int contentLength = 0;
bool isValidContentType = false;
sonde.clearDisplay();
u8x8->setFont(u8x8_font_chroma48medium8_r);
u8x8->drawString(0, 0, "C:");
String dispHost = updateHost.substring(0,14);
String dispHost = updateHost.substring(0, 14);
u8x8->drawString(2, 0, dispHost.c_str());
Serial.println("Connecting to: " + updateHost);
// Connect to Update host
if (client.connect(updateHost.c_str(), updatePort)) {
@ -1394,7 +1754,7 @@ void execOTA() {
Content-Type: application/octet-stream
Content-Length: 357280
Server: AmazonS3
{{BIN FILE CONTENTS}}
*/
@ -1505,17 +1865,17 @@ void execOTA() {
}
void loop() {
Serial.print("Running main loop. free heap:");
Serial.println(ESP.getFreeHeap());
Serial.printf("\nRunning main loop in state %d. free heap: %d;\n", mainState, ESP.getFreeHeap());
Serial.printf("currentDisp:%d lastDisp:%d\n", currentDisplay, lastDisplay);
switch (mainState) {
case ST_DECODER: loopDecoder(); break;
case ST_SCANNER: loopScanner(); break;
case ST_SPECTRUM: loopSpectrum(); break;
case ST_WIFISCAN: loopWifiScan(); break;
case ST_UPDATE: execOTA(); break;
}
#if 1
#if 0
int rssi = sx1278.getRSSI();
Serial.print(" RSSI: ");
Serial.print(rssi);
@ -1525,4 +1885,10 @@ void loop() {
Serial.println(gain);
#endif
loopWifiBackground();
if (currentDisplay != lastDisplay && (mainState == ST_DECODER)) {
disp.setLayout(currentDisplay);
sonde.clearDisplay();
sonde.updateDisplay();
lastDisplay = currentDisplay;
}
}

Wyświetl plik

@ -1,7 +1,12 @@
#-------------------------------#
# Hardware depending settings
#-------------------------------#
button_pin=0
# pin: 255=disabled; x=button x+128=touch button
#button_pin=130
#button2_pin=142
# No specification in config file: try autodetection (gpio4 pin level at startup)
#button_pin=0
#button2_pin=255
# LED port
led_pout=9
# OLED Setup is depending on hardware of LoRa board
@ -11,13 +16,17 @@ led_pout=9
#oled_sda=21
#oled_scl=22
oled_rst=16
#gps_rxd=-1
gps_txd=-1
#-------------------------------#
# General config settings
#-------------------------------#
maxsonde=20
debug=1
debug=0
# wifi mode: 1=client in background; 2=AP in background; 3=client on startup, ap if failure
wifi=3
# display mode: 1=standard 2=fieldmode 3=field w/sondetype
display=1
#-------------------------------#
# Spectrum display settings
#-------------------------------#
@ -33,6 +42,19 @@ marker=1
call=N0CALL
passcode=12345
#-------------------------------#
# Sonde specific settings: bandwidth
# valid values: 3100, 3900, 5200, 6300, 7800, 10400, 12500,
# 15600, 20800, 25000, ...
# other values will be rounded up to the next valid value
# rs92.alt2d: default altitude used by RS92 decoder if only 3 sats available
#-------------------------------#
rs41.agcbw=12500
rs41.rxbw=6300
rs92.rxbw=12500
rs92.alt2d=480
dfm.agcbw=20800
dfm.rxbw=10400
#-------------------------------#
# axudp for sending to aprsmap
#-------------------------------#
# local use only, do not feed to public services

Wyświetl plik

@ -34,12 +34,12 @@
<iframe src="wifi.html" style="border:none;" width="100%%" height="100%%"></iframe>
</div>
<div id="Data" class="tabcontent">
<div id="Data" class="tabcontent" data-src="status.html">
<h3>Data</h3>
<iframe src="status.html" style="border:none;" width="100%%" height="100%%"></iframe>
</div>
<div id="SondeMap" class="tabcontent">
<div id="SondeMap" class="tabcontent" data-src="https://wx.dl2mf.de/#?">
<iframe src="https://wx.dl2mf.de/#?" style="border:none;" width="98%%" height="98%%"></iframe>
</div>
@ -74,13 +74,25 @@ function selTab(evt, id) {
tabcontent=document.getElementsByClassName("tabcontent");
for(i=0; i<tabcontent.length; i++) {
tabcontent[i].style.display = "none";
var link = tabcontent[i].dataset.src;
if(link) {
var iframe = tabcontent[i].getElementsByTagName("iframe")[0];
iframe.setAttribute("src", "");
}
}
tablinks=document.getElementsByClassName("tablinks");
for(i=0; i<tablinks.length; i++) {
tablinks[i].className = tablinks[i].className.replace(" active", "");
}
document.getElementById(id).style.display = "block";
}
var act = document.getElementById(id);
act.style.display = "block";
evt.currentTarget.className += " active";
var link = act.dataset.src;
if(link) {
var iframe = act.getElementsByTagName("iframe")[0];
iframe.setAttribute("src", link);
}
}
document.getElementById("defaultTab").click();
</script>

Wyświetl plik

@ -1,2 +1,2 @@
const char *version_name = "RDZ_TTGO_SONDE";
const char *version_id = "master v0.6c";
const char *version_id = "master v0.7.0";

Wyświetl plik

@ -32,6 +32,7 @@ similar on other OS) and restart IDE
Select Tools -> Library Manager
Install "U8g2"
Install "MicroNMEA"
## Additional libraries, part 2

Wyświetl plik

@ -542,7 +542,7 @@ int32_t SX1278FSK::getFEI()
{
int32_t FEI;
int16_t regval = (readRegister(REG_FEI_MSB)<<8) | readRegister(REG_FEI_LSB);
Serial.printf("feireg: %04x\n", regval);
//Serial.printf("feireg: %04x\n", regval);
FEI = (int32_t)(regval * SX127X_FSTEP);
return FEI;
}
@ -554,7 +554,7 @@ int32_t SX1278FSK::getAFC()
{
int32_t AFC;
int16_t regval = (readRegister(REG_AFC_MSB)<<8) | readRegister(REG_AFC_LSB);
Serial.printf("afcreg: %04x\n", regval);
//Serial.printf("afcreg: %04x\n", regval);
AFC = (int32_t)(regval * SX127X_FSTEP);
return AFC;
}
@ -701,8 +701,6 @@ uint8_t SX1278FSK::receivePacketTimeout(uint32_t wait, byte *data)
state = receive();
if(state != 0) { return state; }
boolean p_received = false;
#if (SX1278FSK_debug_mode > 0)
Serial.println(F("RX mode sucessfully activated"));
#endif
@ -711,20 +709,26 @@ uint8_t SX1278FSK::receivePacketTimeout(uint32_t wait, byte *data)
value = readRegister(REG_IRQ_FLAGS2);
byte ready=0;
// while not yet done or FIFO not yet empty
while( (!ready || bitRead(value,6)==0) && (millis() - previous < wait) &&(!hasKeyPress()) )
while( (!ready || bitRead(value,6)==0) && (millis() - previous < wait) )
{
if( bitRead(value,2)==1 ) ready=1;
if( bitRead(value, 6) == 0 ) { // FIFO not empty
data[di++] = readRegister(REG_FIFO);
if(di==1) {
// It's a bit of a hack.... get RSSI and AFC (a) at beginning of packet and
// for RS41 after about 0.5 sec. It might be more logical to put this decoder-specific
// code into RS41.cpp instead of this file... (maybe TODO?)
if(di==1 || di==290 ) {
int rssi=getRSSI();
int fei=getFEI();
int afc=getAFC();
Serial.print("Test: RSSI="); Serial.println(rssi);
Serial.print("Test: FEI="); Serial.println(fei);
Serial.printf("Test(%d): RSSI=%d", rxtask.currentSonde, rssi/2);
Serial.print("Test: AFC="); Serial.println(afc);
sonde.si()->rssi = rssi;
sonde.si()->afc = afc;
sonde.sondeList[rxtask.currentSonde].rssi = rssi;
sonde.sondeList[rxtask.currentSonde].afc = afc;
if(rxtask.receiveResult==0xFFFF)
rxtask.receiveResult = RX_UPDATERSSI;
//sonde.si()->rssi = rssi;
//sonde.si()->afc = afc;
}
if(di>520) {
// TODO
@ -732,6 +736,8 @@ uint8_t SX1278FSK::receivePacketTimeout(uint32_t wait, byte *data)
break;
}
previous = millis(); // reset timeout after receiving data
} else {
delay(10);
}
value = readRegister(REG_IRQ_FLAGS2);
}

Wyświetl plik

@ -12,10 +12,11 @@
#define DFM_DBG(x)
#endif
int DFM::setup(int inverse)
int DFM::setup(float frequency, int inv)
{
inverse = inv;
#if DFM_DEBUG
Serial.println("Setup sx1278 for DFM sonde");
Serial.printf("Setup sx1278 for DFM sonde (inv=%d)\n",inv);
#endif
if(sx1278.ON()!=0) {
DFM_DBG(Serial.println("Setting SX1278 power on FAILED"));
@ -35,14 +36,14 @@ int DFM::setup(int inverse)
Serial.println(br);
#endif
if(sx1278.setAFCBandwidth(25000)!=0) {
DFM_DBG(Serial.println("Setting AFC bandwidth 25 kHz FAILED"));
return 1;
}
if(sx1278.setRxBandwidth(12000)!=0) {
DFM_DBG(Serial.println("Setting RX bandwidth 12kHz FAILED"));
return 1;
}
if(sx1278.setAFCBandwidth(sonde.config.dfm.agcbw)!=0) {
DFM_DBG(Serial.printf("Setting AFC bandwidth %d Hz FAILED", sonde.config.dfm.agcbw));
return 1;
}
if(sx1278.setRxBandwidth(sonde.config.dfm.rxbw)!=0) {
DFM_DBG(Serial.printf("Setting RX bandwidth to %d Hz FAILED", sonde.config.dfm.rxbw));
return 1;
}
// Enable auto-AFC, auto-AGC, RX Trigger by preamble
if(sx1278.setRxConf(0x1E)!=0) {
DFM_DBG(Serial.println("Setting RX Config FAILED"));
@ -67,23 +68,22 @@ int DFM::setup(int inverse)
DFM_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
DFM_DBG(Serial.println("Setting SX1278 config for DFM finished\n"); Serial.println());
return 0;
}
int DFM::setFrequency(float frequency) {
Serial.print("DFM: setting RX frequency to ");
Serial.println(frequency);
return sx1278.setFrequency(frequency);
int retval = sx1278.setFrequency(frequency);
DFM_DBG(Serial.println("Setting SX1278 config for DFM finished\n"); Serial.println());
return retval;
}
#define bit(value,bitpos) ((value>>(7-bitpos))&0x01)
#define bitpick(value,bitpos) (((value)>>(7-(bitpos)))&0x01)
// Input: str: packed data, MSB first
void DFM::deinterleave(uint8_t *str, int L, uint8_t *block) {
int i, j;
for (j = 0; j < B; j++) { // L = 7 (CFG), 13 (DAT1, DAT2)
for (i = 0; i < L; i++) {
block[B*i+j] = bit( str[(L*j+i)/8], (L*j+i)&7 )?0:1;
block[B*i+j] = bitpick( str[(L*j+i)/8], (L*j+i)&7 )?0:1;
}
}
}
@ -162,7 +162,7 @@ void DFM::printRaw(const char *label, int len, int ret, const uint8_t *data)
Serial.print(" ");
}
int DFM::decodeCFG(uint8_t *cfg)
void DFM::decodeCFG(uint8_t *cfg)
{
static int lowid, highid, idgood=0, type=0;
if((cfg[0]>>4)==0x06 && type==0) { // DFM-6 ID
@ -189,7 +189,7 @@ int DFM::decodeCFG(uint8_t *cfg)
}
}
int DFM::decodeDAT(uint8_t *dat)
void DFM::decodeDAT(uint8_t *dat)
{
Serial.print(" DAT["); Serial.print(dat[6]); Serial.print("]: ");
switch(dat[6]) {
@ -206,7 +206,7 @@ int DFM::decodeDAT(uint8_t *dat)
{
float lat, vh;
lat = ((uint32_t)dat[0]<<24) + ((uint32_t)dat[1]<<16) + ((uint32_t)dat[2]<<8) + ((uint32_t)dat[3]);
vh = (dat[4]<<8) + dat[5];
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;
@ -230,7 +230,7 @@ int DFM::decodeDAT(uint8_t *dat)
{
float alt, vv;
alt = ((uint32_t)dat[0]<<24) + ((uint32_t)dat[1]<<16) + ((uint32_t)dat[2]<<8) + dat[3];
vv = (int16_t)( (dat[4]<<8) | dat[5] );
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;
@ -256,7 +256,7 @@ int DFM::decodeDAT(uint8_t *dat)
}
}
int DFM::bitsToBytes(uint8_t *bits, uint8_t *bytes, int len)
void DFM::bitsToBytes(uint8_t *bits, uint8_t *bytes, int len)
{
int i;
for(i=0; i<len*4; i++) {
@ -266,14 +266,17 @@ int DFM::bitsToBytes(uint8_t *bits, uint8_t *bytes, int len)
bytes[(i-1)/8] &= 0x0F;
}
int DFM::receiveFrame() {
byte data[33];
sx1278.setPayloadLength(33); // Expect 33 bytes (7+13+13 bytes
int DFM::receive() {
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 e = sx1278.receivePacketTimeout(1000, data);
if(e) { return RX_TIMEOUT; } //if timeout... return 1
Serial.printf("inverse is %d\b", inverse);
if(!inverse) { for(int i=0; i<33; i++) { data[i]^=0xFF; } }
deinterleave(data, 7, hamming_conf);
deinterleave(data+7, 13, hamming_dat1);
deinterleave(data+20, 13, hamming_dat2);
@ -293,7 +296,30 @@ int DFM::receiveFrame() {
decodeCFG(byte_conf);
decodeDAT(byte_dat1);
decodeDAT(byte_dat2);
}
return RX_OK;
}
// 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;
}
DFM dfm = DFM();

Wyświetl plik

@ -23,14 +23,16 @@
class DFM
{
private:
int inverse=0;
void deinterleave(uint8_t *str, int L, uint8_t *block);
uint32_t bits2val(const uint8_t *bits, int len);
int check(uint8_t code[8]);
int hamming(uint8_t *ham, int L, uint8_t *sym);
void printRaw(const char *prefix, int len, int ret, const uint8_t* data);
int decodeCFG(uint8_t *cfg);
int decodeDAT(uint8_t *dat);
int bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);
void decodeCFG(uint8_t *cfg);
void decodeDAT(uint8_t *dat);
void bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);
#define B 8
#define S 4
@ -52,9 +54,10 @@ private:
public:
DFM();
int setup(int inverse);
int setFrequency(float frequency);
int receiveFrame();
// main decoder API
int setup(float frequency, int inverse);
int receive();
int waitRXcomplete();
int use_ecc = 1;
};

Wyświetl plik

@ -0,0 +1,431 @@
#include <U8x8lib.h>
#include <U8g2lib.h>
#include <MicroNMEA.h>
#include "Display.h"
#include "Sonde.h"
extern Sonde sonde;
extern MicroNMEA nmea;
extern U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8;
const char *sondeTypeStr[5] = { "DFM6", "DFM9", "RS41", "RS92" };
byte myIP_tiles[8*11];
static uint8_t ap_tile[8]={0x00,0x04,0x22,0x92, 0x92, 0x22, 0x04, 0x00};
static const uint8_t font[10][5]={
0x3E, 0x51, 0x49, 0x45, 0x3E, // 0
0x00, 0x42, 0x7F, 0x40, 0x00, // 1
0x42, 0x61, 0x51, 0x49, 0x46, // 2
0x21, 0x41, 0x45, 0x4B, 0x31, // 3
0x18, 0x14, 0x12, 0x7F, 0x10, // 4
0x27, 0x45, 0x45, 0x45, 0x39, // 5
0x3C, 0x4A, 0x49, 0x49, 0x30, // 6
0x01, 0x01, 0x79, 0x05, 0x03, // 7
0x36, 0x49, 0x49, 0x49, 0x36, // 8
0x06, 0x49, 0x39, 0x29, 0x1E }; // 9; .=0x40
static unsigned char kmh_tiles[] U8X8_PROGMEM = {
0x1F, 0x04, 0x0A, 0x11, 0x00, 0x1F, 0x02, 0x04, 0x42, 0x3F, 0x10, 0x08, 0xFC, 0x22, 0x20, 0xF8
};
static unsigned char ms_tiles[] U8X8_PROGMEM = {
0x1F, 0x02, 0x04, 0x02, 0x1F, 0x40, 0x20, 0x10, 0x08, 0x04, 0x12, 0xA4, 0xA4, 0xA4, 0x40, 0x00
};
static unsigned char stattiles[5][4] = {
0x00, 0x1F, 0x00, 0x00 , // | == ok
0x00, 0x10, 0x10, 0x00 , // . == no header found
0x1F, 0x15, 0x15, 0x00 , // E == decode error
0x00, 0x00, 0x00, 0x00 , // ' ' == unknown/unassigned
0x07, 0x05, 0x07, 0x00 }; // ° = rx ok, but no valid position
//static uint8_t halfdb_tile[8]={0x80, 0x27, 0x45, 0x45, 0x45, 0x39, 0x00, 0x00};
static uint8_t halfdb_tile1[8]={0x00, 0x38, 0x28, 0x28, 0x28, 0xC8, 0x00, 0x00};
static uint8_t halfdb_tile2[8]={0x00, 0x11, 0x02, 0x02, 0x02, 0x01, 0x00, 0x00};
//static uint8_t empty_tile[8]={0x80, 0x3E, 0x51, 0x49, 0x45, 0x3E, 0x00, 0x00};
static uint8_t empty_tile1[8]={0x00, 0xF0, 0x88, 0x48, 0x28, 0xF0, 0x00, 0x00};
static uint8_t empty_tile2[8]={0x00, 0x11, 0x02, 0x02, 0x02, 0x01, 0x00, 0x00};
//static uint8_t gps_tile[8]={0x3E, 0x77, 0x63, 0x77, 0x3E, 0x1C, 0x08, 0x00};
static uint8_t gps_tile[8]={0x00, 0x0E, 0x1F, 0x3B, 0x71, 0x3B, 0x1F, 0x0E};
static uint8_t nogps_tile[8]={0x41, 0x22, 0x14, 0x08, 0x14, 0x22, 0x41, 0x00};
#define SETFONT(large) u8x8->setFont((large)?u8x8_font_7x14_1x2_r:u8x8_font_chroma48medium8_r);
/* Description of display layouts.
* for each display, the content is described by a DispEntry structure
* timeout values are in milliseconds, for view activ, rx signal present, no rx signal present
* for each displey, actions (switching to different sonde or different view) can be defined
* based on key presses or on expired timeouts
*/
DispEntry searchLayout[] = {
{0, 0, FONT_LARGE, disp.drawText, "Scan:"},
{0, 8, FONT_LARGE, disp.drawType, NULL},
{3, 0, FONT_LARGE, disp.drawFreq, " MHz"},
{5, 0, FONT_LARGE, disp.drawSite, NULL},
{7, 5, 0, disp.drawIP, NULL},
{-1, -1, -1, NULL, NULL},
};
int16_t searchTimeouts[] = { -1, 0, 0 };
uint8_t searchActions[] = {
ACT_NONE,
ACT_DISPLAY_DEFAULT, ACT_NONE, ACT_DISPLAY_SPECTRUM, ACT_DISPLAY_WIFI,
ACT_NONE, ACT_NONE, ACT_NONE, ACT_NONE,
ACT_NONE, ACT_DISPLAY_DEFAULT, ACT_NEXTSONDE};
DispEntry legacyLayout[] = {
{0, 5, FONT_SMALL, disp.drawFreq, " MHz"},
{1, 8, FONT_SMALL, disp.drawAFC, NULL},
{0, 0, FONT_SMALL, disp.drawType, NULL},
{1, 0, FONT_SMALL, disp.drawID, NULL},
{2, 0, FONT_LARGE, disp.drawLat, NULL},
{4, 0, FONT_LARGE, disp.drawLon, NULL},
{2, 10, FONT_SMALL, disp.drawAlt, NULL},
{3, 10, FONT_SMALL, disp.drawHS, NULL},
{4, 9, FONT_SMALL, disp.drawVS, NULL},
{6, 0, FONT_LARGE, disp.drawRSSI, NULL},
{6, 7, 0, disp.drawQS, NULL},
{7, 5, 0, disp.drawIP, NULL},
{-1, -1, -1, NULL, NULL},
};
int16_t legacyTimeouts[] = { -1, -1, 20000 };
uint8_t legacyActions[] = {
ACT_NONE,
ACT_NEXTSONDE, ACT_DISPLAY(0), ACT_DISPLAY_SPECTRUM, ACT_DISPLAY_WIFI,
ACT_DISPLAY(2), ACT_NONE, ACT_NONE, ACT_NONE,
ACT_NONE, ACT_NONE, ACT_DISPLAY(0)};
DispEntry fieldLayout[] = {
{2, 0, FONT_LARGE, disp.drawLat, NULL},
{4, 0, FONT_LARGE, disp.drawLon, NULL},
{3, 10, FONT_SMALL, disp.drawHS, NULL},
{4, 9, FONT_SMALL, disp.drawVS, NULL},
{0, 0, FONT_LARGE, disp.drawID, NULL},
{6, 0, FONT_LARGE, disp.drawAlt, NULL},
{6, 7, 0, disp.drawQS, NULL},
{-1, -1, -1, NULL, NULL},
};
int16_t fieldTimeouts[] = { -1, -1, -1 };
uint8_t fieldActions[] = {
ACT_NONE,
ACT_NEXTSONDE, ACT_DISPLAY(0), ACT_DISPLAY_SPECTRUM, ACT_DISPLAY_WIFI,
ACT_DISPLAY(4), ACT_NONE, ACT_NONE, ACT_NONE,
ACT_NONE, ACT_NONE, ACT_NONE};
DispEntry field2Layout[] = {
{2, 0, FONT_LARGE, disp.drawLat, NULL},
{4, 0, FONT_LARGE, disp.drawLon, NULL},
{1, 12, FONT_SMALL, disp.drawType, NULL},
{0, 9, FONT_SMALL, disp.drawFreq, ""},
{3, 10, FONT_SMALL, disp.drawHS, NULL},
{4, 9, FONT_SMALL, disp.drawVS, NULL},
{0, 0, FONT_LARGE, disp.drawID, NULL},
{6, 0, FONT_LARGE, disp.drawAlt, NULL},
{6, 7, 0, disp.drawQS, NULL},
{-1, -1, -1, NULL, NULL},
};
uint8_t field2Actions[] = {
ACT_NONE,
ACT_NEXTSONDE, ACT_DISPLAY(0), ACT_DISPLAY_SPECTRUM, ACT_DISPLAY_WIFI,
ACT_DISPLAY(1), ACT_NONE, ACT_NONE, ACT_NONE,
ACT_NONE, ACT_NONE, ACT_NONE};
DispEntry gpsLayout[] = {
{0, 0, FONT_LARGE, disp.drawID, NULL},
{2, 0, FONT_SMALL, disp.drawLat, NULL},
{3, 0, FONT_SMALL, disp.drawLon, NULL},
{4, 0, FONT_SMALL, disp.drawAlt, NULL},
{6, 0, FONT_SMALL, disp.drawGPS, "V"},
//{6, 1, FONT_SMALL, disp.drawGPS, "A"},
//{6, 8, FONT_SMALL, disp.drawGPS, "O"},
{7, 0, FONT_SMALL, disp.drawGPS, "D"},
{7, 8, FONT_SMALL, disp.drawGPS, "I"},
{-1, -1, -1, NULL, NULL},
};
uint8_t gpsActions[] = {
ACT_NONE,
ACT_NEXTSONDE, ACT_DISPLAY(0), ACT_DISPLAY_SPECTRUM, ACT_DISPLAY_WIFI,
ACT_DISPLAY(1), ACT_NONE, ACT_NONE, ACT_NONE,
ACT_NONE, ACT_NONE, ACT_NONE};
DispInfo layouts[5] = {
{ searchLayout, searchActions, searchTimeouts },
{ legacyLayout, legacyActions, legacyTimeouts },
{ fieldLayout, fieldActions, fieldTimeouts },
{ field2Layout, field2Actions, fieldTimeouts },
{ gpsLayout, gpsActions, fieldTimeouts } };
char Display::buf[17];
Display::Display() {
setLayout(1);
}
void Display::setLayout(int layoutIdx) {
layout = &layouts[layoutIdx];
}
void Display::drawLat(DispEntry *de) {
SETFONT(de->fmt);
if(!sonde.si()->validPos) {
u8x8->drawString(de->x,de->y,"<?""?> ");
return;
}
snprintf(buf, 16, "%2.5f", sonde.si()->lat);
u8x8->drawString(de->x,de->y,buf);
}
void Display::drawLon(DispEntry *de) {
SETFONT(de->fmt);
if(!sonde.si()->validPos) {
u8x8->drawString(de->x,de->y,"<?""?> ");
return;
}
snprintf(buf, 16, "%2.5f", sonde.si()->lon);
u8x8->drawString(de->x,de->y,buf);
}
void Display::drawAlt(DispEntry *de) {
SETFONT(de->fmt);
if(!sonde.si()->validPos) {
u8x8->drawString(de->x,de->y," ");
return;
}
snprintf(buf, 16, sonde.si()->alt>=1000?" %5.0fm":" %3.1fm", sonde.si()->alt);
u8x8->drawString(de->x,de->y,buf+strlen(buf)-6);
}
void Display::drawHS(DispEntry *de) {
SETFONT(de->fmt);
if(!sonde.si()->validPos) {
u8x8->drawString(de->x,de->y," ");
return;
}
snprintf(buf, 16, sonde.si()->hs>99?" %3.0f":" %2.1f", sonde.si()->hs);
u8x8->drawString(de->x,de->y,buf+strlen(buf)-4);
u8x8->drawTile(de->x+4,de->y,2,kmh_tiles);
}
void Display::drawVS(DispEntry *de) {
SETFONT(de->fmt);
if(!sonde.si()->validPos) {
u8x8->drawString(de->x,de->y," ");
return;
}
snprintf(buf, 16, " %+2.1f", sonde.si()->vs);
u8x8->drawString(de->x, de->y, buf+strlen(buf)-5);
u8x8->drawTile(de->x+5,de->y,2,ms_tiles);
}
void Display::drawID(DispEntry *de) {
SETFONT((de->fmt&0x01));
if(!sonde.si()->validID) {
u8x8->drawString(de->x, de->y, "nnnnnnnn ");
return;
}
u8x8->drawString(de->x, de->y, sonde.si()->id);
}
void Display::drawRSSI(DispEntry *de) {
SETFONT(de->fmt);
snprintf(buf, 16, "-%d ", sonde.si()->rssi/2);
int len=strlen(buf)-3;
Serial.printf("drawRSSI: %d %d %d (%d)[%d]\n", de->y, de->x, sonde.si()->rssi/2, sonde.currentSonde, len);
buf[5]=0;
u8x8->drawString(de->x,de->y,buf);
u8x8->drawTile(de->x+len, de->y, 1, (sonde.si()->rssi&1)?halfdb_tile1:empty_tile1);
u8x8->drawTile(de->x+len, de->y+1, 1, (sonde.si()->rssi&1)?halfdb_tile2:empty_tile2);
}
void Display::drawQS(DispEntry *de) {
uint8_t *stat = sonde.si()->rxStat;
for(int i=0; i<18; i+=2) {
uint8_t tile[8];
*(uint32_t *)(&tile[0]) = *(uint32_t *)(&(stattiles[stat[i]]));
*(uint32_t *)(&tile[4]) = *(uint32_t *)(&(stattiles[stat[i+1]]));
u8x8->drawTile(de->x+i/2, de->y, 1, tile);
}
}
void Display::drawType(DispEntry *de) {
SETFONT(de->fmt);
u8x8->drawString(de->x, de->y, sondeTypeStr[sonde.si()->type]);
}
void Display::drawFreq(DispEntry *de) {
SETFONT(de->fmt);
snprintf(buf, 16, "%3.3f%s", sonde.si()->freq, de->extra?de->extra:"");
u8x8->drawString(de->x, de->y, buf);
}
void Display::drawAFC(DispEntry *de) {
if(!sonde.config.showafc) return;
SETFONT(de->fmt);
if(sonde.si()->afc==0) { strcpy(buf, " "); }
else { snprintf(buf, 15, " %+3.2fk", sonde.si()->afc*0.001); }
u8x8->drawString(de->x, de->y, buf+strlen(buf)-8);
}
void Display::drawIP(DispEntry *de) {
u8x8->drawTile(de->x, de->y, 11, myIP_tiles);
}
void Display::drawSite(DispEntry *de) {
SETFONT(de->fmt);
u8x8->drawString(de->x, de->y, sonde.si()->launchsite);
}
void Display::drawTelemetry(DispEntry *de) {
}
#define EARTH_RADIUS (6371000.0F)
#ifndef PI
#define PI (3.1415926535897932384626433832795)
#endif
// defined by Arduino.h #define radians(x) ( (x)*180.0F/PI )
void Display::drawGPS(DispEntry *de) {
if(sonde.config.gps_rxd<0) return;
SETFONT(de->fmt);
switch(de->extra[0]) {
case 'V':
{
// show if GPS location is valid
uint8_t *tile = nmea.isValid()?gps_tile:nogps_tile;
u8x8->drawTile(de->x, de->y, 1, tile);
}
break;
case 'O':
// GPS long
{
float lon = nmea.getLongitude()*0.000001;
Serial.print("lon: "); Serial.println(lon);
snprintf(buf, 16, "%2.5f", lon);
u8x8->drawString(de->x,de->y,buf);
}
break;
case 'A':
// GPS lat
{
float lat = nmea.getLatitude()*0.000001;
Serial.print("lat: "); Serial.println(lat);
snprintf(buf, 16, "%2.5f", lat);
u8x8->drawString(de->x,de->y,buf);
}
break;
case 'H':
// GPS alt
{
long alt = -1;
nmea.getAltitude(alt);
snprintf(buf, 16, "%5fm", alt*0.00001);
u8x8->drawString(de->x,de->y,buf);
}
break;
case 'D':
{
// distance
// equirectangular approximation is good enough
float lat1 = nmea.getLatitude()*0.000001;
float lat2 = sonde.si()->lat;
float x = radians(nmea.getLongitude()*0.000001-sonde.si()->lon) * cos( radians((lat1+lat2)/2) );
float y = radians(lat2-lat1);
float d = sqrt(x*x+y*y)*EARTH_RADIUS;
snprintf(buf, 16, "d=%.0fm ", d);
buf[7]=0;
u8x8->drawString(de->x, de->y, buf);
}
break;
case 'I':
// dIrection
{
float lat1 = radians(nmea.getLatitude()*0.000001);
float lat2 = radians(sonde.si()->lat);
float lon1 = radians(nmea.getLongitude()*0.000001);
float lon2 = radians(sonde.si()->lon);
float y = sin(lon2-lon1)*cos(lat2);
float x = cos(lat1)*sin(lat2) - sin(lat1)*cos(lat2)*cos(lon2-lon1);
float dir = atan2(y, x)/PI*180;
Serial.printf("direction is %.2f\n", dir);
snprintf(buf, 16, "dir=%d ", (int)dir);
buf[8]=0;
u8x8->drawString(de->x, de->y, buf);
}
break;
case 'E':
// elevation
break;
}
}
void Display::drawText(DispEntry *de) {
SETFONT(de->fmt);
u8x8->drawString(de->x, de->y, de->extra);
}
void Display::clearIP() {
memset(myIP_tiles, 0, 11*8);
}
void Display::setIP(const char *ip, bool AP) {
memset(myIP_tiles, 0, 11*8);
int len = strlen(ip);
int pix = (len-3)*6+6;
int tp = 80-pix+8;
if(AP) memcpy(myIP_tiles+(tp<16?0:8), ap_tile, 8);
for(int i=0; i<len; i++) {
if(ip[i]=='.') { myIP_tiles[tp++]=0x40; myIP_tiles[tp++]=0x00; }
else {
int idx = ip[i]-'0';
memcpy(myIP_tiles+tp, &font[idx], 5);
myIP_tiles[tp+5] = 0;
tp+=6;
}
}
while(tp<8*10) { myIP_tiles[tp++]=0; }
}
void Display::updateDisplayPos() {
for(DispEntry *di=layout->de; di->func != NULL; di++) {
if(di->func != disp.drawLat && di->func != disp.drawLon) continue;
di->func(di);
}
}
void Display::updateDisplayPos2() {
for(DispEntry *di=layout->de; di->func != NULL; di++) {
if(di->func != disp.drawAlt && di->func != disp.drawHS && di->func != disp.drawVS) continue;
di->func(di);
}
}
void Display::updateDisplayID() {
for(DispEntry *di=layout->de; di->func != NULL; di++) {
if(di->func != disp.drawID) continue;
di->func(di);
}
}
void Display::updateDisplayRSSI() {
for(DispEntry *di=layout->de; di->func != NULL; di++) {
if(di->func != disp.drawRSSI) continue;
di->func(di);
}
}
void Display::updateStat() {
for(DispEntry *di=layout->de; di->func != NULL; di++) {
if(di->func != disp.drawQS) continue;
di->func(di);
}
}
void Display::updateDisplayRXConfig() {
for(DispEntry *di=layout->de; di->func != NULL; di++) {
if(di->func != disp.drawQS && di->func != disp.drawAFC) continue;
di->func(di);
}
}
void Display::updateDisplayIP() {
for(DispEntry *di=layout->de; di->func != NULL; di++) {
if(di->func != disp.drawIP) continue;
Serial.printf("updateDisplayIP: %d %d\n",di->x, di->y);
di->func(di);
}
}
void Display::updateDisplay() {
for(DispEntry *di=layout->de; di->func != NULL; di++) {
di->func(di);
}
}
Display disp = Display();

Wyświetl plik

@ -0,0 +1,64 @@
#ifndef Display_h
#define Display_h
#define FONT_LARGE 1
#define FONT_SMALL 0
struct DispEntry {
int8_t y;
int8_t x;
int16_t fmt;
void (*func)(DispEntry *de);
const char *extra;
};
struct DispInfo {
DispEntry *de;
uint8_t *actions;
int16_t *timeouts;
};
class Display {
private:
public:
void setLayout(DispInfo *layout);
DispInfo *layout;
Display();
static char buf[17];
static void drawLat(DispEntry *de);
static void drawLon(DispEntry *de);
static void drawAlt(DispEntry *de);
static void drawHS(DispEntry *de);
static void drawVS(DispEntry *de);
static void drawID(DispEntry *de);
static void drawRSSI(DispEntry *de);
static void drawQS(DispEntry *de);
static void drawType(DispEntry *de);
static void drawFreq(DispEntry *de);
static void drawAFC(DispEntry *de);
static void drawIP(DispEntry *de);
static void drawSite(DispEntry *de);
static void drawTelemetry(DispEntry *de);
static void drawGPS(DispEntry *de);
static void drawText(DispEntry *de);
void clearIP();
void setIP(const char *ip, bool AP);
void updateDisplayPos();
void updateDisplayPos2();
void updateDisplayID();
void updateDisplayRSSI();
void updateStat();
void updateDisplayRXConfig();
void updateDisplayIP();
void updateDisplay();
void setLayout(int layout);
};
extern Display disp;
#endif

Wyświetl plik

@ -5,7 +5,7 @@
#include "rsc.h"
#include "Sonde.h"
#define RS41_DEBUG 1
#define RS41_DEBUG 0
#if RS41_DEBUG
#define RS41_DBG(x) x
@ -13,6 +13,10 @@
#define RS41_DBG(x)
#endif
#define RS41MAXLEN (320)
static byte data[800];
static int dpos = 0;
static uint16_t CRCTAB[256];
#define X2C_DIVR(a, b) ((b) != 0.0f ? (a)/(b) : (a))
@ -69,7 +73,7 @@ static void Gencrctab(void)
} /* end for */
} /* end Gencrctab() */
int RS41::setup()
int RS41::setup(float frequency)
{
#if RS41_DEBUG
Serial.println("Setup sx1278 for RS41 sonde");
@ -99,11 +103,11 @@ int RS41::setup()
#endif
if(sx1278.setAFCBandwidth(sonde.config.rs41.agcbw)!=0) {
RS41_DBG(Serial.println("Setting AFC bandwidth 25 kHz FAILED"));
RS41_DBG(Serial.printf("Setting AFC bandwidth %d Hz FAILED", sonde.config.rs41.agcbw));
return 1;
}
if(sx1278.setRxBandwidth(sonde.config.rs41.rxbw)!=0) {
RS41_DBG(Serial.println("Setting RX bandwidth 12kHz FAILED"));
RS41_DBG(Serial.printf("Setting RX bandwidth to %d Hz FAILED", sonde.config.rs41.rxbw));
return 1;
}
// Enable auto-AFC, auto-AGC, RX Trigger by preamble
@ -131,14 +135,18 @@ int RS41::setup()
RS41_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
RS41_DBG(Serial.println("Setting SX1278 config for RS41 finished\n"); Serial.println());
return 0;
}
int RS41::setFrequency(float frequency) {
Serial.print("RS41: setting RX frequency to ");
Serial.println(frequency);
return sx1278.setFrequency(frequency);
int retval = sx1278.setFrequency(frequency);
dpos = 0;
#if RS41_DEBUG
RS41_DBG(Serial.println("Setting SX1278 config for RS41 finished\n"); Serial.println());
#endif
// go go go
sx1278.setPayloadLength(RS41MAXLEN-8); // Expect 320-8 bytes or 518-8 bytes (8 byte header)
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
return retval;
}
uint32_t RS41::bits2val(const uint8_t *bits, int len) {
@ -439,7 +447,7 @@ void RS41::printRaw(uint8_t *data, int len)
Serial.println();
}
int RS41::bitsToBytes(uint8_t *bits, uint8_t *bytes, int len)
void RS41::bitsToBytes(uint8_t *bits, uint8_t *bytes, int len)
{
int i;
for(i=0; i<len*4; i++) {
@ -452,7 +460,7 @@ static unsigned char lookup[16] = {
0x0, 0x8, 0x4, 0xc, 0x2, 0xa, 0x6, 0xe,
0x1, 0x9, 0x5, 0xd, 0x3, 0xb, 0x7, 0xf, };
uint8_t reverse(uint8_t n) {
static uint8_t reverse(uint8_t n) {
return (lookup[n&0x0f] << 4) | lookup[n>>4];
}
@ -464,23 +472,37 @@ static uint8_t scramble[64] = {150U,131U,62U,81U,177U,73U,8U,152U,50U,5U,89U,
180U,182U,6U,170U,244U,35U,120U,110U,59U,174U,191U,123U,76U,
193U};
static byte data[800];
#define RS41MAXLEN (320)
int RS41::receiveFrame() {
//sx1278.setPayloadLength(518-8); // Expect 320-8 bytes or 518-8 bytes (8 byte header)
sx1278.setPayloadLength(RS41MAXLEN-8); // Expect 320-8 bytes or 518-8 bytes (8 byte header)
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
int RS41::receive() {
sx1278.setPayloadLength(RS41MAXLEN-8);
int e = sx1278.receivePacketTimeout(1000, data+8);
if(e) { Serial.println("TIMEOUT"); return RX_TIMEOUT; } //if timeout... return 1
if(e) { Serial.println("TIMEOUT"); return RX_TIMEOUT; }
for(int i=0; i<RS41MAXLEN; i++) { data[i] = reverse(data[i]); }
//printRaw(data, MAXLEN);
for(int i=0; i<RS41MAXLEN; i++) { data[i] = data[i] ^ scramble[i&0x3F]; }
//printRaw(data, MAXLEN);
int res = decode41(data, RS41MAXLEN);
return res==0 ? RX_OK : RX_ERROR;
for(int i=0; i<RS41MAXLEN; i++) { data[i] = reverse(data[i]); }
for(int i=0; i<RS41MAXLEN; i++) { data[i] = data[i] ^ scramble[i&0x3F]; }
return decode41(data, RS41MAXLEN);
}
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;
}
RS41 rs41 = RS41();

Wyświetl plik

@ -22,7 +22,7 @@ class RS41
private:
uint32_t bits2val(const uint8_t *bits, int len);
void printRaw(uint8_t *data, int len);
int bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);
void bitsToBytes(uint8_t *bits, uint8_t *bytes, int len);
int decode41(byte *data, int maxlen);
#define B 8
@ -46,9 +46,18 @@ private:
public:
RS41();
int setup();
int setFrequency(float frequency);
int receiveFrame();
// New interface:
// setup() is called when channel is activated (sets mode and frequency and activates receiver)
int setup(float frequency);
// processRXbyte is called by background task for each received byte
// should be fast enough to not cause sx127x fifo buffer overflow
// void processRXbyte(uint8_t data);
// is called approx. 1x per second, may do some post-processing of received data
// and update information in sonde data structure
// returns infomration about sucess/error (for timers and for quality bar in display)
int receive();
int waitRXcomplete();
//int receiveFrame();
int use_ecc = 1;
};

Wyświetl plik

@ -0,0 +1,720 @@
/* RS92 decoder functions */
#include "RS92.h"
#include "SX1278FSK.h"
#include "rsc.h"
#include "Sonde.h"
#include <SPIFFS.h>
// well...
#include "rs92gps.h"
#define RS92_DEBUG 1
#if RS92_DEBUG
#define RS92_DBG(x) x
#else
#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))
#define X2C_DIVL(a, b) ((a)/(b))
static uint32_t X2C_LSH(uint32_t a, int32_t length, int32_t n)
{
uint32_t m;
m = 0;
m = (length == 32) ? 0xFFFFFFFFl : (1 << length) - 1;
if (n > 0) {
if (n >= (int32_t)length)
return 0;
return (a << n) & m;
}
if (n <= (int32_t)-length)
return 0;
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;
uint16_t i;
uint16_t crc;
if(!CRCTAB) { CRCTAB=(uint16_t *)malloc(256*sizeof(uint16_t)); }
for (i = 0U; i<=255U; i++) {
crc = (uint16_t)(i*256U);
for (j = 0U; j<=7U; j++) {
if ((0x8000U & crc)) crc = X2C_LSH(crc,16,1)^0x1021U;
else crc = X2C_LSH(crc,16,1);
} /* end for */
CRCTAB[i] = X2C_LSH(crc,16,-8)|X2C_LSH(crc,16,8);
} /* end for */
} /* end Gencrctab() */
static byte data1[512]={0x2A, 0x2A, 0x2A, 0x2A, 0x2A, 0x10};
static byte data2[512]={0x2A, 0x2A, 0x2A, 0x2A, 0x2A, 0x10};
static byte *dataptr=data1;
static uint8_t rxbitc;
static int32_t asynst[10]={0};
static uint16_t rxbyte;
int rxp=0;
static int haveNewFrame = 0;
static int lastFrame = 0;
static int headerDetected = 0;
int RS92::setup(float frequency)
{
#if RS92_DEBUG
Serial.println("Setup sx1278 for RS92 sonde");
#endif
if(!initialized) {
Gencrctab();
initrsc();
// not here for now.... get_eph("/brdc.19n");
initialized = true;
}
if(sx1278.ON()!=0) {
RS92_DBG(Serial.println("Setting SX1278 power on FAILED"));
return 1;
}
if(sx1278.setFSK()!=0) {
RS92_DBG(Serial.println("Setting FSJ mode FAILED"));
return 1;
}
if(sx1278.setBitrate(4800)!=0) {
RS92_DBG(Serial.println("Setting bitrate 4800bit/s FAILED"));
return 1;
}
#if RS92_DEBUG
float br = sx1278.getBitrate();
Serial.print("Exact bitrate is ");
Serial.println(br);
#endif
if(sx1278.setAFCBandwidth(sonde.config.rs92.rxbw)!=0) {
RS92_DBG(Serial.printf("Setting AFC bandwidth %d Hz FAILED", sonde.config.rs92.rxbw));
return 1;
}
if(sx1278.setRxBandwidth(sonde.config.rs92.rxbw)!=0) {
RS92_DBG(Serial.printf("Setting RX bandwidth to %d Hz FAILED", sonde.config.rs92.rxbw));
return 1;
}
// Enable auto-AFC, auto-AGC, RX Trigger by preamble
if(sx1278.setRxConf(0x1E)!=0) {
RS92_DBG(Serial.println("Setting RX Config FAILED"));
return 1;
}
// Set autostart_RX to 01, preamble 0, SYNC detect==on, syncsize=3 (==4 byte
//char header[] = "0110.0101 0110.0110 1010.0101 1010.1010";
//const char *SYNC="\x10\xB6\xCA\x11\x22\x96\x12\xF8";
//const char *SYNC="\x08\x6D\x53\x88\x44\x69\x48\x1F";
// was 0x57
//const char *SYNC="\x99\x9A";
#if 1
// version 1, working with continuous RX
const char *SYNC="\x66\x65";
if(sx1278.setSyncConf(0x70, 2, (const uint8_t *)SYNC)!=0) {
RS92_DBG(Serial.println("Setting SYNC Config FAILED"));
return 1;
}
if(sx1278.setPreambleDetect(0xA8)!=0) {
RS92_DBG(Serial.println("Setting PreambleDetect FAILED"));
return 1;
}
#endif
#if 0
// version 2, with per-packet rx start, untested
// header is 2a 10 65, i.e. with lsb first
// 0 0101 0100 1 0 0000 1000 1 0 1010 0110 1
// 10 10011001 10011010 01 10 10101010 01101010 01 10 01100110 10010110 01
// preamble 0x6A 0x66 0x6A
// i.e. preamble detector on (0x80), preamble detector size 1 (0x00), preample chip errors??? (0x0A)
// after 2a2a2a2a2a1065
if(sx1278.setPreambleDetect(0xA8)!=0) {
RS92_DBG(Serial.println("Setting PreambleDetect FAILED"));
return 1;
}
// sync config: ato restart (01), preamble polarity AA (0), sync on (1), resevered (0), syncsize 2+1 (010) => 0x52
const char *SYNC="\x6A\x66\x69";
if(sx1278.setSyncConf(0x52, 3, (const uint8_t *)SYNC)!=0) {
RS92_DBG(Serial.println("Setting SYNC Config FAILED"));
return 1;
}
// payload length is ((240 - 7)*10 +6)/8 = 292
#endif
// Packet config 1: fixed len, no mancecer, no crc, no address filter
// Packet config 2: packet mode, no home ctrl, no beackn, msb(packetlen)=0)
if(sx1278.setPacketConfig(0x08, 0x40)!=0) {
RS92_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
Serial.print("RS92: setting RX frequency to ");
Serial.println(frequency);
int res = sx1278.setFrequency(frequency);
// enable RX
sx1278.setPayloadLength(0); // infinite for now...
//sx1278.setPayloadLength(292);
sx1278.writeRegister(REG_OP_MODE, FSK_RX_MODE);
#if RS92_DEBUG
RS92_DBG(Serial.println("Setting SX1278 config for RS92 finished\n"); Serial.println());
#endif
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++) {
val |= (bits[j] << (len-1-j));
}
return val;
}
RS92::RS92() {
}
/* RS92 reed solomon decoder, from dxlAPRS
*/
#if 0
static char crcrs(const byte frame[], uint32_t frame_len,
int32_t from, int32_t to)
{
uint16_t crc;
int32_t i;
int32_t tmp;
crc = 0xFFFFU;
tmp = to-3L;
i = from;
if (i<=tmp) for (;; i++) {
crc = X2C_LSH(crc,16,-8)^CRCTAB[(uint32_t)((crc^(uint16_t)(uint8_t)frame[i])&0xFFU)];
if (i==tmp) break;
} /* end for */
return frame[to-1L]==(char)crc && frame[to-2L]==(char)X2C_LSH(crc,
16,-8);
} /* end crcrs() */
static int32_t getint32(const byte frame[], uint32_t frame_len,
uint32_t p)
{
uint32_t n;
uint32_t i;
n = 0UL;
for (i = 3UL;; i--) {
n = n*256UL+(uint32_t)(uint8_t)frame[p+i];
if (i==0UL) break;
} /* end for */
return (int32_t)n;
} /* end getint32() */
static uint32_t getcard16(const byte frame[], uint32_t frame_len,
uint32_t p)
{
return (uint32_t)(uint8_t)frame[p]+256UL*(uint32_t)(uint8_t)
frame[p+1UL];
} /* end getcard16() */
static int32_t getint16(const byte frame[], uint32_t frame_len,
uint32_t p)
{
uint32_t n;
n = (uint32_t)(uint8_t)frame[p]+256UL*(uint32_t)(uint8_t)
frame[p+1UL];
if (n>=32768UL) return (int32_t)(n-65536UL);
return (int32_t)n;
} /* end getint16() */
static void wgs84r(double x, double y, double z,
double * lat, double * long0,
double * heig)
{
double sl;
double ct;
double st;
double t;
double rh;
double xh;
double h;
h = x*x+y*y;
if (h>0.0) {
rh = (double)sqrt((float)h);
xh = x+rh;
*long0 = atang2(xh, y)*2.0;
if (*long0>3.1415926535898) *long0 = *long0-6.2831853071796;
t = (double)atan((float)(X2C_DIVL(z*1.003364089821,
rh)));
st = (double)sin((float)t);
ct = (double)cos((float)t);
*lat = (double)atan((float)
(X2C_DIVL(z+4.2841311513312E+4*st*st*st,
rh-4.269767270718E+4*ct*ct*ct)));
sl = (double)sin((float)*lat);
*heig = X2C_DIVL(rh,(double)cos((float)*lat))-(double)(X2C_DIVR(6.378137E+6f,
sqrt((float)(1.0-6.6943799901413E-3*sl*sl))));
}
else {
*lat = 0.0;
*long0 = 0.0;
*heig = 0.0;
}
/* lat:=atan(z/(rh*(1.0 - E2))); */
/* heig:=sqrt(h + z*z) - EARTHA; */
} /* end wgs84r() */
#endif
static int32_t reedsolomon92(uint8_t *buf, uint32_t buf_len)
{
uint32_t i;
int32_t res;
uint8_t b[256];
uint32_t eraspos[24];
for (i = 0UL; i<=255UL; i++) {
b[i] = 0;
} /* end for */
for (i = 0UL; i<=209UL; i++) {
b[230UL-i] = buf[i+6UL];
} /* end for */
for (i = 0UL; i<=23UL; i++) {
b[254UL-i] = buf[i+216UL];
} /* end for */
res = decodersc((char *)b, eraspos, 0L);
if (res>0L && res<=12L) {
for (i = 0UL; i<=209UL; i++) {
buf[i+6UL] = b[230UL-i];
} /* end for */
for (i = 0UL; i<=23UL; i++) {
buf[i+216UL] = b[254UL-i];
} /* end for */
}
return res;
} /* end reedsolomon92() */
void printRaw(uint8_t *data, int len)
{
char buf[3];
int i;
for(i=0; i<len; i++) {
snprintf(buf, 3, "%02X", data[i]);
Serial.print(buf);
}
Serial.println();
}
void RS92::decodeframe92(uint8_t *data)
{
//uint32_t gpstime;
//uint32_t flen;
//uint32_t j;
int32_t corr;
corr = reedsolomon92(data, 301ul);
//int calok;
//int mesok;
//uint32_t calibok;
lastFrame = (dataptr==data1)?1:2;
Serial.printf("rs corr is %d --- data:%p data1:%p data2:%p lastframe=%d\n", corr, data, data1, data2, lastFrame);
dataptr = (dataptr==data1)?data2:data1;
//print_frame(data, 240);
#if 0
/* from sondemod*/
int p=6;
while(1) {
uint8_t typ = data[p];
if(typ==0xff) break;
++p;
int len = ((uint32_t)data[p])*2 + 2;
Serial.printf("type %c: len=%d\n", typ, len);
//printRaw(data+p, len+2);
if(len>240) {
Serial.print("RS92 frame too long: ");
Serial.println(len);
break;
}
++p;
j=0;
uint16_t crc = 0xFFFF;
while(j<len) {
if(j < len-2) {
for(int ic = 0; ic<=7; ic++) {
if (((0x8000&crc)!=0) != ( ((1<<(7-ic))&data[p])!=0 )) {
crc <<= 1;
crc ^= 0x1021;
} else {
crc <<= 1;
}
}
}
++p;
++j;
if(p>240) {
Serial.println("eof");
return;
}
}
if ( (((uint8_t)(crc&0xff)) != data[p-2]) || (((uint8_t)(crc>>8)) != data[p-1])) {
Serial.printf("************ crc error: expected %04x\n",crc);
continue;
}
switch(typ) {
case 'e':
Serial.println("cal ");
//docalib(sf, 256, objname, 9, &contextr9, &mhz, &frameno);
// ...
break;
case 'i':
if(calok && calibok==0xffffffff) {
//domes(sf, 256, &hp, &hyg, &temp)
mesok = 1;
}
break;
case 'g':
Serial.println("gps ");
if(1||calok) {
//dogps(data+p-len, 256, &contextr9, &contextr9.timems, &gpstime);
}
break;
case 'h':
Serial.println("data "); break;
if(data[p+2]!=3) Serial.println("aux ");
// ..
break;
}
}
#endif
} /* end decodeframe92() */
void RS92::printRaw(uint8_t *data, int len)
{
char buf[3];
int i;
for(i=0; i<len; i++) {
snprintf(buf, 3, "%02X", data[i]);
Serial.print(buf);
}
Serial.println();
}
#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)
{
dataptr[rxp] = b;
if(rxp>=5 || b=='*') rxp++; else rxp=0;
if(rxp==6) { // header detected
headerDetected = 1;
}
if(rxp>=240) { // frame complete... (240 byte)
rxp=0;
//printRaw(data, 240);
decodeframe92(dataptr);
haveNewFrame = 1;
}
} /* end stobyte92() */
uint32_t rxdata;
bool rxsearching=true;
// search for
// 101001100110011010011010011001100110100110101010100110101001
// 1010011001100110100110100110 0110.0110 1001.1010 1010.1001 1010.1001 => 0x669AA9A9
void RS92::process8N1data(uint8_t dt)
{
for(int i=0; i<8; i++) {
uint8_t d = (dt&0x80)?1:0;
rxdata = (rxdata<<1) | d;
if((rxbitc&1)==1) { rxbyte = (rxbyte>>1) + (d<<9); } // mancester decoded data
dt <<= 1;
//
if(rxsearching) {
if(rxdata == 0x669AA9A9) {
rxsearching = false;
rxbitc = 0;
rxp = 6;
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;
}
} else {
rxbitc = (rxbitc+1)%20;
if(rxbitc == 0) { // got startbit, 8 data bit, stop bit
//Serial.printf("%03x ",rxbyte);
dataptr[rxp++] = (rxbyte>>1)&0xff;
if(rxp==7 && dataptr[6] != 0x65) {
Serial.printf("wrong start: %02x\n",dataptr[6]);
rxsearching = true;
}
if(rxp>=240) {
rxsearching = true;
decodeframe92(dataptr);
haveNewFrame = 1;
}
}
}
}
}
void process8N1dataOrig(uint8_t data)
{
// data contains 8 bits (after mancester encoding; 4 real bit), big endian
for(int i=0; i<4; i++) {
uint8_t d = (data&0x80)?1:0;
data = data << 2;
rxbyte = (rxbyte>>1) + (d<<8);
int maxk = 0;
int max0 = 0;
for(int k = 0; k< 10; k++) {
int n = asynst[k] - asynst[(k+1)%10];
if(abs(n)>abs(max0)) {
max0 = n;
maxk = k;
}
}
//Serial.printf("<%d,%d,%d>",max0,maxk,rxbitc);
if(rxbitc == maxk) {
if(max0<0) { rxbyte = rxbyte ^ 0xFF; }
/////TODO stobyte92( rxbyte&0xff );
}
//Serial.printf("%d:",asynst[rxbitc]);
if(d) {
asynst[rxbitc] += (32767-asynst[rxbitc])/16;
} else {
asynst[rxbitc] -= (32767+asynst[rxbitc])/16;
}
//Serial.printf("%d ",asynst[rxbitc]);
rxbitc = (rxbitc+1) % 10;
}
}
int RS92::receive() {
unsigned long t0 = millis();
Serial.printf("RS92::receive() start at %ld\n",t0);
while( millis() - t0 < 1000 ) {
uint8_t value = sx1278.readRegister(REG_IRQ_FLAGS2);
if ( bitRead(value, 7) ) {
Serial.println("FIFO full");
}
if ( bitRead(value, 4) ) {
Serial.println("FIFO overflow");
}
if ( bitRead(value, 2) == 1 ) {
Serial.println("FIFO: ready()");
sx1278.clearIRQFlags();
}
if(bitRead(value, 6) == 0) { // while FIFO not empty
byte data = sx1278.readRegister(REG_FIFO);
//Serial.printf("%02x",data);
process8N1data(data);
value = sx1278.readRegister(REG_IRQ_FLAGS2);
} else {
if(headerDetected) {
t0 = millis(); // restart timer... don't time out if header detected...
headerDetected = 0;
}
if(haveNewFrame) {
Serial.printf("RS92::receive(): new frame complete after %ldms\n", millis()-t0);
haveNewFrame = 0;
return RX_OK;
}
delay(2);
}
}
Serial.printf("RS92::receive() timed out\n");
return RX_TIMEOUT; // TODO RX_OK;
}
#define RS92MAXLEN (240)
int RS92::waitRXcomplete() {
// called after complete...
Serial.printf("decoding frame %d\n", lastFrame);
print_frame(lastFrame==1?data1:data2, 240);
SondeInfo *si = sonde.sondeList+rxtask.receiveSonde;
si->lat = gpx.lat;
si->lon = gpx.lon;
si->alt = gpx.alt;
si->vs = gpx.vU;
si->hs = gpx.vH;
si->dir = gpx.vD;
si->validPos = 0x3f;
memcpy(si->id, gpx.id, 9);
si->validID = true;
#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

@ -0,0 +1,96 @@
/*
* RS92.h
* Functions for decoding RS92 sondes with SX127x chips
* Copyright (C) 2019 Hansi Reiser, dl9rdz
*
* SPDX-License-Identifier: GPL-2.0+
*/
#ifndef RS92_h
#define RS92_h
#include <stdlib.h>
#include <stdint.h>
#include <Arduino.h>
#ifndef inttypes_h
#include <inttypes.h>
#endif
struct CONTEXTR9 {
char calibdata[512];
uint32_t calibok;
char mesok;
char posok;
char framesent;
double lat;
double lon;
double heig;
double speed;
double dir;
double climb;
double lastlat;
double laslong;
double lastalt;
double lastspeed;
double lastdir;
double lastclb;
float hrmsc;
float vrmsc;
double hp;
double hyg;
double temp;
double ozontemp;
double ozon;
uint32_t goodsats;
uint32_t timems;
uint32_t framenum;
};
/* Main class */
class RS92
{
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);
int decode92(byte *data, int maxlen);
uint8_t hamming_conf[ 7*8]; // 7*8=56
uint8_t hamming_dat1[13*8]; // 13*8=104
uint8_t hamming_dat2[13*8];
uint8_t block_conf[ 7*4]; // 7*4=28
uint8_t block_dat1[13*4]; // 13*4=52
uint8_t block_dat2[13*4];
uint8_t H[4][8] = // extended Hamming(8,4) particy check matrix
{{ 0, 1, 1, 1, 1, 0, 0, 0},
{ 1, 0, 1, 1, 0, 1, 0, 0},
{ 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:
// 1-bit-error-Syndrome
boolean initialized = false;
public:
RS92();
int setup(float frequency);
int receive();
int waitRXcomplete();
int use_ecc = 1;
};
extern RS92 rs92;
#endif

Wyświetl plik

@ -3,64 +3,70 @@
#include "Sonde.h"
#include "RS41.h"
#include "RS92.h"
#include "DFM.h"
#include "SX1278FSK.h"
#include "Display.h"
extern U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8;
extern SX1278FSK sx1278;
//SondeInfo si = { STYPE_RS41, 403.450, "P1234567", true, 48.1234, 14.9876, 543, 3.97, -0.5, true, 120 };
const char *sondeTypeStr[5] = { "DFM6", "DFM9", "RS41" };
RXTask rxtask = { -1, -1, -1, 0xFFFF, 0 };
static unsigned char kmh_tiles[] U8X8_PROGMEM = {
0x1F, 0x04, 0x0A, 0x11, 0x00, 0x1F, 0x02, 0x04, 0x42, 0x3F, 0x10, 0x08, 0xFC, 0x22, 0x20, 0xF8
};
static unsigned char ms_tiles[] U8X8_PROGMEM = {
0x1F, 0x02, 0x04, 0x02, 0x1F, 0x40, 0x20, 0x10, 0x08, 0x04, 0x12, 0xA4, 0xA4, 0xA4, 0x40, 0x00
};
static unsigned char stattiles[4][4] = {
0x00, 0x1F, 0x00, 0x00 , // | == ok
0x00, 0x10, 0x10, 0x00 , // . == no header found
0x1F, 0x15, 0x15, 0x00 , // E == decode error
0x00, 0x00, 0x00, 0x00 }; // ' ' == unknown/unassigned
const char *evstring[]={"NONE", "KEY1S", "KEY1D", "KEY1M", "KEY1L", "KEY2S", "KEY2D", "KEY2M", "KEY2L",
"VIEWTO", "RXTO", "NORXTO", "(max)"};
byte myIP_tiles[8*11];
const char *RXstr[]={"RX_OK", "RX_TIMEOUT", "RX_ERROR", "RX_UNKNOWN"};
static const uint8_t font[10][5]={
0x3E, 0x51, 0x49, 0x45, 0x3E, // 0
0x00, 0x42, 0x7F, 0x40, 0x00, // 1
0x42, 0x61, 0x51, 0x49, 0x46, // 2
0x21, 0x41, 0x45, 0x4B, 0x31, // 3
0x18, 0x14, 0x12, 0x7F, 0x10, // 4
0x27, 0x45, 0x45, 0x45, 0x39, // 5
0x3C, 0x4A, 0x49, 0x49, 0x30, // 6
0x01, 0x01, 0x79, 0x05, 0x03, // 7
0x36, 0x49, 0x49, 0x49, 0x36, // 8
0x06, 0x49, 0x39, 0x29, 0x1E }; // 9; .=0x40
int getKeyPressEvent(); /* in RX_FSK.ino */
static uint8_t halfdb_tile[8]={0x80, 0x27, 0x45, 0x45, 0x45, 0x39, 0x00, 0x00};
static uint8_t halfdb_tile1[8]={0x00, 0x38, 0x28, 0x28, 0x28, 0xC8, 0x00, 0x00};
static uint8_t halfdb_tile2[8]={0x00, 0x11, 0x02, 0x02, 0x02, 0x01, 0x00, 0x00};
static uint8_t empty_tile[8]={0x80, 0x3E, 0x51, 0x49, 0x45, 0x3E, 0x00, 0x00};
static uint8_t empty_tile1[8]={0x00, 0xF0, 0x88, 0x48, 0x28, 0xF0, 0x00, 0x00};
static uint8_t empty_tile2[8]={0x00, 0x11, 0x02, 0x02, 0x02, 0x01, 0x00, 0x00};
static uint8_t ap_tile[8]={0x00,0x04,0x22,0x92, 0x92, 0x22, 0x04, 0x00};
/* Task model:
* There is a background task for all SX1278 interaction.
* - On startup and on each mode/frequency change (requested by setting requestNextSonde
* to an sonde index >=0) it calls Sonde::setup(), which will call the new decoder's
* setup function. Setup will update the value currentSonde.
* - Periodically it calls Sonde::receive(), which calls the current decoder's receive()
* function. It should return control to the SX1278 main loop at least once per second.
* It will also set the internal variable receiveResult. The decoder's receive function
* must make sure that there are no FIFI overflows in the SX1278.
* - the Arduino main loop will call the waitRXcomplete function, which should return as
* soon as there is some new data to display, or no later than after 1s, returning the
* value of receiveResult (or timeout, if receiveResult was not set within 1s). It
* should also return immediately if there is some keyboard input.
*/
int initlevels[40];
Sonde::Sonde() {
config.button_pin = 0;
for (int i = 0; i < 39; i++) {
initlevels[i] = gpio_get_level((gpio_num_t)i);
}
for (int i = 0; i < 39*3; i++) {
initlevels[i%39] += gpio_get_level((gpio_num_t)(i%39));
}
sondeList = (SondeInfo *)malloc((MAXSONDE+1)*sizeof(SondeInfo));
memset(sondeList, 0, (MAXSONDE+1)*sizeof(SondeInfo));
config.touch_thresh = 70;
config.led_pout = 9;
// Try autodetecting board type
// Seems like on startup, GPIO4 is 1 on v1 boards, 0 on v2.1 boards?
int autodetect = gpio_get_level((gpio_num_t)4);
if(autodetect==1) {
config.gps_rxd = -1;
config.gps_txd = -1;
if(initlevels[16]==0) {
config.oled_sda = 4;
config.oled_scl = 15;
config.button_pin = 0;
config.button2_pin = T4 + 128; // T4 == GPIO13
} else {
config.oled_sda = 21;
config.oled_scl = 22;
if(initlevels[17]==0) { // T-Beam
config.button_pin = 39;
config.button2_pin = T4 + 128; // T4 == GPIO13
config.gps_rxd = 12;
} else {
config.button_pin = 2 + 128; // GPIO2 / T2
config.button2_pin = 14 + 128; // GPIO14 / T6
}
}
//
config.oled_rst = 16;
@ -71,16 +77,20 @@ Sonde::Sonde() {
config.debug=0;
config.wifi=1;
config.wifiap=1;
config.display=1;
config.startfreq=400;
config.channelbw=10;
config.spectrum=10;
config.timer=0;
config.marker=0;
config.norx_timeout=0;
config.showafc=0;
config.freqofs=0;
config.rs41.agcbw=25;
config.rs41.rxbw=12;
config.rs41.agcbw=12500;
config.rs41.rxbw=6300;
config.rs92.rxbw=12500;
config.rs92.alt2d=480;
config.dfm.agcbw=20800;
config.dfm.rxbw=10400;
config.udpfeed.active = 1;
config.udpfeed.type = 0;
strcpy(config.udpfeed.host, "192.168.42.20");
@ -115,6 +125,10 @@ void Sonde::setConfig(const char *cfg) {
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,"touch_thresh")==0) {
config.touch_thresh = atoi(val);
} else if(strcmp(cfg,"led_pout")==0) {
config.led_pout = atoi(val);
} else if(strcmp(cfg,"oled_sda")==0) {
@ -123,6 +137,10 @@ void Sonde::setConfig(const char *cfg) {
config.oled_scl = atoi(val);
} else if(strcmp(cfg,"oled_rst")==0) {
config.oled_rst = 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,"maxsonde")==0) {
config.maxsonde = atoi(val);
if(config.maxsonde>MAXSONDE) config.maxsonde=MAXSONDE;
@ -132,6 +150,9 @@ void Sonde::setConfig(const char *cfg) {
config.wifi = atoi(val);
} else if(strcmp(cfg,"wifiap")==0) {
config.wifiap = atoi(val);
} else if(strcmp(cfg,"display")==0) {
config.display = atoi(val);
disp.setLayout(config.display);
} else if(strcmp(cfg,"startfreq")==0) {
config.startfreq = atoi(val);
} else if(strcmp(cfg,"channelbw")==0) {
@ -142,8 +163,6 @@ void Sonde::setConfig(const char *cfg) {
config.timer = atoi(val);
} else if(strcmp(cfg,"marker")==0) {
config.marker = atoi(val);
} else if(strcmp(cfg,"norx_timeout")==0) {
config.norx_timeout = atoi(val);
} else if(strcmp(cfg,"showafc")==0) {
config.showafc = atoi(val);
} else if(strcmp(cfg,"freqofs")==0) {
@ -152,6 +171,14 @@ void Sonde::setConfig(const char *cfg) {
config.rs41.agcbw = atoi(val);
} else if(strcmp(cfg,"rs41.rxbw")==0) {
config.rs41.rxbw = atoi(val);
} else if(strcmp(cfg,"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,"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) {
@ -182,25 +209,11 @@ void Sonde::setConfig(const char *cfg) {
}
void Sonde::clearIP() {
memset(myIP_tiles, 0, 11*8);
disp.clearIP();
}
void Sonde::setIP(const char *ip, bool AP) {
memset(myIP_tiles, 0, 11*8);
int len = strlen(ip);
int pix = (len-3)*6+6;
int tp = 80-pix+8;
if(AP) memcpy(myIP_tiles+(tp<16?0:8), ap_tile, 8);
for(int i=0; i<len; i++) {
if(ip[i]=='.') { myIP_tiles[tp++]=0x40; myIP_tiles[tp++]=0x00; }
else {
int idx = ip[i]-'0';
memcpy(myIP_tiles+tp, &font[idx], 5);
myIP_tiles[tp+5] = 0;
tp+=6;
}
}
while(tp<8*10) { myIP_tiles[tp++]=0; }
disp.setIP(ip, AP);
}
void Sonde::clearSonde() {
@ -211,6 +224,7 @@ void Sonde::addSonde(float frequency, SondeType type, int active, char *launchsi
Serial.println("Cannot add another sonde, MAXSONDE reached");
return;
}
Serial.printf("Adding %f - %d - %d - %s\n", frequency, type, active, launchsite);
sondeList[nSonde].type = type;
sondeList[nSonde].freq = frequency;
sondeList[nSonde].active = active;
@ -218,8 +232,13 @@ void Sonde::addSonde(float frequency, SondeType type, int active, char *launchsi
memcpy(sondeList[nSonde].rxStat, "\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3\x3", 18); // unknown/undefined
nSonde++;
}
// called by updateState (only)
void Sonde::nextConfig() {
currentSonde++;
if(currentSonde>=nSonde) {
currentSonde=0;
}
// Skip non-active entries (but don't loop forever if there are no active ones)
for(int i=0; i<config.maxsonde; i++) {
if(!sondeList[currentSonde].active) {
@ -227,154 +246,257 @@ void Sonde::nextConfig() {
if(currentSonde>=nSonde) currentSonde=0;
}
}
if(currentSonde>=nSonde) {
currentSonde=0;
}
void Sonde::nextRxSonde() {
rxtask.currentSonde++;
if(rxtask.currentSonde>=nSonde) {
rxtask.currentSonde=0;
}
setup();
for(int i=0; i<config.maxsonde; i++) {
if(!sondeList[rxtask.currentSonde].active) {
rxtask.currentSonde++;
if(rxtask.currentSonde>=nSonde) rxtask.currentSonde=0;
}
}
Serial.printf("nextRxSonde: %d\n", rxtask.currentSonde);
}
SondeInfo *Sonde::si() {
return &sondeList[currentSonde];
}
void Sonde::setup() {
// Test only: setIP("123.456.789.012");
// update receiver config: TODO
Serial.print("Setting up receiver on channel ");
Serial.println(currentSonde);
switch(sondeList[currentSonde].type) {
if(rxtask.currentSonde<0 || rxtask.currentSonde>=config.maxsonde) {
Serial.print("Invalid rxtask.currentSonde: ");
Serial.println(rxtask.currentSonde);
rxtask.currentSonde = 0;
}
// update receiver config
Serial.print("\nSonde::setup() on sonde index ");
Serial.println(rxtask.currentSonde);
switch(sondeList[rxtask.currentSonde].type) {
case STYPE_RS41:
rs41.setup();
rs41.setFrequency(sondeList[currentSonde].freq * 1000000);
rs41.setup(sondeList[rxtask.currentSonde].freq * 1000000);
break;
case STYPE_DFM06:
case STYPE_DFM09:
dfm.setup( sondeList[currentSonde].type==STYPE_DFM06?0:1 );
dfm.setFrequency(sondeList[currentSonde].freq * 1000000);
dfm.setup( sondeList[rxtask.currentSonde].freq * 1000000, sondeList[rxtask.currentSonde].type==STYPE_DFM06?0:1 );
break;
case STYPE_RS92:
rs92.setup( sondeList[rxtask.currentSonde].freq * 1000000);
}
// debug
float afcbw = sx1278.getAFCBandwidth();
float rxbw = sx1278.getRxBandwidth();
Serial.printf("AFC BW: %f RX BW: %f\n", afcbw, rxbw);
}
int Sonde::receiveFrame() {
int ret;
if(sondeList[currentSonde].type == STYPE_RS41) {
ret = rs41.receiveFrame();
void Sonde::receive() {
uint16_t res = 0;
SondeInfo *si = &sondeList[rxtask.currentSonde];
switch(si->type) {
case STYPE_RS41:
res = rs41.receive();
break;
case STYPE_RS92:
res = rs92.receive();
break;
case STYPE_DFM06:
case STYPE_DFM09:
res = dfm.receive();
break;
}
// state information for RX_TIMER / NORX_TIMER events
if(res==0) { // RX OK
if(si->lastState != 1) {
si->rxStart = millis();
si->lastState = 1;
}
} else { // RX not ok
if(si->lastState != 0) {
si->norxStart = millis();
si->lastState = 0;
}
}
Serial.printf("debug: res was %d, now lastState is %d\n", res, si->lastState);
// we should handle timer events here, because after returning from receive,
// we'll directly enter setup
rxtask.receiveSonde = rxtask.currentSonde; // pass info about decoded sonde to main loop
int event = getKeyPressEvent();
if (!event) event = timeoutEvent(si);
int action = (event==EVT_NONE) ? ACT_NONE : disp.layout->actions[event];
// If action is to move to a different sonde index, we do update things here, set activate
// to force the sx1278 task to call sonde.setup(), and pass information about sonde to
// main loop (display update...)
if(action == ACT_NEXTSONDE || action==ACT_PREVSONDE) {
// handled here...
nextRxSonde();
action = ACT_SONDE(rxtask.currentSonde);
if(rxtask.activate==-1) {
// race condition here. maybe better use mutex. TODO
rxtask.activate = action;
}
}
res = (action<<8) | (res&0xff);
Serial.printf("receive Result is %04x\n", res);
// let waitRXcomplete resume...
rxtask.receiveResult = res;
}
// return (action<<8) | (rxresult)
uint16_t Sonde::waitRXcomplete() {
uint16_t res=0;
uint32_t t0 = millis();
rxloop:
while( rxtask.receiveResult==0xFFFF && millis()-t0 < 2000) { delay(50); }
if( rxtask.receiveResult == RX_UPDATERSSI ) {
Serial.println("RSSI update");
rxtask.receiveResult = 0xFFFF;
disp.updateDisplayRSSI();
goto rxloop;
}
if( rxtask.receiveResult==0xFFFF) {
res = RX_TIMEOUT;
} else {
ret = dfm.receiveFrame();
res = rxtask.receiveResult;
}
rxtask.receiveResult = 0xFFFF;
/// TODO: THis has caused an exception when swithcing back to spectrumm...
Serial.printf("waitRXcomplete returning %04x (%s)\n", res, (res&0xff)<4?RXstr[res&0xff]:"");
// currently used only by RS92
// TODO: rxtask.currentSonde might not be the right thing (after sonde channel change)
switch(sondeList[/*rxtask.*/currentSonde].type) {
case STYPE_RS41:
rs41.waitRXcomplete();
break;
case STYPE_RS92:
rs92.waitRXcomplete();
break;
case STYPE_DFM06:
case STYPE_DFM09:
dfm.waitRXcomplete();
break;
}
memmove(sonde.si()->rxStat+1, sonde.si()->rxStat, 17);
sonde.si()->rxStat[0] = ret;
return ret; // 0: OK, 1: Timeuot, 2: Other error, 3: unknown
sonde.si()->rxStat[0] = res;
return res;
}
uint8_t Sonde::timeoutEvent(SondeInfo *si) {
uint32_t now = millis();
#if 1
Serial.printf("Timeout check: %d - %d vs %d; %d - %d vs %d; %d - %d vs %d\n",
now, si->viewStart, disp.layout->timeouts[0],
now, si->rxStart, disp.layout->timeouts[1],
now, si->norxStart, disp.layout->timeouts[2]);
#endif
Serial.printf("lastState is %d\n", si->lastState);
if(disp.layout->timeouts[0]>=0 && now - si->viewStart >= disp.layout->timeouts[0]) {
Serial.println("View timer expired");
return EVT_VIEWTO;
}
if(si->lastState==1 && disp.layout->timeouts[1]>=0 && now - si->rxStart >= disp.layout->timeouts[1]) {
Serial.println("RX timer expired");
return EVT_RXTO;
}
if(si->lastState==0 && disp.layout->timeouts[2]>=0 && now - si->norxStart >= disp.layout->timeouts[2]) {
Serial.println("NORX timer expired");
return EVT_NORXTO;
}
return 0;
}
uint8_t Sonde::updateState(uint8_t event) {
Serial.printf("Sonde::updateState for event %d\n", event);
// No change
if(event==ACT_NONE) return 0xFF;
// In all cases (new display mode, new sonde) we reset the mode change timers
sonde.sondeList[sonde.currentSonde].viewStart = millis();
sonde.sondeList[sonde.currentSonde].lastState = -1;
// Moving to a different display mode
if (event==ACT_DISPLAY_SPECTRUM || event==ACT_DISPLAY_WIFI) {
// main loop will call setMode() and disable sx1278 background task
return event;
}
int n = event;
if(event==ACT_DISPLAY_DEFAULT) {
n = config.display;
}
if(n>=0&&n<5) {
disp.setLayout(n);
// TODO: This is kind of a hack...
// ACT_NEXTSONDE will cause loopDecoder to call enterMode(ST_DECODER)
//return ACT_NEXTSONDE;
// TODO::: we probably should clear the display?? -- YES
sonde.clearDisplay();
return 0xFF;
}
// Moving to a different value for currentSonde
// TODO: THis should be done in sx1278 task, not in main loop!!!!!
if(event==ACT_NEXTSONDE) {
sonde.nextConfig();
Serial.printf("advancing to next sonde %d\n", sonde.currentSonde);
return event;
}
if (event==ACT_PREVSONDE) {
// TODO
Serial.printf("previous not supported, advancing to next sonde\n");
sonde.nextConfig();
return ACT_NEXTSONDE;
}
if(event&0x80) {
sonde.currentSonde = (event&0x7F);
return ACT_NEXTSONDE;
}
return 0xFF;
}
void Sonde::updateDisplayPos() {
char buf[16];
u8x8->setFont(u8x8_font_7x14_1x2_r);
if(si()->validPos) {
snprintf(buf, 16, "%2.5f", si()->lat);
u8x8->drawString(0,2,buf);
snprintf(buf, 16, "%2.5f", si()->lon);
u8x8->drawString(0,4,buf);
} else {
u8x8->drawString(0,2,"<??> ");
u8x8->drawString(0,4,"<??> ");
}
disp.updateDisplayPos();
}
void Sonde::updateDisplayPos2() {
char buf[16];
u8x8->setFont(u8x8_font_chroma48medium8_r);
if(!si()->validPos) {
u8x8->drawString(10,2," ");
u8x8->drawString(10,3," ");
u8x8->drawString(10,4," ");
return;
}
snprintf(buf, 16, si()->alt>999?" %5.0fm":" %3.1fm", si()->alt);
u8x8->drawString((10+6-strlen(buf)),2,buf);
snprintf(buf, 16, si()->hs>99?" %3.0f":" %2.1f", si()->hs);
u8x8->drawString((10+4-strlen(buf)),3,buf);
snprintf(buf, 16, " %+2.1f", si()->vs);
u8x8->drawString((10+4-strlen(buf)),4,buf);
u8x8->drawTile(14,3,2,kmh_tiles);
u8x8->drawTile(14,4,2,ms_tiles);
disp.updateDisplayPos2();
}
void Sonde::updateDisplayID() {
u8x8->setFont(u8x8_font_chroma48medium8_r);
if(si()->validID) {
u8x8->drawString(0,1, si()->id);
} else {
u8x8->drawString(0,1, "nnnnnnnn ");
}
disp.updateDisplayID();
}
void Sonde::updateDisplayRSSI() {
char buf[16];
u8x8->setFont(u8x8_font_7x14_1x2_r);
snprintf(buf, 16, "-%d ", sonde.si()->rssi/2);
int len=strlen(buf)-3;
buf[5]=0;
u8x8->drawString(0,6,buf);
u8x8->drawTile(len,6,1,(sonde.si()->rssi&1)?halfdb_tile1:empty_tile1);
u8x8->drawTile(len,7,1,(sonde.si()->rssi&1)?halfdb_tile2:empty_tile2);
disp.updateDisplayRSSI();
}
void Sonde::updateStat() {
uint8_t *stat = si()->rxStat;
for(int i=0; i<18; i+=2) {
uint8_t tile[8];
*(uint32_t *)(&tile[0]) = *(uint32_t *)(&(stattiles[stat[i]]));
*(uint32_t *)(&tile[4]) = *(uint32_t *)(&(stattiles[stat[i+1]]));
u8x8->drawTile(7+i/2, 6, 1, tile);
}
disp.updateStat();
}
void Sonde::updateDisplayRXConfig() {
char buf[16];
u8x8->setFont(u8x8_font_chroma48medium8_r);
u8x8->drawString(0,0, sondeTypeStr[si()->type]);
snprintf(buf, 16, "%3.3f MHz", si()->freq);
u8x8->drawString(5,0, buf);
if(config.showafc) {
snprintf(buf, 15, " %+3.2fk", si()->afc*0.001);
u8x8->drawString(8,1,buf+strlen(buf)-8);
}
//snprintf(buf, 8, "%s", si()->launchsite);
//u8x8->drawString(0,5, buf);
disp.updateDisplayRXConfig();
}
void Sonde::updateDisplayIP() {
u8x8->drawTile(5, 7, 11, myIP_tiles);
disp.updateDisplayIP();
}
// Probing RS41
// 40x.xxx MHz
void Sonde::updateDisplayScanner() {
char buf[16];
u8x8->setFont(u8x8_font_7x14_1x2_r);
u8x8->drawString(0, 0, "Scan:");
u8x8->drawString(8, 0, sondeTypeStr[si()->type]);
snprintf(buf, 16, "%3.3f MHz", si()->freq);
u8x8->drawString(0,3, buf);
snprintf(buf, 16, "%s", si()->launchsite);
u8x8->drawString(0,5, buf);
updateDisplayIP();
disp.setLayout(0);
disp.updateDisplay();
disp.setLayout(config.display);
}
void Sonde::updateDisplay()
{
char buf[16];
updateDisplayRXConfig();
updateDisplayID();
updateDisplayPos();
updateDisplayPos2();
updateDisplayRSSI();
updateStat();
updateDisplayIP();
disp.updateDisplay();
}
void Sonde::clearDisplay() {

Wyświetl plik

@ -1,31 +1,99 @@
#ifndef Sonde_h
#define Sonde_H
#define Sonde_h
#include "aprs.h"
// RX_TIMEOUT: no header detected
// RX_ERROR: header detected, but data not decoded (crc error, etc.)
// RX_OK: header and data ok
enum RxResult { RX_OK, RX_TIMEOUT, RX_ERROR, RX_UNKNOWN };
enum RxResult { RX_OK, RX_TIMEOUT, RX_ERROR, RX_UNKNOWN, RX_NOPOS };
#define RX_UPDATERSSI 0xFFFE
enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41 };
// Events that change what is displayed (mode, sondenr)
// Keys:
// 1 Button (short) or Touch (short)
// 2 Button (double) or Touch (double)
// 3 Button (mid) or Touch (mid)
// 4 Button (long) or Touch (long)
// 5 Touch1/2 (short)
// 6 Touch1/2 (double)
// 7 Touch1/2 (mid)
// 8 Touch1/2 (long)
/* Keypress => Sonde++ / Sonde-- / Display:=N*/
enum Events { EVT_NONE, EVT_KEY1SHORT, EVT_KEY1DOUBLE, EVT_KEY1MID, EVT_KEY1LONG,
EVT_KEY2SHORT, EVT_KEY2DOUBLE, EVT_KEY2MID, EVT_KEY2LONG,
EVT_VIEWTO, EVT_RXTO, EVT_NORXTO,
EVT_MAX };
extern const char *evstring[];
extern const char *RXstr[];
#define EVENTNAME(s) evstring[s]
//int8_t actions[EVT_MAX];
#define ACT_NONE 255
#define ACT_DISPLAY(n) (n)
#define ACT_DISPLAY_DEFAULT 63
#define ACT_DISPLAY_SPECTRUM 62
#define ACT_DISPLAY_WIFI 61
#define ACT_NEXTSONDE 65
#define ACT_PREVSONDE 66
#define ACT_SONDE(n) ((n)+128)
// 0000nnnn => goto display nnnn
// 01000000 => goto sonde -1
// 01000001 => goto sonde +1
enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41, STYPE_RS92 };
extern const char *sondeTypeStr[5];
// Used for interacting with the RX background task
typedef struct st_RXTask {
// Variables set by Arduino main loop to value >=0 for requesting
// mode change to sonde reception for sonde <value) in RXTask.
// Will be reset to -1 by RXTask
int activate;
// Variables set by RXTask, corresponding to mode ST_DECODER (if active) or something else,
// and currently received sonde
int mainState;
int currentSonde;
// Variable set by RXTask to communicate status to Arduino task
// via waitRXcomplete function
uint16_t receiveResult;
uint16_t receiveSonde; // sonde inde corresponding to receiveResult
// status variabe set by decoder to indicate something is broken
// int fifoOverflow;
} RXTask;
extern RXTask rxtask;
struct st_rs41config {
int agcbw;
int rxbw;
};
struct st_rs92config {
int rxbw;
int alt2d;
};
struct st_dfmconfig {
int agcbw;
int rxbw;
};
typedef struct st_rdzconfig {
int button_pin; // PIN port number menu button (for some boards)
int button_pin; // PIN port number menu button (+128 for touch mode)
int button2_pin; // PIN port number menu button (+128 for touch mode)
int touch_thresh; // Threshold value (0..100) for touch input button
int led_pout; // POUT port number of LED (used as serial monitor)
int oled_sda; // OLED data pin
int oled_scl; // OLED clock pin
int oled_rst; // OLED reset pin
int gps_rxd; // GPS module RXD pin. We expect 9600 baud NMEA data.
int gps_txd; // GPS module TXD pin
int debug; // show port and config options after reboot
int wifi; // connect to known WLAN 0=skip
int wifiap; // enable/disable WiFi AccessPoint mode 0=disable
int display; // select display mode (0=default, 1=default, 2=fieldmode)
int startfreq; // spectrum display start freq (400, 401, ...)
int channelbw; // spectrum channel bandwidth (valid: 5, 10, 20, 25, 50, 100 kHz)
int spectrum; // show freq spectrum for n seconds 0=disable
@ -39,6 +107,8 @@ typedef struct st_rdzconfig {
char call[9]; // APRS callsign
char passcode[9]; // APRS passcode
struct st_rs41config rs41; // configuration options specific for RS41 receiver
struct st_rs92config rs92;
struct st_dfmconfig dfm;
// for now, one feed for each type is enough, but might get extended to more?
struct st_feedinfo udpfeed; // target for AXUDP messages
struct st_feedinfo tcpfeed; // target for APRS-IS TCP connections
@ -46,7 +116,7 @@ typedef struct st_rdzconfig {
typedef struct st_sondeinfo {
// receiver configuration
bool active;
bool active;
SondeType type;
float freq;
// decoded ID
@ -59,14 +129,19 @@ typedef struct st_sondeinfo {
float alt; // altitude
float vs; // vertical speed
float hs; // horizontal speed
float dir; // 0..360
float dir; // 0..360
uint8_t validPos; // bit pattern for validity of above 6 fields
// RSSI from receiver
int rssi; // signal strength
int32_t afc; // afc correction value
// statistics
uint8_t rxStat[20];
uint32_t rxStart; // millis() timestamp of continuous rx start
uint32_t norxStart; // millis() timestamp of continuous no rx start
uint32_t viewStart; // millis() timestamp of viewinf this sonde with current display
int8_t lastState; // -1: disabled; 0: norx; 1: rx
} SondeInfo;
// rxState: 0=undef[empty] 1=timeout[.] 2=errro[E] 3=ok[1]
// rxStat: 3=undef[empty] 1=timeout[.] 2=errro[E] 3=ok[1] 5=no valid position[°]
#define MAXSONDE 99
@ -78,7 +153,9 @@ public:
RDZConfig config;
int currentSonde = 0;
int nSonde;
SondeInfo sondeList[MAXSONDE+1];
// moved to heap, saving space in .bss
//SondeInfo sondeList[MAXSONDE+1];
SondeInfo *sondeList;
Sonde();
void setConfig(const char *str);
@ -86,11 +163,23 @@ public:
void clearSonde();
void addSonde(float frequency, SondeType type, int active, char *launchsite);
void nextConfig();
void setup();
void nextRxSonde();
/* new interface */
void setup();
void receive();
uint16_t waitRXcomplete();
/* old and temp interface */
#if 0
void processRXbyte(uint8_t data);
int receiveFrame();
#endif
SondeInfo *si();
uint8_t timeoutEvent(SondeInfo *si);
uint8_t updateState(uint8_t event);
void updateDisplayPos();
void updateDisplayPos2();
void updateDisplayID();

Wyświetl plik

@ -0,0 +1,43 @@
Heltec board
(sda,scl: 4,15) (same as LORA v1.0)
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:0 16:0 17:0 18:0 19:0 20:0 21:1 22:0 23:0 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
TTGO LORA32 v2.1_1.6 (button1: touch gpio 2 => 130; button2: touch gpio14 => 142)
(sda,scl: 21,22)
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:1 16:1 17:1 18:0 19:0 20:0 21:1 22:1 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
0:4 1:4 2:0 3:4 4:0 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:0 13:0 14:4 15:4 16:4 17:4 18:0 19:0 20:0 21:4 22:4 23:4 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (in Sonde())
TTGO LORA v1.0
(sda,scl: 4,15) (button1: 0) (button2: touch gpio13 = 141)
0:1 1:0 2:0 3:1 4:1 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:0 13:0 14:1 15:1 16:0 17:0 18:0 19:0 20:0 21:0 22:0 23:0 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
0:4 1:4 2:0 3:4 4:4 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:0 13:0 14:4 15:4 16:0 17:0 18:0 19:0 20:0 21:0 22:0 23:0 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (in Sonde())
TTGO T-Beam
(sda,scl: 21,22) (button1: 39) (button2: touch gpio13 = 141) (gps rx: 12)
0:1 1:0 2:0 3:1 4:0 5:1 6:0 7:1 8:0 9:1 10:1 11:1 12:1 13:0 14:1 15:1 16:1 17:0 18:0 19:0 20:0 21:1 22:1 23:1 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0
0:4 1:4 2:0 3:4 4:0 5:4 6:0 7:4 8:0 9:4 10:4 11:4 12:4 13:0 14:4 15:4 16:4 17:0 18:0 19:0 20:0 21:4 22:4 23:4 24:0 25:0 26:0 27:0 28:0 29:0 30:0 31:0 32:0 33:0 34:0 35:0 36:0 37:0 38:0 (before setup)
Current autodetect strategy:
RST always set to 16
GPIO16=0 (GPio22,23 would also work):
==Heltec or TTGO LORA v1.0==
SDA,SCL set to (4,15)
Button 1 set to GPIO 0
Button 2 set to Touch in GPIO 13 (141)
otherwise
==LORA32 v2.1 or T-Beam==
SDA,SCL set to (21,22)
GPIO17=0:
== T-BEAM =
GPS RX set to 12
Button 1 set to GPIO39
Button 2 set to Touch GPIO13 (141)
otherweise:
GPS disabled
Button 1 set to Touch GPIO2 (130)
Button 2 set to Touch GPIO14 (142)

Wyświetl plik

@ -0,0 +1,226 @@
#include "time.h"
#include "geteph.h"
#include <SPIFFS.h>
#include <WiFi.h>
#include <rom/miniz.h>
#include <inttypes.h>
#include <WiFi.h>
#include <U8x8lib.h>
extern U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8;
extern WiFiClient client;
static const char *ftpserver = "www.ngs.noaa.gov";
char outbuf[128];
uint8_t getreply() {
String s = client.readStringUntil('\n');
Serial.println(s);
const char *str = s.c_str();
if(strlen(str)<4) return 255; // something unusual...
if(str[3]=='-') { // multi-line resonse...
String s2;
const char *str2;
do {
s2 = client.readStringUntil('\n');
Serial.println(s2);
str2 = s2.c_str();
if(strlen(str2)<4) return 255; // something is wrong
} while( str[0]!=str2[0] || str[1]!=str2[1] || str[2]!=str2[2] || str2[3]!=' ' );
}
return str[0];
}
void writeFully(File &file, uint8_t *buf, size_t len)
{
size_t olen;
while(len) {
olen = file.write(buf, len);
Serial.printf("written: %d of %d\n", olen, len);
len -= olen;
buf += olen;
}
}
void geteph() {
// Set current time via network...
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) {
Serial.println("Failed to get current date/time");
return;
}
// Check time of last update
int year = tinfo.tm_year + 1900;
int day = tinfo.tm_yday + 1;
Serial.printf("year %d, day %d\n", year, day);
char nowstr[20];
snprintf(nowstr, 20, "%04d%03d%02d", year, day, tinfo.tm_hour);
File status = SPIFFS.open("/brdc.time", "r");
if(status) {
String ts = status.readStringUntil('\n');
const char *tsstr = ts.c_str();
if(tsstr && strlen(tsstr)>=9) {
if(strcmp(nowstr, ts.c_str())<=0) {
Serial.println("local brdc is up to date\n");
return;
}
}
Serial.printf("now: %s, existing: %s => updating\n", nowstr, tsstr);
}
status.close();
u8x8->clear();
u8x8->setFont(u8x8_font_chroma48medium8_r);
u8x8->drawString(0, 0, "FTP ngs.noaa.gov");
// fetch rinex from server
File fh = SPIFFS.open("/brdc.gz","w");
if(!fh) {
Serial.println("cannot open file\n");
return;
}
char buf[252];
snprintf(buf, 128, "/cors/rinex/%04d/%03d/brdc%03d0.%02dn.gz", year, day, day, year-2000);
Serial.println("running geteph\n");
u8x8->drawString(0, 1, buf+21);
if(!client.connect(ftpserver, 21)) {
Serial.println("FTP connection to www.ngs.noaa.gov failed");
return;
}
#if 0
while(!client.available()) delay(1);
while(client.available()) {
String s = client.readStringUntil('\n');
Serial.println(s);
}
#endif
if(getreply()>='4') { Serial.println("connected failed"); return; }
client.print("USER anonymous\r\n");
if(getreply()>='4') { Serial.println("USER failed"); return; }
client.print("PASS anonymous\r\n");
if(getreply()>='4') { Serial.println("PASS failed"); return; }
client.print("TYPE I\r\n");
if(getreply()>='4') { Serial.println("TYPE I failed"); return; }
client.print("PASV\r\n");
String s = client.readStringUntil('\n');
Serial.println(s);
if(s.c_str()[0]>='4') { Serial.println("PASV failed"); return; }
int array_pasv[6];
char *tStr = strtok((char *)s.c_str(), "(,");
for(int i=0; i<6; i++) {
tStr = strtok(NULL, "(,");
if(tStr==NULL) {
Serial.println("strange response to PASV");
return;
}
array_pasv[i] = atoi(tStr);
Serial.println(array_pasv[i]);
}
uint16_t port = (array_pasv[4]<<8) | (array_pasv[5]&0xff);
WiFiClient dclient;
Serial.printf("connecting to %s:%d\n", ftpserver,port);
dclient.connect(ftpserver, port);
if(!dclient) {
Serial.println("data connection failed");
return;
}
client.print("RETR ");
Serial.printf("fetching %s with FTP...\n", buf);
client.println(buf);
s = client.readStringUntil('\n');
Serial.println(s);
if(s.c_str()[0]>='4') { Serial.println("RETR failed"); return; }
int len=0;
while(dclient.connected()) {
while(dclient.available()) {
char c = dclient.read();
fh.write(c);
len++;
}
}
Serial.printf("fetched %d bytes\n", len);
fh.close();
snprintf(buf, 16, "Fetched %d B ",len);
buf[16]=0;
u8x8->drawString(0,2,buf);
u8x8->drawString(0,4,"Decompressing...");
// decompression
tinfl_decompressor *decomp = (tinfl_decompressor *)malloc(sizeof(tinfl_decompressor));
tinfl_init(decomp);
File file = SPIFFS.open("/brdc.gz","r");
if(!file) {
Serial.println("cannot open file\n");
return;
}
File ofile = SPIFFS.open("/brdc", "w");
if(!ofile) {
Serial.println("cannot open file /brdc for writing");
return;
}
file.readBytes(buf, 10); // skip gzip header
char flags = buf[3];
if(flags&0x07) {
Serial.println("Unsupported flags in gzip header, may or may not cause a problem");
}
if(flags&0x08) { // skip file name extra header
do {
int res=file.readBytes(buf, 1);
if(res!=1) return;
} while(*buf);
}
if(flags&0x10) { // skip file name extra header
do {
int res=file.readBytes(buf, 1);
if(res!=1) return;
} while(*buf);
}
int opos = 0;
int total = 0;
Serial.println("Decompressing ephemeris data...\n");
char *obuf =(char *)malloc(32768);
char *ibuf =(char *)malloc(8192);
while(file.available()) {
size_t len = file.readBytes(ibuf, 8192);
size_t inofs = 0;
size_t inlen = len;
while(inofs<len) {
size_t outlen=32768-opos;
int res = tinfl_decompress(decomp, (const mz_uint8 *)ibuf+inofs, &inlen, (uint8_t *)obuf, (mz_uint8 *)obuf+opos, &outlen, TINFL_FLAG_HAS_MORE_INPUT);
if(res<0) break;
if(outlen==0) break;
Serial.printf("... (res=%d) decompressed %d into %d bytes\n", res, inlen, outlen);
inofs += inlen;
inlen = len - inofs;
//size_t retv = ofile.write((uint8_t *)(obuf+opos), outlen);
//Serial.printf("write %d bytes\n", retv);
writeFully(ofile, (uint8_t *)(obuf+opos), outlen);
//Serial.write((uint8_t *)(obuf+opos), outlen);
total += outlen;
opos += outlen;
if(res==0) break; // done indication
if(opos>=32768) {
Serial.printf("... decompressed %d bytes\n", total);
opos=0;
}
}
}
// maybe todo: check crc?!?
Serial.printf("done extracing content (total length: %d)\n", total);
status = SPIFFS.open("/brdc.time","w");
status.println(nowstr);
status.close();
snprintf(buf, 16, "Done: %d B ",total);
buf[16]=0;
u8x8->drawString(0,5,buf);
delay(1000);
free(obuf);
free(ibuf);
free(decomp);
file.close();
ofile.close();
}

Wyświetl plik

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

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,148 @@
typedef struct {
uint16_t prn;
uint16_t week;
uint32_t toa;
char epoch[20];
double toe;
double toc;
double e;
double delta_n;
double delta_i;
double i0;
double OmegaDot;
double sqrta;
double Omega0;
double w;
double M0;
double tgd;
double idot;
double cuc;
double cus;
double crc;
double crs;
double cic;
double cis;
double af0;
double af1;
double af2;
int gpsweek;
uint16_t svn;
uint8_t ura;
uint8_t health;
uint8_t conf;
} EPHEM_t;
typedef struct {
uint32_t t;
double pseudorange;
double pseudorate;
double clock_corr;
double clock_drift;
double X;
double Y;
double Z;
double vX;
double vY;
double vZ;
int ephhr;
double PR;
double ephtime;
int prn;
} SAT_t;
typedef struct {double X; double Y; double Z;} LOC_t;
typedef struct {double X; double Y; double Z;
double vX; double vY; double vZ;} VEL_t;
double dist(double X1, double Y1, double Z1, double X2, double Y2, double Z2);
void GPS_SatelliteClockCorrection(
const unsigned short transmission_gpsweek, // GPS week when signal was transmit (0-1024+) [weeks]
const double transmission_gpstow, // GPS time of week when signal was transmit [s]
const unsigned short ephem_week, // ephemeris: GPS week (0-1024+) [weeks]
const double toe, // ephemeris: time of week [s]
const double toc, // ephemeris: clock reference time of week [s]
const double af0, // ephemeris: polynomial clock correction coefficient [s],
const double af1, // ephemeris: polynomial clock correction coefficient [s/s],
const double af2, // ephemeris: polynomial clock correction coefficient [s/s^2]
const double ecc, // ephemeris: eccentricity of satellite orbit []
const double sqrta, // ephemeris: square root of the semi-major axis of orbit [m^(1/2)]
const double delta_n, // ephemeris: mean motion difference from computed value [rad]
const double m0, // ephemeris: mean anomaly at reference time [rad]
const double tgd, // ephemeris: group delay differential between L1 and L2 [s]
double* clock_correction );
void GPS_SatellitePosition_Ephem(
const unsigned short gpsweek, // gps week of signal transmission (0-1024+) [week]
const double gpstow, // time of week of signal transmission (gpstow-psr/c) [s]
EPHEM_t ephem,
double* clock_correction, // clock correction for this satellite for this epoch [m]
double* satX, // satellite X position WGS84 ECEF [m]
double* satY, // satellite Y position WGS84 ECEF [m]
double* satZ // satellite Z position WGS84 ECEF [m]
);
void GPS_SatelliteClockDriftCorrection(
const unsigned short transmission_gpsweek, // GPS week when signal was transmit (0-1024+) [weeks]
const double transmission_gpstow, // GPS time of week when signal was transmit [s]
const unsigned short ephem_week, // ephemeris: GPS week (0-1024+) [weeks]
const double toe, // ephemeris: time of week [s]
const double toc, // ephemeris: clock reference time of week [s]
const double af0, // ephemeris: polynomial clock correction coefficient [s],
const double af1, // ephemeris: polynomial clock correction coefficient [s/s],
const double af2, // ephemeris: polynomial clock correction coefficient [s/s^2]
const double ecc, // ephemeris: eccentricity of satellite orbit []
const double sqrta, // ephemeris: square root of the semi-major axis of orbit [m^(1/2)]
const double delta_n, // ephemeris: mean motion difference from computed value [rad]
const double m0, // ephemeris: mean anomaly at reference time [rad]
const double tgd, // ephemeris: group delay differential between L1 and L2 [s]
double* clock_correction, // ephemeris: satellite clock correction [m]
double* clock_drift ) ;
void GPS_SatellitePositionVelocity_Ephem(
const unsigned short gpsweek, // gps week of signal transmission (0-1024+) [week]
const double gpstow, // time of week of signal transmission (gpstow-psr/c) [s]
EPHEM_t ephem,
double* clock_correction, // clock correction for this satellite for this epoch [m]
double* clock_drift, // clock correction for this satellite for this epoch [m]
double* satX, // satellite X position WGS84 ECEF [m]
double* satY, // satellite Y position WGS84 ECEF [m]
double* satZ, // satellite Z position WGS84 ECEF [m]
double* satvX, // satellite X velocity WGS84 ECEF [m]
double* satvY, // satellite Y velocity WGS84 ECEF [m]
double* satvZ // satellite Z velocity WGS84 ECEF [m]
);
int NAV_ClosedFormSolution_FromPseudorange(
SAT_t sats[4], // input: satellite position and pseudorange
double* latitude, // output: ellipsoid latitude [rad]
double* longitude, // ellipsoid longitude [rad]
double* height, // ellipsoid height [m]
double* rx_clock_bias, // receiver clock bias [m]
double pos_ecef[3] );
int calc_DOPn(int n, SAT_t satss[], double pos_ecef[3], double DOP[4]);
int NAV_LinP(int N, SAT_t satv[], double pos_ecef[3], double dt,
double dpos_ecef[3], double *cc);
void ecef2elli(double X, double Y, double Z, double *lat, double *lon, double *alt);
int NAV_LinP(int N, SAT_t satv[], double pos_ecef[3], double dt,
double dpos_ecef[3], double *cc);
int NAV_LinV(int N, SAT_t satv[], double pos_ecef[3],
double vel_ecef[3], double dt,
double dvel_ecef[3], double *cc);
int NAV_bancroft1(int N, SAT_t sats[], double pos_ecef[3], double *cc);
EPHEM_t *read_RNXpephs(const char *file);

Plik diff jest za duży Load Diff

Wyświetl plik

@ -0,0 +1,21 @@
typedef struct {
int frnr;
char id[11];
int week; int gpssec;
int jahr; int monat; int tag;
int wday;
int std; int min; float sek;
double lat; double lon; double alt;
double vH; double vD; double vU;
int sats[4];
double dop;
int freq;
unsigned short aux[4];
double diter;
} gpx_t;
extern gpx_t gpx;
void print_frame(uint8_t *data, int len);
void get_eph(const char *file);