Several incremental changes (not yet ready for a new release)
- Correctly decode DMF06 (thanks to Chrischan for test sonde!!!) - Touch button support (in particular for v2 boards with "real" button) now its sufficient to just touch one of the pins of a v2 board - Multiple displays (inspired by DL2MF's modifications) - Wifi mode 2 (AP2) fixed missing initialization of mDNS (http://rdzsonde.local) - updated OTA URL (my.to domain unfortunately expired) - millis() call removed from ISR (/1000 on uint64_t type in millis causes library function call not marked as IRAM_ATTR, causing crash in some cases - edit files on file system (http://rdzsonde.local/edit.html?file=xyz.txt) (use with caution, no checks for buffer overflows) Some TODOs pending for next release version - sending AXUDP to aprsmap currently disabled - RX loop a bit too slow (in particular with AXUDP enabled), causing loss of RX frames due to SX1278 overflow. Needs some redesign in SX1278 handling. - display layout editable via config file
This commit is contained in:
parent
5797041272
commit
b3943aee31
|
|
@ -46,14 +46,21 @@ enum KeyPress { KP_NONE = 0, KP_SHORT, KP_DOUBLE, KP_MID, KP_LONG };
|
|||
|
||||
struct Button {
|
||||
uint8_t pin;
|
||||
|
||||
uint32_t numberKeyPresses;
|
||||
KeyPress pressed;
|
||||
unsigned long press_ts;
|
||||
boolean doublepress;
|
||||
|
||||
bool isTouched;
|
||||
long touchTime;
|
||||
};
|
||||
Button button1 = {0, 0, KP_NONE, 0, false};
|
||||
Button button1 = {0, 0, KP_NONE, 0, false, false, 0};
|
||||
Button button2 = {0, 0, KP_NONE, 0, false, false, 0};
|
||||
|
||||
|
||||
static int lastDisplay = 1;
|
||||
static int currentDisplay = 1;
|
||||
|
||||
// Set LED GPIO
|
||||
int ledPin = 1;
|
||||
|
|
@ -117,7 +124,7 @@ void setupChannelList() {
|
|||
return;
|
||||
}
|
||||
int i = 0;
|
||||
char launchsite[17]=" ";
|
||||
char launchsite[17] = " ";
|
||||
sonde.clearSonde();
|
||||
Serial.println("Reading channel config:");
|
||||
while (file.available()) {
|
||||
|
|
@ -143,8 +150,8 @@ void setupChannelList() {
|
|||
int active = space[3] == '+' ? 1 : 0;
|
||||
if (space[4] == ' ') {
|
||||
memset(launchsite, ' ', 16);
|
||||
int str_len = strlen(space+5);
|
||||
strncpy(launchsite, space+5, str_len>16?16:str_len);
|
||||
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);
|
||||
}
|
||||
|
|
@ -367,7 +374,7 @@ 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 */
|
||||
|
|
@ -407,6 +414,7 @@ struct st_configitems config_list[] = {
|
|||
{"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},
|
||||
{"button2_pin", "Button 2 input port (needs reboot)", 0, &sonde.config.button2_pin},
|
||||
{"led_pout", "LED output port (needs reboot)", 0, &sonde.config.led_pout},
|
||||
};
|
||||
const static int N_CONFIG = (sizeof(config_list) / sizeof(struct st_configitems));
|
||||
|
|
@ -489,16 +497,20 @@ const char *handleConfigPost(AsyncWebServerRequest *request) {
|
|||
f.printf("%s=%s\n", config_list[idx].name, strvalue.c_str());
|
||||
}
|
||||
f.close();
|
||||
currentDisplay = sonde.config.display;
|
||||
setupConfigData();
|
||||
}
|
||||
|
||||
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=\"");
|
||||
|
|
@ -532,6 +544,22 @@ const char *handleControlPost(AsyncWebServerRequest *request) {
|
|||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -562,10 +590,10 @@ const char *createEditForm(String filename) {
|
|||
const char *handleEditPost(AsyncWebServerRequest *request) {
|
||||
Serial.println("Handling post request");
|
||||
AsyncWebParameter *filep = request->getParam("file");
|
||||
if(!filep) return NULL;
|
||||
if (!filep) return NULL;
|
||||
String filename = filep->value();
|
||||
AsyncWebParameter *textp = request->getParam("text", true);
|
||||
if(!textp) return NULL;
|
||||
if (!textp) return NULL;
|
||||
String content = textp->value();
|
||||
File file = SPIFFS.open("/" + filename, "w");
|
||||
if (!file) {
|
||||
|
|
@ -733,56 +761,106 @@ const char *fetchWifiPw(const char *id) {
|
|||
return NULL;
|
||||
}
|
||||
|
||||
static bool isTouched = false;
|
||||
long touchTime = 0;
|
||||
hw_timer_t * timer = NULL;
|
||||
// It is not safe to call millis() in ISR!!!
|
||||
// millis() does a division int16_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();
|
||||
|
||||
#define IS_TOUCH(x) (((x)!=255)&&((x)!=-1)&&((x)&128))
|
||||
void initTouch() {
|
||||
#if 1
|
||||
timer = timerBegin(0, 80, true);
|
||||
if ( !(IS_TOUCH(sonde.config.button_pin) || IS_TOUCH(sonde.config.button2_pin)) ) return; // no touch buttongs configured
|
||||
|
||||
hw_timer_t *timer = timerBegin(0, 80, true);
|
||||
timerAttachInterrupt(timer, checkTouchStatus, true);
|
||||
timerAlarmWrite(timer, 300000, true);
|
||||
timerAlarmEnable(timer);
|
||||
touchAttachInterrupt(T4, touchISR, 20);
|
||||
#endif
|
||||
}
|
||||
|
||||
void IRAM_ATTR touchISR() {
|
||||
if (!isTouched) {
|
||||
touchTime = millis();
|
||||
isTouched = true;
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
void IRAM_ATTR checkTouchStatus() {
|
||||
if (isTouched) {
|
||||
if (touchRead(T4) > 60) {
|
||||
isTouched = false;
|
||||
void IRAM_ATTR touchISR() {
|
||||
if (!button1.isTouched) {
|
||||
button1.touchTime = my_millis();
|
||||
button1.isTouched = true;
|
||||
}
|
||||
}
|
||||
|
||||
void IRAM_ATTR touchISR2() {
|
||||
if (!button2.isTouched) {
|
||||
button2.touchTime = my_millis();
|
||||
button2.isTouched = true;
|
||||
}
|
||||
}
|
||||
|
||||
inline void IRAM_ATTR checkTouchButton(Button &button) {
|
||||
if (button.isTouched) {
|
||||
int tmp = touchRead(button.pin & 0x7f);
|
||||
// bad idea within ISR: Serial.printf("touchRead on pin %d is %d\n", button.pin, tmp);
|
||||
if (tmp > 60) {
|
||||
button.isTouched = false;
|
||||
// simulate key press
|
||||
button1.pressed = KP_SHORT;
|
||||
button.pressed = KP_SHORT;
|
||||
} else {
|
||||
if (millis() - touchTime > 3000) {
|
||||
if (my_millis() - button.touchTime > 3000) {
|
||||
// long touch
|
||||
// ginore for now
|
||||
// ignore for now
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void IRAM_ATTR 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.press_ts < 500) {
|
||||
// Double press
|
||||
button1.doublepress = true;
|
||||
} else {
|
||||
button1.doublepress = false;
|
||||
}
|
||||
button1.press_ts = millis();
|
||||
button1.press_ts = now;
|
||||
} else { //Button up
|
||||
unsigned int elapsed = millis() - button1.press_ts;
|
||||
unsigned int elapsed = now - button1.press_ts;
|
||||
if (elapsed > 1500) {
|
||||
if (elapsed < 4000) {
|
||||
button1.pressed = KP_MID;
|
||||
|
|
@ -795,17 +873,36 @@ void IRAM_ATTR buttonISR() {
|
|||
else button1.pressed = KP_SHORT;
|
||||
}
|
||||
button1.numberKeyPresses += 1;
|
||||
button1.press_ts = millis();
|
||||
button1.press_ts = now;
|
||||
}
|
||||
}
|
||||
|
||||
int getKeyPress() {
|
||||
KeyPress p = button1.pressed;
|
||||
button1.pressed = KP_NONE;
|
||||
Serial.printf("button1 press: %d at %ld (%d)\n", p, button1.press_ts, 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.press_ts, 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 */
|
||||
/* TODO: map touch event and second button */
|
||||
}
|
||||
|
||||
void setup()
|
||||
|
|
@ -819,7 +916,6 @@ void setup()
|
|||
}
|
||||
Serial.println("");
|
||||
pinMode(LORA_LED, OUTPUT);
|
||||
initTouch();
|
||||
|
||||
aprs_gencrctab();
|
||||
|
||||
|
|
@ -831,6 +927,7 @@ void setup()
|
|||
|
||||
setupConfigData(); // configuration must be read first due to OLED ports!!!
|
||||
LORA_LED = sonde.config.led_pout;
|
||||
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();
|
||||
|
|
@ -850,7 +947,11 @@ void setup()
|
|||
|
||||
setupWifiList();
|
||||
button1.pin = sonde.config.button_pin;
|
||||
pinMode(button1.pin, INPUT);
|
||||
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) {
|
||||
|
|
@ -925,7 +1026,10 @@ void setup()
|
|||
// xTaskCreate(mainloop, "MainServer", 10240, NULL, 10, NULL);
|
||||
|
||||
// Handle button press
|
||||
attachInterrupt(button1.pin, buttonISR, CHANGE);
|
||||
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();
|
||||
|
|
@ -948,6 +1052,10 @@ void setup()
|
|||
|
||||
void enterMode(int mode) {
|
||||
Serial.printf("enterMode(%d)\n", mode);
|
||||
if (mode == ST_SCANNER) {
|
||||
mode = ST_DECODER;
|
||||
currentDisplay = 0;
|
||||
}
|
||||
mainState = (MainState)mode;
|
||||
if (mainState == ST_SPECTRUM) {
|
||||
sonde.clearDisplay();
|
||||
|
|
@ -959,6 +1067,7 @@ void enterMode(int mode) {
|
|||
}
|
||||
|
||||
void loopDecoder() {
|
||||
#if 0
|
||||
switch (getKeyPress()) {
|
||||
case KP_SHORT:
|
||||
sonde.nextConfig();
|
||||
|
|
@ -966,7 +1075,8 @@ void loopDecoder() {
|
|||
sonde.updateDisplay();
|
||||
break;
|
||||
case KP_DOUBLE:
|
||||
enterMode(ST_SCANNER);
|
||||
//enterMode(ST_SCANNER);
|
||||
currentDisplay = 0;
|
||||
return;
|
||||
case KP_MID:
|
||||
enterMode(ST_SPECTRUM);
|
||||
|
|
@ -975,10 +1085,25 @@ void loopDecoder() {
|
|||
enterMode(ST_WIFISCAN);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
// Handle events that change display or sonde
|
||||
uint8_t event = getKeyPressEvent();
|
||||
if (!event) event = sonde.timeoutEvent();
|
||||
// Check if there is an action for this event
|
||||
int action = disp.layout->actions[event];
|
||||
Serial.printf("Loop: action is %d for event %s(%d)\n", action, EVENTNAME(event), event);
|
||||
action = sonde.updateState(action);
|
||||
Serial.printf("action is %d after updateState\n", action);
|
||||
if (action >= 0) {
|
||||
if (action == ACT_DISPLAY_SPECTRUM) enterMode(ST_SPECTRUM);
|
||||
else if (action == ACT_DISPLAY_WIFI) enterMode(ST_WIFISCAN);
|
||||
return;
|
||||
}
|
||||
|
||||
// sonde knows the current type and frequency, and delegates to the right decoder
|
||||
int res = sonde.receiveFrame();
|
||||
|
||||
if (res == 0 && connected) {
|
||||
if (0 && res == 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)) {
|
||||
|
|
@ -994,9 +1119,12 @@ 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();
|
||||
|
|
@ -1026,7 +1154,7 @@ void loopScanner() {
|
|||
tries = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void loopSpectrum() {
|
||||
int marker = 0;
|
||||
|
|
@ -1302,7 +1430,7 @@ void startAP() {
|
|||
String myIPstr = myIP.toString();
|
||||
sonde.setIP(myIPstr.c_str(), true);
|
||||
sonde.updateDisplayIP();
|
||||
SetupAsyncServer();
|
||||
enableNetwork(true);
|
||||
}
|
||||
|
||||
void initialMode() {
|
||||
|
|
@ -1597,21 +1725,17 @@ void execOTA() {
|
|||
}
|
||||
|
||||
|
||||
static int lastDisplay = 1;
|
||||
|
||||
void loop() {
|
||||
Serial.print("Running main loop. free heap:");
|
||||
Serial.println(ESP.getFreeHeap());
|
||||
//Serial.println(touchRead(13));
|
||||
//Serial.println(touchRead(4));
|
||||
Serial.printf("Running main loop in state %d. free heap: %d;\n ", mainState, ESP.getFreeHeap());
|
||||
switch (mainState) {
|
||||
case ST_DECODER: loopDecoder(); break;
|
||||
case ST_SCANNER: loopScanner(); break;
|
||||
// handled by decoder now ...... 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);
|
||||
|
|
@ -1621,9 +1745,10 @@ void loop() {
|
|||
Serial.println(gain);
|
||||
#endif
|
||||
loopWifiBackground();
|
||||
if (sonde.config.display != lastDisplay && (mainState == ST_DECODER)) {
|
||||
if (currentDisplay != lastDisplay && (mainState == ST_DECODER)) {
|
||||
disp.setLayout(currentDisplay);
|
||||
sonde.clearDisplay();
|
||||
sonde.updateDisplay();
|
||||
lastDisplay = sonde.config.display;
|
||||
lastDisplay = currentDisplay;
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -1,7 +1,9 @@
|
|||
#-------------------------------#
|
||||
# Hardware depending settings
|
||||
#-------------------------------#
|
||||
# pin: 255=disabled; x=button x+128=touch button
|
||||
button_pin=0
|
||||
button2_pin=255
|
||||
# LED port
|
||||
led_pout=9
|
||||
# OLED Setup is depending on hardware of LoRa board
|
||||
|
|
@ -15,9 +17,9 @@ oled_rst=16
|
|||
# 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
|
||||
wifi=2
|
||||
# display mode: 1=standard 2=fieldmode 3=field w/sondetype
|
||||
display=1
|
||||
#-------------------------------#
|
||||
|
|
@ -35,6 +37,11 @@ marker=1
|
|||
call=N0CALL
|
||||
passcode=12345
|
||||
#-------------------------------#
|
||||
# Sonde specific settings: bandwidth
|
||||
#-------------------------------#
|
||||
rs41.agcbw=6300
|
||||
rs41.rxbw=6300
|
||||
#-------------------------------#
|
||||
# axudp for sending to aprsmap
|
||||
#-------------------------------#
|
||||
# local use only, do not feed to public services
|
||||
|
|
|
|||
|
|
@ -1,2 +1,2 @@
|
|||
const char *version_name = "RDZ_TTGO_SONDE";
|
||||
const char *version_id = "devel20190523";
|
||||
const char *version_id = "devel20190524";
|
||||
|
|
|
|||
|
|
@ -16,7 +16,7 @@ int DFM::setup(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"));
|
||||
|
|
@ -275,7 +275,8 @@ int DFM::receiveFrame() {
|
|||
int e = sx1278.receivePacketTimeout(1000, data);
|
||||
if(e) { return RX_TIMEOUT; } //if timeout... return 1
|
||||
|
||||
if(inverse) { for(int i=0; i<33; i++) { data[i]^=0xFF; } }
|
||||
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);
|
||||
|
|
|
|||
|
|
@ -52,6 +52,12 @@ static uint8_t empty_tile2[8]={0x00, 0x11, 0x02, 0x02, 0x02, 0x01, 0x00, 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},
|
||||
|
|
@ -60,6 +66,12 @@ DispEntry searchLayout[] = {
|
|||
{7, 5, 0, disp.drawIP},
|
||||
{-1, -1, -1, NULL},
|
||||
};
|
||||
int16_t searchTimeouts[] = { -1, 0, 0 };
|
||||
int8_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},
|
||||
|
|
@ -74,6 +86,12 @@ DispEntry legacyLayout[] = {
|
|||
{6, 7, 0, disp.drawQS},
|
||||
{-1, -1, -1, NULL},
|
||||
};
|
||||
int16_t legacyTimeouts[] = { -1, -1, 20000 };
|
||||
int8_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},
|
||||
{4, 0, FONT_LARGE, disp.drawLon},
|
||||
|
|
@ -84,7 +102,12 @@ DispEntry fieldLayout[] = {
|
|||
{6, 7, 0, disp.drawQS},
|
||||
{-1, -1, -1, NULL},
|
||||
};
|
||||
DispEntry fieldLayout2[] = {
|
||||
int8_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_NONE, ACT_NONE, ACT_DISPLAY(0)};
|
||||
DispEntry field2Layout[] = {
|
||||
{2, 0, FONT_LARGE, disp.drawLat},
|
||||
{4, 0, FONT_LARGE, disp.drawLon},
|
||||
{1, 12, FONT_SMALL, disp.drawType},
|
||||
|
|
@ -96,21 +119,26 @@ DispEntry fieldLayout2[] = {
|
|||
{6, 7, 0, disp.drawQS},
|
||||
{-1, -1, -1, NULL},
|
||||
};
|
||||
int8_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_DISPLAY(0)};
|
||||
|
||||
DispEntry *layouts[]={searchLayout, legacyLayout, fieldLayout, fieldLayout2};
|
||||
DispInfo layouts[4] = {
|
||||
{ searchLayout, searchActions, searchTimeouts },
|
||||
{ legacyLayout, legacyActions, legacyTimeouts },
|
||||
{ fieldLayout, fieldActions, legacyTimeouts },
|
||||
{ field2Layout, field2Actions, legacyTimeouts } };
|
||||
|
||||
char Display::buf[17];
|
||||
|
||||
Display::Display() {
|
||||
setLayout(legacyLayout);
|
||||
}
|
||||
|
||||
void Display::setLayout(DispEntry *newLayout) {
|
||||
layout = newLayout;
|
||||
setLayout(1);
|
||||
}
|
||||
|
||||
void Display::setLayout(int layoutIdx) {
|
||||
layout = layouts[layoutIdx];
|
||||
layout = &layouts[layoutIdx];
|
||||
}
|
||||
|
||||
void Display::drawLat(DispEntry *de) {
|
||||
|
|
@ -245,44 +273,44 @@ void Display::setIP(const char *ip, bool AP) {
|
|||
|
||||
|
||||
void Display::updateDisplayPos() {
|
||||
for(DispEntry *di=layout; di->func != NULL; di++) {
|
||||
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; di->func != NULL; di++) {
|
||||
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; di->func != NULL; di++) {
|
||||
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; di->func != NULL; di++) {
|
||||
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; di->func != NULL; di++) {
|
||||
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; di->func != NULL; di++) {
|
||||
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; di->func != NULL; di++) {
|
||||
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);
|
||||
|
|
@ -290,7 +318,7 @@ void Display::updateDisplayIP() {
|
|||
}
|
||||
|
||||
void Display::updateDisplay() {
|
||||
for(DispEntry *di=layout; di->func != NULL; di++) {
|
||||
for(DispEntry *di=layout->de; di->func != NULL; di++) {
|
||||
di->func(di);
|
||||
}
|
||||
}
|
||||
|
|
|
|||
|
|
@ -14,12 +14,19 @@ struct DispEntry {
|
|||
const char *extra;
|
||||
};
|
||||
|
||||
struct DispInfo {
|
||||
DispEntry *de;
|
||||
int8_t *actions;
|
||||
int16_t *timeouts;
|
||||
};
|
||||
|
||||
|
||||
class Display {
|
||||
private:
|
||||
DispEntry *layout;
|
||||
void setLayout(DispEntry *layout);
|
||||
public:
|
||||
void setLayout(DispInfo *layout);
|
||||
DispInfo *layout;
|
||||
|
||||
Display();
|
||||
static char buf[17];
|
||||
static void drawLat(DispEntry *de);
|
||||
|
|
|
|||
|
|
@ -11,9 +11,12 @@ 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 *evstring[]={"NONE", "KEY1S", "KEY1D", "KEY1M", "KEY1L", "KEY2S", "KEY2D", "KEY2M", "KEY2L",
|
||||
"VIEWTO", "RXTO", "NORXTO", "(max)"};
|
||||
|
||||
Sonde::Sonde() {
|
||||
config.button_pin = 0;
|
||||
config.button2_pin = T4 + 128; // T4 == GPIO13, should be ok for v1 and v2
|
||||
config.led_pout = 9;
|
||||
// Try autodetecting board type
|
||||
// Seems like on startup, GPIO4 is 1 on v1 boards, 0 on v2.1 boards?
|
||||
|
|
@ -40,7 +43,6 @@ Sonde::Sonde() {
|
|||
config.spectrum=10;
|
||||
config.timer=0;
|
||||
config.marker=0;
|
||||
config.norx_timeout=0;
|
||||
config.showafc=0;
|
||||
config.freqofs=0;
|
||||
config.rs41.agcbw=25000;
|
||||
|
|
@ -79,6 +81,8 @@ 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,"led_pout")==0) {
|
||||
config.led_pout = atoi(val);
|
||||
} else if(strcmp(cfg,"oled_sda")==0) {
|
||||
|
|
@ -109,8 +113,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) {
|
||||
|
|
@ -191,6 +193,8 @@ SondeInfo *Sonde::si() {
|
|||
|
||||
void Sonde::setup() {
|
||||
// Test only: setIP("123.456.789.012");
|
||||
sondeList[currentSonde].lastState = -1;
|
||||
sondeList[currentSonde].viewStart = millis();
|
||||
// update receiver config: TODO
|
||||
Serial.print("Setting up receiver on channel ");
|
||||
Serial.println(currentSonde);
|
||||
|
|
@ -220,9 +224,72 @@ int Sonde::receiveFrame() {
|
|||
}
|
||||
memmove(sonde.si()->rxStat+1, sonde.si()->rxStat, 17);
|
||||
sonde.si()->rxStat[0] = ret;
|
||||
if(ret==0) {
|
||||
if(sonde.si()->lastState != 1) {
|
||||
sonde.si()->rxStart = millis();
|
||||
sonde.si()->lastState = 1;
|
||||
}
|
||||
} else {
|
||||
if(sonde.si()->lastState != 0) {
|
||||
sonde.si()->norxStart = millis();
|
||||
sonde.si()->lastState = 0;
|
||||
}
|
||||
}
|
||||
return ret; // 0: OK, 1: Timeuot, 2: Other error, 3: unknown
|
||||
}
|
||||
|
||||
uint8_t Sonde::timeoutEvent() {
|
||||
uint32_t now = millis();
|
||||
Serial.printf("Timeout check: %ld - %ld vs %ld; %ld - %ld vs %ld; %ld - %ld vs %ld\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]);
|
||||
Serial.printf("lastState is %d\n", sonde.si()->lastState);
|
||||
if(disp.layout->timeouts[0]>=0 && now - sonde.si()->viewStart >= disp.layout->timeouts[0]) {
|
||||
Serial.println("View timeout");
|
||||
return EVT_VIEWTO;
|
||||
}
|
||||
if(sonde.si()->lastState==1 && disp.layout->timeouts[1]>=0 && now - sonde.si()->rxStart >= disp.layout->timeouts[1]) {
|
||||
Serial.println("RX timeout");
|
||||
return EVT_RXTO;
|
||||
}
|
||||
if(sonde.si()->lastState==0 && disp.layout->timeouts[2]>=0 && now - sonde.si()->norxStart >= disp.layout->timeouts[2]) {
|
||||
Serial.println("No RX timeout");
|
||||
return EVT_NORXTO;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int Sonde::updateState(int8_t event) {
|
||||
Serial.printf("Sonde::updateState for event %d\n", event);
|
||||
if(event==ACT_NONE) return -1;
|
||||
if(event==ACT_NEXTSONDE) {
|
||||
Serial.printf("advancing to next sonde\n");
|
||||
sonde.nextConfig();
|
||||
return -1;
|
||||
}
|
||||
if (event==ACT_PREVSONDE) {
|
||||
// TODO
|
||||
Serial.printf("previous not supported, advancing to next sonde\n");
|
||||
sonde.nextConfig();
|
||||
return -1;
|
||||
}
|
||||
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();
|
||||
}
|
||||
// TODO: change display to n
|
||||
return -1;
|
||||
}
|
||||
|
||||
void Sonde::updateDisplayPos() {
|
||||
disp.updateDisplayPos();
|
||||
}
|
||||
|
|
|
|||
|
|
@ -9,6 +9,38 @@
|
|||
// RX_OK: header and data ok
|
||||
enum RxResult { RX_OK, RX_TIMEOUT, RX_ERROR, RX_UNKNOWN };
|
||||
|
||||
// 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[];
|
||||
#define EVENTNAME(s) evstring[s]
|
||||
|
||||
//int8_t actions[EVT_MAX];
|
||||
#define ACT_NONE -1
|
||||
#define ACT_DISPLAY(n) (n)
|
||||
#define ACT_DISPLAY_DEFAULT 15
|
||||
#define ACT_DISPLAY_SPECTRUM 14
|
||||
#define ACT_DISPLAY_WIFI 13
|
||||
#define ACT_NEXTSONDE 65
|
||||
#define ACT_PREVSONDE 64
|
||||
|
||||
// 0000nnnn => goto display nnnn
|
||||
// 01000000 => goto sonde -1
|
||||
// 01000001 => goto sonde +1
|
||||
|
||||
enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41 };
|
||||
extern const char *sondeTypeStr[5];
|
||||
|
||||
|
|
@ -18,7 +50,8 @@ struct st_rs41config {
|
|||
};
|
||||
|
||||
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 led_pout; // POUT port number of LED (used as serial monitor)
|
||||
int oled_sda; // OLED data pin
|
||||
int oled_scl; // OLED clock pin
|
||||
|
|
@ -65,9 +98,14 @@ typedef struct st_sondeinfo {
|
|||
// 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: 0=undef[empty] 1=timeout[.] 2=errro[E] 3=ok[1]
|
||||
|
||||
|
||||
#define MAXSONDE 99
|
||||
|
|
@ -92,6 +130,9 @@ public:
|
|||
int receiveFrame();
|
||||
SondeInfo *si();
|
||||
|
||||
uint8_t timeoutEvent();
|
||||
int updateState(int8_t event);
|
||||
|
||||
void updateDisplayPos();
|
||||
void updateDisplayPos2();
|
||||
void updateDisplayID();
|
||||
|
|
|
|||
Loading…
Reference in New Issue