kopia lustrzana https://github.com/dl9rdz/rdz_ttgo_sonde
Several updates for testing before next master release
- RS92 should now work fine, inluding some fixes to the ephemeris download, and including information about download - Download only started if there is some RS92 in the qrg.txt configuration - Some enhancements to new internal structure (separate RX Task for handling the SX1278), should now work as good as before the reorganisation :-) - Avoid key glitch after startup on T-BEAM (triggering double wifi scan) - GPS playground (for T-Beam or external GPS connected to board)...ims100
rodzic
7fb4b8f999
commit
0556d67fa0
|
@ -7,6 +7,8 @@
|
|||
#include <SPI.h>
|
||||
#include <Update.h>
|
||||
#include <ESPmDNS.h>
|
||||
#include <MicroNMEA.h>
|
||||
#include <Ticker.h>
|
||||
|
||||
#include <SX1278FSK.h>
|
||||
#include <Sonde.h>
|
||||
|
@ -31,7 +33,7 @@ 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";
|
||||
|
@ -46,16 +48,17 @@ 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 keydowTime;
|
||||
bool doublepress;
|
||||
unsigned long keydownTime;
|
||||
int8_t doublepress;
|
||||
bool isTouched;
|
||||
};
|
||||
Button button1 = {0, 0, KP_NONE, 0, false, false};
|
||||
Button button2 = {0, 0, KP_NONE, 0, false, false};
|
||||
Button button1 = {0, 0, KP_NONE, 0, -1, false};
|
||||
Button button2 = {0, 0, KP_NONE, 0, -1, false};
|
||||
|
||||
|
||||
static int lastDisplay = 1;
|
||||
|
@ -424,6 +427,8 @@ struct st_configitems config_list[] = {
|
|||
{"button2_pin", "Button 2 input port (needs reboot)", 0, &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));
|
||||
|
||||
|
@ -590,7 +595,7 @@ const char *createEditForm(String filename) {
|
|||
String line = file.readStringUntil('\n');
|
||||
strcat(ptr, line.c_str()); strcat(ptr, "\n");
|
||||
}
|
||||
strcat(ptr, "</textarea><input type=\"submit\">Save</input></form></body></html>");
|
||||
strcat(ptr, "</textarea><input type=\"submit\" value=\"Save\"></input></form></body></html>");
|
||||
return message;
|
||||
}
|
||||
|
||||
|
@ -770,7 +775,7 @@ const char *fetchWifiPw(const char *id) {
|
|||
}
|
||||
|
||||
// It is not safe to call millis() in ISR!!!
|
||||
// millis() does a division int16_t by 1000 for which gcc creates a library call
|
||||
// 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
|
||||
|
@ -808,14 +813,23 @@ void touchISR2();
|
|||
///// 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 buttongs configured
|
||||
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);
|
||||
|
||||
hw_timer_t *timer = timerBegin(0, 80, true);
|
||||
timerAttachInterrupt(timer, checkTouchStatus, true);
|
||||
timerAlarmWrite(timer, 300000, true);
|
||||
timerAlarmEnable(timer);
|
||||
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);
|
||||
|
@ -826,6 +840,40 @@ void initTouch() {
|
|||
}
|
||||
}
|
||||
|
||||
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.
|
||||
|
@ -833,36 +881,32 @@ void sx1278Task(void *parameter) {
|
|||
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
|
||||
(2) set an output flag (success/errors/timeout-norx)
|
||||
(3) return to this task look after about 1s or if some extern trigger (key) is detected
|
||||
(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)
|
||||
|
||||
*/
|
||||
Serial.printf("rx task: activate=%d mainstate=%d\n", rxtask.activate, rxtask.mainState);
|
||||
while (1) {
|
||||
boolean resetup = false;
|
||||
// RX task state update. Check rxtask.activate and rxtask.requestSonde
|
||||
if (rxtask.activate >= 0) {
|
||||
Serial.printf("rx task: activate=%d requestsonde=%d mainstate=%d\n", rxtask.activate, rxtask.requestSonde, rxtask.mainState);
|
||||
rxtask.mainState = rxtask.activate;
|
||||
rxtask.activate = -1;
|
||||
resetup = true;
|
||||
}
|
||||
if (rxtask.requestSonde >= 0) {
|
||||
Serial.printf("rx task: activate=%d requestsonde=%d mainstate=%d\n", rxtask.activate, rxtask.requestSonde, rxtask.mainState);
|
||||
resetup = true;
|
||||
rxtask.currentSonde = rxtask.requestSonde;
|
||||
rxtask.requestSonde = -1;
|
||||
if (rxtask.activate >= 128) {
|
||||
// activating sx1278 background task...
|
||||
rxtask.mainState = ST_DECODER;
|
||||
rxtask.currentSonde = rxtask.activate & 0x7F;
|
||||
Serial.println("rx task: calling sonde.setup()");
|
||||
sonde.setup();
|
||||
}
|
||||
rxtask.activate = -1;
|
||||
/* only if mainState is ST_DECODER */
|
||||
if (rxtask.mainState != ST_DECODER) {
|
||||
delay(100);
|
||||
continue;
|
||||
}
|
||||
#if 0
|
||||
if (resetup) {
|
||||
Serial.println("rx task: calling sonde.setup()");
|
||||
resetup = false;
|
||||
sonde.setup();
|
||||
}
|
||||
//Serial.println("rx task: calling sonde.receive()");
|
||||
#endif
|
||||
sonde.receive();
|
||||
delay(20);
|
||||
}
|
||||
|
@ -872,9 +916,9 @@ void sx1278Task(void *parameter) {
|
|||
void IRAM_ATTR touchISR() {
|
||||
if (!button1.isTouched) {
|
||||
unsigned long now = my_millis();
|
||||
if (now - button1.keydowTime < 500) button1.doublepress = true;
|
||||
else button1.doublepress = false;
|
||||
button1.keydowTime = now;
|
||||
if (now - button1.keydownTime < 500) button1.doublepress = 1;
|
||||
else button1.doublepress = 0;
|
||||
button1.keydownTime = now;
|
||||
button1.isTouched = true;
|
||||
}
|
||||
}
|
||||
|
@ -882,19 +926,20 @@ void IRAM_ATTR touchISR() {
|
|||
void IRAM_ATTR touchISR2() {
|
||||
if (!button2.isTouched) {
|
||||
unsigned long now = my_millis();
|
||||
if (now - button2.keydowTime < 500) button2.doublepress = true;
|
||||
else button2.doublepress = false;
|
||||
button2.keydowTime = now;
|
||||
if (now - button2.keydownTime < 500) button2.doublepress = 1;
|
||||
else button2.doublepress = 0;
|
||||
button2.keydownTime = now;
|
||||
button2.isTouched = true;
|
||||
}
|
||||
}
|
||||
|
||||
void IRAM_ATTR checkTouchButton(Button &button) {
|
||||
// TODO: touchRead in ISR is also a bad idea.
|
||||
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.keydowTime;
|
||||
unsigned long elapsed = my_millis() - button.keydownTime;
|
||||
if (elapsed > 1500) {
|
||||
if (elapsed < 4000) {
|
||||
button.pressed = KP_MID;
|
||||
|
@ -911,7 +956,7 @@ void IRAM_ATTR checkTouchButton(Button &button) {
|
|||
}
|
||||
}
|
||||
|
||||
void IRAM_ATTR checkTouchStatus() {
|
||||
void checkTouchStatus() {
|
||||
checkTouchButton(button1);
|
||||
checkTouchButton(button2);
|
||||
}
|
||||
|
@ -920,15 +965,16 @@ void IRAM_ATTR checkTouchStatus() {
|
|||
void IRAM_ATTR buttonISR() {
|
||||
unsigned long now = my_millis();
|
||||
if (digitalRead(button1.pin) == 0) { // Button down
|
||||
if (now - button1.keydowTime < 500) {
|
||||
if (now - button1.keydownTime < 500) {
|
||||
// Double press
|
||||
button1.doublepress = true;
|
||||
button1.doublepress = 1;
|
||||
} else {
|
||||
button1.doublepress = false;
|
||||
button1.doublepress = 0;
|
||||
}
|
||||
button1.keydowTime = now;
|
||||
button1.keydownTime = now;
|
||||
} else { //Button up
|
||||
unsigned int elapsed = now - button1.keydowTime;
|
||||
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;
|
||||
|
@ -941,21 +987,22 @@ void IRAM_ATTR buttonISR() {
|
|||
else button1.pressed = KP_SHORT;
|
||||
}
|
||||
button1.numberKeyPresses += 1;
|
||||
button1.keydowTime = now;
|
||||
button1.keydownTime = now;
|
||||
}
|
||||
}
|
||||
|
||||
int getKeyPress() {
|
||||
KeyPress p = button1.pressed;
|
||||
button1.pressed = KP_NONE;
|
||||
//Serial.printf("button1 press: %d at %ld (%d)\n", p, button1.keydowTime, button1.numberKeyPresses);
|
||||
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.keydowTime, button2.numberKeyPresses);
|
||||
Serial.printf("button2 press: %d at %ld (%d)\n", p, button2.keydownTime, button2.numberKeyPresses);
|
||||
return p;
|
||||
}
|
||||
int hasKeyPress() {
|
||||
|
@ -994,6 +1041,18 @@ 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
|
||||
|
@ -1013,12 +1072,6 @@ void setup()
|
|||
sonde.clearDisplay();
|
||||
|
||||
setupWifiList();
|
||||
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
|
||||
|
||||
// == show initial values from config.txt ========================= //
|
||||
if (sonde.config.debug == 1) {
|
||||
|
@ -1092,11 +1145,6 @@ void setup()
|
|||
// }
|
||||
// xTaskCreate(mainloop, "MainServer", 10240, NULL, 10, NULL);
|
||||
|
||||
// Handle button press
|
||||
if ( (button1.pin & 0x80) == 0) {
|
||||
attachInterrupt( button1.pin, buttonISR, CHANGE);
|
||||
Serial.printf("button1.pin is %d, attaching interrupt\n", button1.pin);
|
||||
}
|
||||
|
||||
// == setup default channel list if qrg.txt read fails =========== //
|
||||
setupChannelList();
|
||||
|
@ -1118,8 +1166,10 @@ void setup()
|
|||
1, /* priority */
|
||||
NULL); /* task handle*/
|
||||
sonde.setup();
|
||||
initGPS();
|
||||
|
||||
WiFi.onEvent(WiFiEvent);
|
||||
getKeyPress(); // clear key buffer
|
||||
}
|
||||
|
||||
void enterMode(int mode) {
|
||||
|
@ -1129,83 +1179,67 @@ void enterMode(int mode) {
|
|||
if (mode != ST_DECODER) {
|
||||
rxtask.activate = mode;
|
||||
while (rxtask.activate == mode) {
|
||||
delay(10); // until cleared by RXtask
|
||||
delay(10); // until cleared by RXtask -- rx task is deactivated
|
||||
}
|
||||
}
|
||||
mainState = (MainState)mode;
|
||||
if (mainState == ST_SPECTRUM) {
|
||||
Serial.println("Entering ST_SPECTRUM mode");
|
||||
sonde.clearDisplay();
|
||||
u8x8->setFont(u8x8_font_chroma48medium8_r);
|
||||
specTimer = millis();
|
||||
//scanner.init();
|
||||
} else {
|
||||
//sonde.clearDisplay();
|
||||
} else if (mainState == ST_WIFISCAN) {
|
||||
sonde.clearDisplay();
|
||||
}
|
||||
if (mode == ST_DECODER) {
|
||||
// trigger activation of background task
|
||||
// currentSonde should be set before enterMode()
|
||||
rxtask.requestSonde = sonde.currentSonde;
|
||||
rxtask.activate = mode;
|
||||
rxtask.activate = ACT_SONDE(sonde.currentSonde);
|
||||
sonde.clearDisplay();
|
||||
sonde.updateDisplay();
|
||||
}
|
||||
}
|
||||
|
||||
static char text[40];
|
||||
static const char *action2text(int action) {
|
||||
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";
|
||||
snprintf(text, 40, "Display=%d", action);
|
||||
if (action >= 128) {
|
||||
snprintf(text, 40, "Sonde=%d", action & 127);
|
||||
} else {
|
||||
snprintf(text, 40, "Display=%d", action);
|
||||
}
|
||||
return text;
|
||||
}
|
||||
void loopDecoder() {
|
||||
#if 0
|
||||
switch (getKeyPress()) {
|
||||
case KP_SHORT:
|
||||
sonde.nextConfig();
|
||||
sonde.updateDisplayRXConfig();
|
||||
sonde.updateDisplay();
|
||||
enterMode(ST_DECODER); // just to trigger rxtask reconfiguration
|
||||
break;
|
||||
case KP_DOUBLE:
|
||||
currentDisplay = 0;
|
||||
enterMode(ST_DECODER); // just to trigger rxtask reconfiguration
|
||||
return;
|
||||
case KP_MID:
|
||||
enterMode(ST_SPECTRUM);
|
||||
return;
|
||||
case KP_LONG:
|
||||
enterMode(ST_WIFISCAN);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
// sonde knows the current type and frequency, and delegates to the right decoder
|
||||
int res = sonde.waitRXcomplete();
|
||||
uint16_t res = sonde.waitRXcomplete();
|
||||
int action, event = 0;
|
||||
if ((res >> 8) == 0xFF) { // no implicit action returned from RXTask
|
||||
// Handle events that change display or sonde
|
||||
event = getKeyPressEvent();
|
||||
if (!event) event = sonde.timeoutEvent();
|
||||
// Check if there is an action for this event
|
||||
Serial.printf("Event: %d\n", event);
|
||||
action = disp.layout->actions[event];
|
||||
} else {
|
||||
action = res >> 8;
|
||||
action = (int)(int8_t)action;
|
||||
sonde.currentSonde = rxtask.currentSonde;
|
||||
}
|
||||
action = (int)(res >> 8);
|
||||
// TODO: update displayed sonde?
|
||||
|
||||
if (action >= 0) {
|
||||
Serial.printf("Loop: triggering action %s (%d) for event %s (%d)\n", action2text(action), action, EVENTNAME(event), event);
|
||||
Serial.printf("current main is %d, current rxtask is %d\n", sonde.currentSonde, rxtask.currentSonde);
|
||||
if (action != ACT_NONE) {
|
||||
Serial.printf("Loop: triggering action %s (%d)\n", action2text(action), action);
|
||||
action = sonde.updateState(action);
|
||||
if (action >= 0) {
|
||||
if (action == ACT_DISPLAY_SPECTRUM) enterMode(ST_SPECTRUM);
|
||||
else if (action == ACT_DISPLAY_WIFI) enterMode(ST_WIFISCAN);
|
||||
else if (action == ACT_NEXTSONDE) enterMode(ST_DECODER); // update rx background task
|
||||
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);
|
||||
}
|
||||
|
||||
|
||||
|
@ -1225,42 +1259,9 @@ void loopDecoder() {
|
|||
udp.endPacket();
|
||||
}
|
||||
}
|
||||
// Handle events (keypress and timeouts)
|
||||
sonde.updateDisplay();
|
||||
}
|
||||
|
||||
#if 0
|
||||
// now handled by loopDecoder in display mode 0
|
||||
#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;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
void loopSpectrum() {
|
||||
int marker = 0;
|
||||
|
@ -1273,6 +1274,7 @@ void loopSpectrum() {
|
|||
return;
|
||||
case KP_MID: /* restart, TODO */ break;
|
||||
case KP_LONG:
|
||||
Serial.println("loopSpectrum: KP_LONG");
|
||||
enterMode(ST_WIFISCAN);
|
||||
return;
|
||||
case KP_DOUBLE:
|
||||
|
@ -1652,8 +1654,14 @@ void loopWifiScan() {
|
|||
sonde.setIP(localIPstr.c_str(), false);
|
||||
sonde.updateDisplayIP();
|
||||
wifi_state = WIFI_CONNECTED;
|
||||
geteph();
|
||||
get_eph("/brdc");
|
||||
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);
|
||||
|
|
|
@ -1,2 +1,2 @@
|
|||
const char *version_name = "RDZ_TTGO_SONDE";
|
||||
const char *version_id = "devel20190602";
|
||||
const char *version_id = "devel20190608";
|
||||
|
|
1
Setup.md
1
Setup.md
|
@ -32,6 +32,7 @@ similar on other OS) and restart IDE
|
|||
Select Tools -> Library Manager
|
||||
|
||||
Install "U8g2"
|
||||
Install "MicroNMEA"
|
||||
|
||||
## Additional libraries, part 2
|
||||
|
||||
|
|
|
@ -1,11 +1,13 @@
|
|||
#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" };
|
||||
|
@ -50,6 +52,9 @@ static uint8_t halfdb_tile2[8]={0x00, 0x11, 0x02, 0x02, 0x02, 0x01, 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);
|
||||
|
||||
|
@ -68,7 +73,7 @@ DispEntry searchLayout[] = {
|
|||
{-1, -1, -1, NULL, NULL},
|
||||
};
|
||||
int16_t searchTimeouts[] = { -1, 0, 0 };
|
||||
int8_t searchActions[] = {
|
||||
uint8_t searchActions[] = {
|
||||
ACT_NONE,
|
||||
ACT_DISPLAY_DEFAULT, ACT_NONE, ACT_DISPLAY_SPECTRUM, ACT_DISPLAY_WIFI,
|
||||
ACT_NONE, ACT_NONE, ACT_NONE, ACT_NONE,
|
||||
|
@ -89,7 +94,7 @@ DispEntry legacyLayout[] = {
|
|||
{-1, -1, -1, NULL, NULL},
|
||||
};
|
||||
int16_t legacyTimeouts[] = { -1, -1, 20000 };
|
||||
int8_t legacyActions[] = {
|
||||
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,
|
||||
|
@ -105,10 +110,10 @@ DispEntry fieldLayout[] = {
|
|||
{-1, -1, -1, NULL, NULL},
|
||||
};
|
||||
int16_t fieldTimeouts[] = { -1, -1, -1 };
|
||||
int8_t fieldActions[] = {
|
||||
uint8_t fieldActions[] = {
|
||||
ACT_NONE,
|
||||
ACT_NEXTSONDE, ACT_DISPLAY(0), ACT_DISPLAY_SPECTRUM, ACT_DISPLAY_WIFI,
|
||||
ACT_DISPLAY(3), ACT_NONE, ACT_NONE, ACT_NONE,
|
||||
ACT_DISPLAY(4), ACT_NONE, ACT_NONE, ACT_NONE,
|
||||
ACT_NONE, ACT_NONE, ACT_NONE};
|
||||
DispEntry field2Layout[] = {
|
||||
{2, 0, FONT_LARGE, disp.drawLat, NULL},
|
||||
|
@ -122,17 +127,35 @@ DispEntry field2Layout[] = {
|
|||
{6, 7, 0, disp.drawQS, NULL},
|
||||
{-1, -1, -1, NULL, NULL},
|
||||
};
|
||||
int8_t field2Actions[] = {
|
||||
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[4] = {
|
||||
DispInfo layouts[5] = {
|
||||
{ searchLayout, searchActions, searchTimeouts },
|
||||
{ legacyLayout, legacyActions, legacyTimeouts },
|
||||
{ fieldLayout, fieldActions, fieldTimeouts },
|
||||
{ field2Layout, field2Actions, fieldTimeouts } };
|
||||
{ field2Layout, field2Actions, fieldTimeouts },
|
||||
{ gpsLayout, gpsActions, fieldTimeouts } };
|
||||
|
||||
char Display::buf[17];
|
||||
|
||||
|
@ -245,7 +268,85 @@ void Display::drawSite(DispEntry *de) {
|
|||
}
|
||||
void Display::drawTelemetry(DispEntry *de) {
|
||||
}
|
||||
void Display::drawGPSdist(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);
|
||||
|
|
|
@ -16,7 +16,7 @@ struct DispEntry {
|
|||
|
||||
struct DispInfo {
|
||||
DispEntry *de;
|
||||
int8_t *actions;
|
||||
uint8_t *actions;
|
||||
int16_t *timeouts;
|
||||
};
|
||||
|
||||
|
@ -43,7 +43,7 @@ public:
|
|||
static void drawIP(DispEntry *de);
|
||||
static void drawSite(DispEntry *de);
|
||||
static void drawTelemetry(DispEntry *de);
|
||||
static void drawGPSdist(DispEntry *de);
|
||||
static void drawGPS(DispEntry *de);
|
||||
static void drawText(DispEntry *de);
|
||||
void clearIP();
|
||||
void setIP(const char *ip, bool AP);
|
||||
|
|
|
@ -476,7 +476,6 @@ static uint8_t scramble[64] = {150U,131U,62U,81U,177U,73U,8U,152U,50U,5U,89U,
|
|||
int RS41::receive() {
|
||||
sx1278.setPayloadLength(RS41MAXLEN-8);
|
||||
int e = sx1278.receivePacketTimeout(1000, data+8);
|
||||
rxtask.lastSonde = rxtask.currentSonde;
|
||||
if(e) { Serial.println("TIMEOUT"); return RX_TIMEOUT; }
|
||||
|
||||
for(int i=0; i<RS41MAXLEN; i++) { data[i] = reverse(data[i]); }
|
||||
|
|
|
@ -613,7 +613,7 @@ int RS92::waitRXcomplete() {
|
|||
Serial.printf("decoding frame %d\n", lastFrame);
|
||||
print_frame(lastFrame==1?data1:data2, 240);
|
||||
|
||||
SondeInfo *si = sonde.sondeList+sonde.currentSonde;
|
||||
SondeInfo *si = sonde.sondeList+rxtask.receiveSonde;
|
||||
si->lat = gpx.lat;
|
||||
si->lon = gpx.lon;
|
||||
si->alt = gpx.alt;
|
||||
|
|
|
@ -11,13 +11,15 @@
|
|||
extern U8X8_SSD1306_128X64_NONAME_SW_I2C *u8x8;
|
||||
extern SX1278FSK sx1278;
|
||||
|
||||
RXTask rxtask = { -1, -1, -1, -1, -1, 0 };
|
||||
RXTask rxtask = { -1, -1, -1, 0xFFFF, 0 };
|
||||
|
||||
const char *evstring[]={"NONE", "KEY1S", "KEY1D", "KEY1M", "KEY1L", "KEY2S", "KEY2D", "KEY2M", "KEY2L",
|
||||
"VIEWTO", "RXTO", "NORXTO", "(max)"};
|
||||
|
||||
const char *RXstr[]={"RX_OK", "RX_TIMEOUT", "RX_ERROR", "RX_UNKNOWN"};
|
||||
|
||||
int getKeyPressEvent(); /* in RX_FSK.ino */
|
||||
|
||||
/* Task model:
|
||||
* There is a background task for all SX1278 interaction.
|
||||
* - On startup and on each mode/frequency change (requested by setting requestNextSonde
|
||||
|
@ -52,6 +54,8 @@ Sonde::Sonde() {
|
|||
}
|
||||
//
|
||||
config.oled_rst = 16;
|
||||
config.gps_rxd = -1;
|
||||
config.gps_txd = -1;
|
||||
config.noisefloor = -125;
|
||||
strcpy(config.call,"NOCALL");
|
||||
strcpy(config.passcode, "---");
|
||||
|
@ -119,6 +123,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;
|
||||
|
@ -248,9 +256,6 @@ void Sonde::setup() {
|
|||
Serial.println(rxtask.currentSonde);
|
||||
rxtask.currentSonde = 0;
|
||||
}
|
||||
// TODO: maybe better done in arduino task, not in rx task
|
||||
sondeList[rxtask.currentSonde].lastState = -1;
|
||||
sondeList[rxtask.currentSonde].viewStart = millis();
|
||||
|
||||
// update receiver config
|
||||
Serial.print("\nSonde::setup() on sonde index ");
|
||||
|
@ -300,20 +305,27 @@ void Sonde::receive() {
|
|||
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
|
||||
int event = timeoutEvent();
|
||||
int action = disp.layout->actions[event];
|
||||
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();
|
||||
rxtask.requestSonde = rxtask.currentSonde;
|
||||
res = 0xFF00 | res;
|
||||
} else {
|
||||
res = (action<<8) | res;
|
||||
action = ACT_SONDE(rxtask.currentSonde);
|
||||
rxtask.activate = action;
|
||||
}
|
||||
res = (action<<8) | (res&0xff);
|
||||
Serial.printf("receive Result is %04x\n", res);
|
||||
// let waitRXcomplete resume...
|
||||
rxtask.receiveResult = res;
|
||||
}
|
||||
|
@ -337,7 +349,8 @@ rxloop:
|
|||
res = rxtask.receiveResult;
|
||||
}
|
||||
rxtask.receiveResult = 0xFFFF;
|
||||
Serial.printf("waitRXcomplete returning %04x (%s)\n", res, RXstr[res&0xff]);
|
||||
/// 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) {
|
||||
|
@ -357,33 +370,61 @@ rxloop:
|
|||
return res;
|
||||
}
|
||||
|
||||
uint8_t Sonde::timeoutEvent() {
|
||||
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, sonde.si()->viewStart, disp.layout->timeouts[0],
|
||||
now, sonde.si()->rxStart, disp.layout->timeouts[1],
|
||||
now, sonde.si()->norxStart, disp.layout->timeouts[2]);
|
||||
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", sonde.si()->lastState);
|
||||
if(disp.layout->timeouts[0]>=0 && now - sonde.si()->viewStart >= disp.layout->timeouts[0]) {
|
||||
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(sonde.si()->lastState==1 && disp.layout->timeouts[1]>=0 && now - sonde.si()->rxStart >= disp.layout->timeouts[1]) {
|
||||
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(sonde.si()->lastState==0 && disp.layout->timeouts[2]>=0 && now - sonde.si()->norxStart >= disp.layout->timeouts[2]) {
|
||||
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;
|
||||
}
|
||||
|
||||
int Sonde::updateState(int8_t event) {
|
||||
uint8_t Sonde::updateState(uint8_t event) {
|
||||
Serial.printf("Sonde::updateState for event %d\n", event);
|
||||
if(event==ACT_NONE) return -1;
|
||||
// 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);
|
||||
|
@ -395,20 +436,11 @@ int Sonde::updateState(int8_t event) {
|
|||
sonde.nextConfig();
|
||||
return ACT_NEXTSONDE;
|
||||
}
|
||||
if (event==ACT_DISPLAY_SPECTRUM || event==ACT_DISPLAY_WIFI) {
|
||||
return event;
|
||||
}
|
||||
int n = event;
|
||||
if(event==ACT_DISPLAY_DEFAULT) {
|
||||
n = config.display;
|
||||
}
|
||||
if(n>=0&&n<4) {
|
||||
disp.setLayout(n);
|
||||
clearDisplay();
|
||||
updateDisplay();
|
||||
if(event&0x80) {
|
||||
sonde.currentSonde = (event&0x7F);
|
||||
return ACT_NEXTSONDE;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
return 0xFF;
|
||||
}
|
||||
|
||||
void Sonde::updateDisplayPos() {
|
||||
|
|
|
@ -31,13 +31,14 @@ extern const char *RXstr[];
|
|||
#define EVENTNAME(s) evstring[s]
|
||||
|
||||
//int8_t actions[EVT_MAX];
|
||||
#define ACT_NONE -1
|
||||
#define ACT_NONE 255
|
||||
#define ACT_DISPLAY(n) (n)
|
||||
#define ACT_DISPLAY_DEFAULT 15
|
||||
#define ACT_DISPLAY_SPECTRUM 14
|
||||
#define ACT_DISPLAY_WIFI 13
|
||||
#define ACT_DISPLAY_DEFAULT 63
|
||||
#define ACT_DISPLAY_SPECTRUM 62
|
||||
#define ACT_DISPLAY_WIFI 61
|
||||
#define ACT_NEXTSONDE 65
|
||||
#define ACT_PREVSONDE 64
|
||||
#define ACT_PREVSONDE 66
|
||||
#define ACT_SONDE(n) ((n)+128)
|
||||
|
||||
// 0000nnnn => goto display nnnn
|
||||
// 01000000 => goto sonde -1
|
||||
|
@ -49,19 +50,19 @@ 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 in RXTask. Will be reset to -1 by RXTask
|
||||
// mode change to sonde reception for sonde <value) in RXTask.
|
||||
// Will be reset to -1 by RXTask
|
||||
int activate;
|
||||
int requestSonde;
|
||||
// Variables set by RXTask, corresponding to activate
|
||||
// and requestSonde
|
||||
// Variables set by RXTask, corresponding to mode ST_DECODER (if active) or something else,
|
||||
// and currently received sonde
|
||||
int mainState;
|
||||
int currentSonde;
|
||||
int lastSonde;
|
||||
// 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 fifoOverflo;
|
||||
// int fifoOverflow;
|
||||
} RXTask;
|
||||
|
||||
extern RXTask rxtask;
|
||||
|
@ -87,6 +88,8 @@ typedef struct st_rdzconfig {
|
|||
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
|
||||
|
@ -174,8 +177,8 @@ public:
|
|||
|
||||
SondeInfo *si();
|
||||
|
||||
uint8_t timeoutEvent();
|
||||
int updateState(int8_t event);
|
||||
uint8_t timeoutEvent(SondeInfo *si);
|
||||
uint8_t updateState(uint8_t event);
|
||||
|
||||
void updateDisplayPos();
|
||||
void updateDisplayPos2();
|
||||
|
|
|
@ -5,7 +5,9 @@
|
|||
#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";
|
||||
|
@ -29,6 +31,18 @@ uint8_t getreply() {
|
|||
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;
|
||||
|
@ -58,20 +72,19 @@ void geteph() {
|
|||
Serial.printf("now: %s, existing: %s => updating\n", nowstr, tsstr);
|
||||
}
|
||||
status.close();
|
||||
|
||||
status = SPIFFS.open("/brdc.time","w");
|
||||
status.println(nowstr);
|
||||
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[256];
|
||||
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");
|
||||
|
@ -130,8 +143,11 @@ void geteph() {
|
|||
}
|
||||
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);
|
||||
|
@ -166,22 +182,26 @@ void geteph() {
|
|||
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(buf, 256);
|
||||
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 *)buf+inofs, &inlen, (uint8_t *)obuf, (mz_uint8 *)obuf+opos, &outlen, TINFL_FLAG_HAS_MORE_INPUT);
|
||||
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);
|
||||
if(res==0) break; // done indication
|
||||
Serial.printf("... (res=%d) decompressed %d into %d bytes\n", res, inlen, outlen);
|
||||
inofs += inlen;
|
||||
inlen = len - inofs;
|
||||
ofile.write((uint8_t *)(obuf+opos), outlen);
|
||||
//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;
|
||||
|
@ -190,7 +210,16 @@ void geteph() {
|
|||
}
|
||||
// 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();
|
||||
|
|
|
@ -382,7 +382,7 @@ EPHEM_t *read_RNXpephs(const char *file) {
|
|||
while ((c=fgetc(fp)) != '\n') { if (c == EOF) break; } */
|
||||
|
||||
ephem.week = 1; // ephem.gpsweek
|
||||
Serial.printf("Reading ephem for prn %d\n", ui);
|
||||
//Serial.printf("Reading ephem for prn %d\n", ui);
|
||||
if(ui<33) {
|
||||
#if 0
|
||||
// no need to do it the difficult way, most recent data is at end of file :-)
|
||||
|
|
Ładowanie…
Reference in New Issue