kopia lustrzana https://github.com/dl9rdz/rdz_ttgo_sonde
debug output cleanup; minor dfm17 id bugs removed
rodzic
aaa33267d7
commit
1b0cde0f6c
|
@ -128,13 +128,13 @@ const String sondeTypeSelect(int activeType) {
|
|||
String sts = "";
|
||||
for (int i = 0; i < NSondeTypes; i++) {
|
||||
sts += "<option value=\"";
|
||||
sts += sondeTypeStr[i];
|
||||
sts += sondeTypeLongStr[i];
|
||||
sts += "\"";
|
||||
if (activeType == i) {
|
||||
sts += " selected";
|
||||
}
|
||||
sts += ">";
|
||||
sts += sondeTypeStr[i];
|
||||
sts += sondeTypeLongStr[i];
|
||||
sts += "</option>";
|
||||
}
|
||||
return sts;
|
||||
|
@ -368,7 +368,7 @@ void addSondeStatus(char *ptr, int i)
|
|||
struct tm ts;
|
||||
SondeInfo *s = &sonde.sondeList[i];
|
||||
strcat(ptr, "<table>");
|
||||
sprintf(ptr + strlen(ptr), "<tr><td id=\"sfreq\">%3.3f MHz, Type: %s</td><tr><td>ID: %s", s->freq, sondeTypeStr[s->type],
|
||||
sprintf(ptr + strlen(ptr), "<tr><td id=\"sfreq\">%3.3f MHz, Type: %s</td><tr><td>ID: %s", s->freq, sondeTypeLongStr[s->type],
|
||||
s->validID ? s->id : "<?""?>");
|
||||
if (s->validID && (s->type == STYPE_DFM06 || s->type == STYPE_DFM09 || s->type == STYPE_M10)) {
|
||||
sprintf(ptr + strlen(ptr), " (ser: %s)", s->ser);
|
||||
|
@ -447,8 +447,8 @@ struct st_configitems config_list[] = {
|
|||
{"rs41.rxbw", "RS41 RX bandwidth", 0, &sonde.config.rs41.rxbw},
|
||||
{"rs92.rxbw", "RS92 RX (and AGC) bandwidth", 0, &sonde.config.rs92.rxbw},
|
||||
{"rs92.alt2d", "RS92 2D fix default altitude", 0, &sonde.config.rs92.alt2d},
|
||||
{"dfm.agcbw", "DFM6/9 AGC bandwidth", 0, &sonde.config.dfm.agcbw},
|
||||
{"dfm.rxbw", "DFM6/9 RX bandwidth", 0, &sonde.config.dfm.rxbw},
|
||||
{"dfm.agcbw", "DFM AGC bandwidth", 0, &sonde.config.dfm.agcbw},
|
||||
{"dfm.rxbw", "DFM RX bandwidth", 0, &sonde.config.dfm.rxbw},
|
||||
{"", "Data feed configuration", -5, NULL},
|
||||
/* APRS settings */
|
||||
{"call", "Call", 8, sonde.config.call},
|
||||
|
@ -1649,7 +1649,7 @@ void loopDecoder() {
|
|||
// sonde knows the current type and frequency, and delegates to the right decoder
|
||||
uint16_t res = sonde.waitRXcomplete();
|
||||
int action;
|
||||
Serial.printf("waitRX result is %x\n", (int)res);
|
||||
//Serial.printf("waitRX result is %x\n", (int)res);
|
||||
action = (int)(res >> 8);
|
||||
// TODO: update displayed sonde?
|
||||
|
||||
|
@ -1673,7 +1673,7 @@ void loopDecoder() {
|
|||
}
|
||||
|
||||
if (!tncclient.connected()) {
|
||||
Serial.println("TNC client not connected");
|
||||
//Serial.println("TNC client not connected");
|
||||
tncclient = tncserver.available();
|
||||
if (tncclient.connected()) {
|
||||
Serial.println("new TCP KISS connection");
|
||||
|
@ -1696,8 +1696,8 @@ void loopDecoder() {
|
|||
if (connected) {
|
||||
char raw[201];
|
||||
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
|
||||
Serial.println("Sending position via UDP");
|
||||
Serial.print("Sending: "); Serial.println(raw);
|
||||
Serial.print("Sending UDP:");
|
||||
Serial.println(raw);
|
||||
udp.beginPacket(sonde.config.udpfeed.host, sonde.config.udpfeed.port);
|
||||
udp.write((const uint8_t *)raw, rawlen);
|
||||
udp.endPacket();
|
||||
|
@ -1713,14 +1713,15 @@ void loopDecoder() {
|
|||
// also send to web socket
|
||||
//TODO
|
||||
}
|
||||
Serial.println("updateDisplay started");
|
||||
Serial.print("updateDisplay started... ");
|
||||
if (forceReloadScreenConfig) {
|
||||
disp.initFromFile();
|
||||
sonde.clearDisplay();
|
||||
forceReloadScreenConfig = false;
|
||||
}
|
||||
int t = millis();
|
||||
sonde.updateDisplay();
|
||||
Serial.println("updateDisplay done");
|
||||
Serial.printf("updateDisplay done (after %d ms)\n", (int)(millis()-t));
|
||||
}
|
||||
|
||||
void setCurrentDisplay(int value) {
|
||||
|
@ -2336,8 +2337,8 @@ void execOTA() {
|
|||
|
||||
|
||||
void loop() {
|
||||
Serial.printf("\nRunning main loop in state %d. free heap: %d;\n", mainState, ESP.getFreeHeap());
|
||||
Serial.printf("currentDisp:%d lastDisp:%d\n", currentDisplay, lastDisplay);
|
||||
Serial.printf("\nRunning main loop in state %d [currentDisp:%d, lastDiso:%d]. free heap: %d;\n",
|
||||
mainState, currentDisplay, lastDisplay, ESP.getFreeHeap());
|
||||
switch (mainState) {
|
||||
case ST_DECODER:
|
||||
#ifndef DISABLE_MAINRX
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
const char *version_name = "rdzTTGOsonde";
|
||||
const char *version_id = "devel20201128b";
|
||||
const char *version_id = "devel20201129";
|
||||
const int SPIFFS_MAJOR=2;
|
||||
const int SPIFFS_MINOR=4;
|
||||
|
|
|
@ -193,14 +193,13 @@ void DFM::finddfname(uint8_t *b)
|
|||
st = b[0]; /* frame start byte */
|
||||
ix = b[3]; /* hi/lo part of ser; (LSB due to our bitsToBytes...) */
|
||||
d = (b[1]<<8) + b[2]; /* data byte */
|
||||
i = 0;
|
||||
/* find highest channel number single frame serial,
|
||||
(2 frame serial will make a single serial too) */
|
||||
if(dfmstate.idcnt0 < DFMIDTHRESHOLD && dfmstate.idcnt1 < DFMIDTHRESHOLD) {
|
||||
uint32_t v = (st<<20) | (d<<4) | ix;
|
||||
if ( st > (dfmstate.lastfrid>>20) ) {
|
||||
dfmstate.lastfrid = v;
|
||||
Serial.print("MAXCH: "); Serial.println(st);
|
||||
Serial.print(" MAXCH:"); Serial.print(st);
|
||||
dfmstate.lastfrcnt = 0;
|
||||
} else if ( st == (dfmstate.lastfrid>>20) ) {
|
||||
/* same id found */
|
||||
|
@ -228,14 +227,14 @@ void DFM::finddfname(uint8_t *b)
|
|||
return;
|
||||
}
|
||||
dfmstate.lastfrcnt = 0;
|
||||
Serial.println(" NOT NUMERIC SERIAL");
|
||||
Serial.print(" NOT NUMERIC SERIAL");
|
||||
}
|
||||
//anonym->idtime = osic_time();
|
||||
} else {
|
||||
Serial.print(" MAXCHCNT/SECURITYLEVEL:");
|
||||
Serial.print(" MAXCHCNT/SECLVL:");
|
||||
Serial.print(dfmstate.lastfrcnt);
|
||||
Serial.print("/");
|
||||
Serial.println(thres);
|
||||
Serial.print(thres);
|
||||
}
|
||||
} else {
|
||||
dfmstate.lastfrid = v; /* not stable ser */
|
||||
|
@ -244,7 +243,9 @@ void DFM::finddfname(uint8_t *b)
|
|||
}
|
||||
} /*find highest channel number single frame serial */
|
||||
|
||||
i = 0;
|
||||
while (i<dfmstate.nameregtop && dfmstate.start[i]!=st) i++;
|
||||
Serial.printf(" %02x:i=%d,top=%d", st, i, dfmstate.nameregtop);
|
||||
if (i<dfmstate.nameregtop) {
|
||||
if (ix<=1UL && (dfmstate.cnt[2*i+ix]==0 || dfmstate.dat[2*i+ix]==d)) {
|
||||
dfmstate.dat[2*i+ix] = d;
|
||||
|
@ -260,21 +261,21 @@ void DFM::finddfname(uint8_t *b)
|
|||
Serial.print(",st=");
|
||||
Serial.print(st);
|
||||
Serial.print(",lastfrid=");
|
||||
Serial.println(dfmstate.lastfrid>>20);
|
||||
Serial.print(dfmstate.lastfrid>>20);
|
||||
if( (dfmstate.cnt[2*i]>DFMIDTHRESHOLD && dfmstate.cnt[2*i+1]>DFMIDTHRESHOLD) ||
|
||||
(dfmstate.cnt[2*1]>0 && dfmstate.cnt[2*i+1]>0 && st == (dfmstate.lastfrid>>20) && (st>>4)>6) ) {
|
||||
(dfmstate.cnt[2*i]>0 && dfmstate.cnt[2*i+1]>0 && st == (dfmstate.lastfrid>>20) && (st>>4)>6) ) {
|
||||
if(dfmstate.idcnt0 <= 1) {
|
||||
dfmstate.idcnt0 = dfmstate.cnt[2*i];
|
||||
dfmstate.idcnt1 = dfmstate.cnt[2*i+1];
|
||||
dfmstate.nameregok = i;
|
||||
// generate id.....
|
||||
snprintf(sonde.si()->id, 10, "D%d", ((dfmstate.dat[2*i]<<16)|dfmstate.dat[2*i+1])%100000000);
|
||||
Serial.print(" NEW AUTOID:");
|
||||
Serial.print("\nNEW AUTOID:");
|
||||
Serial.println(sonde.si()->id);
|
||||
sonde.si()->validID = true;
|
||||
}
|
||||
if(dfmstate.nameregok==i) {
|
||||
Serial.println("ID OK");
|
||||
Serial.print(" ID OK");
|
||||
// idtime = .... /* TODO */
|
||||
}
|
||||
}
|
||||
|
@ -439,7 +440,6 @@ int DFM::receive() {
|
|||
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);
|
||||
|
@ -460,6 +460,7 @@ int DFM::receive() {
|
|||
decodeCFG(byte_conf);
|
||||
decodeDAT(byte_dat1);
|
||||
decodeDAT(byte_dat2);
|
||||
Serial.println("");
|
||||
}
|
||||
return RX_OK;
|
||||
}
|
||||
|
|
|
@ -29,6 +29,7 @@ extern SemaphoreHandle_t axpSemaphore;
|
|||
SPIClass spiDisp(HSPI);
|
||||
|
||||
const char *sondeTypeStr[NSondeTypes] = { "DFM6", "DFM9", "RS41", "RS92", "M10 " };
|
||||
const char *sondeTypeLongStr[NSondeTypes] = { "DFM6/17", "DFM9", "RS41", "RS92", "M10 " };
|
||||
|
||||
#define TYPE_IS_DFM(t) ( (t)==STYPE_DFM06 || (t)==STYPE_DFM09 )
|
||||
#define TYPE_IS_METEO(t) ( (t)==STYPE_M10 )
|
||||
|
@ -391,7 +392,7 @@ void ILI9225Display::drawString(uint8_t x, uint8_t y, const char *s, int16_t wid
|
|||
int16_t w,h;
|
||||
boolean alignright=false;
|
||||
if(findex<3) { // standard font
|
||||
Serial.printf("Simple Text %s at %d,%d [%d]\n", s, x, y, width);
|
||||
DebugPrintf(DEBUG_DISPLAY, "Simple Text %s at %d,%d [%d]\n", s, x, y, width);
|
||||
tft->drawText(x, y, s, fg);
|
||||
return;
|
||||
}
|
||||
|
@ -406,7 +407,7 @@ void ILI9225Display::drawString(uint8_t x, uint8_t y, const char *s, int16_t wid
|
|||
width=w;
|
||||
if(alignright) {
|
||||
x -= w;
|
||||
Serial.print("reducing x by widht, its now ");
|
||||
DebugPrint(DEBUG_DISPLAY, "reducing x by widht, its now ");
|
||||
Serial.println(x);
|
||||
}
|
||||
}
|
||||
|
@ -414,7 +415,7 @@ void ILI9225Display::drawString(uint8_t x, uint8_t y, const char *s, int16_t wid
|
|||
|
||||
if(findex-3>=ngfx) findex=3;
|
||||
tft->fillRectangle(x, y, x + width, y + gfxoffsets[findex-3].yclear, bg);
|
||||
Serial.printf("GFX Text %s at %d,%d+%d in color %x, width=%d (w=%d)\n", s, x, y, gfxoffsets[findex-3].yofs, fg, width, w);
|
||||
DebugPrintf(DEBUG_DISPLAY,"GFX Text %s at %d,%d+%d in color %x, width=%d (w=%d)\n", s, x, y, gfxoffsets[findex-3].yofs, fg, width, w);
|
||||
if(alignright) {
|
||||
tft->drawGFXText(x + width - w, y + gfxoffsets[findex-3].yofs, s, fg);
|
||||
} else {
|
||||
|
@ -1021,7 +1022,7 @@ void Display::drawVS(DispEntry *de) {
|
|||
return;
|
||||
}
|
||||
snprintf(buf, 16, " %+2.1f", sonde.si()->vs);
|
||||
Serial.printf("drawVS: extra is %s width=%d\n", de->extra?de->extra:"<null>", de->width);
|
||||
DebugPrintf(DEBUG_DISPLAY, "drawVS: extra is %s width=%d\n", de->extra?de->extra:"<null>", de->width);
|
||||
if(de->extra) { strcat(buf, de->extra); }
|
||||
drawString(de, buf+strlen(buf)-5- (de->extra?strlen(de->extra):0) );
|
||||
if(!de->extra) rdis->drawTile(de->x+5,de->y,2,ms_tiles);
|
||||
|
@ -1227,7 +1228,7 @@ static int tmpc=0;
|
|||
gpsBear = -1;
|
||||
}
|
||||
|
||||
Serial.printf("GPS data: valid%d GPS at %f,%f (alt=%d,cog=%d); sonde at dist=%d, dir=%d rel.bear=%d\n",gpsValid?1:0,
|
||||
DebugPrintf(DEBUG_DISPLAY, "GPS data: valid%d GPS at %f,%f (alt=%d,cog=%d); sonde at dist=%d, dir=%d rel.bear=%d\n",gpsValid?1:0,
|
||||
gpsLat, gpsLon, gpsAlt, gpsCourse, gpsDist, gpsDir, gpsBear);
|
||||
}
|
||||
|
||||
|
|
|
@ -138,7 +138,7 @@ void Scanner::scan()
|
|||
int wait = scanconfig.ADDWAIT + 20 + 1000*(1<<(scanconfig.SMOOTH+1))/4/(0.001*CHANBW);
|
||||
Serial.print("wait time (us) is: "); Serial.println(wait);
|
||||
for(int iter=0; iter<3; iter++) { // three interations, to catch all RS41 transmissions
|
||||
delayMicroseconds(20000);
|
||||
delayMicroseconds(20000); yield();
|
||||
for(int i=0; i<scanconfig.PLOT_W*scanconfig.SMPL_PIX; i++) {
|
||||
freq = STARTF + 1000.0*i*scanconfig.CHANSTEP;
|
||||
//freq = 404000000 + 100*i*scanconfig.CHANSTEP;
|
||||
|
@ -159,6 +159,7 @@ void Scanner::scan()
|
|||
}
|
||||
}
|
||||
}
|
||||
yield();
|
||||
unsigned long duration = millis()-start;
|
||||
Serial.print("wait: ");
|
||||
Serial.println(wait);
|
||||
|
|
|
@ -10,6 +10,7 @@
|
|||
#include "Display.h"
|
||||
#include <Wire.h>
|
||||
|
||||
uint8_t debug = 255-8;
|
||||
|
||||
RXTask rxtask = { -1, -1, -1, 0xFFFF, 0 };
|
||||
|
||||
|
@ -465,7 +466,7 @@ void Sonde::receive() {
|
|||
int event = getKeyPressEvent();
|
||||
if (!event) event = timeoutEvent(si);
|
||||
int action = (event==EVT_NONE) ? ACT_NONE : disp.layout->actions[event];
|
||||
Serial.printf("event %x: action is %x\n", event, action);
|
||||
if(action!=ACT_NONE) { Serial.printf("event %x: action is %x\n", event, action); }
|
||||
// If action is to move to a different sonde index, we do update things here, set activate
|
||||
// to force the sx1278 task to call sonde.setup(), and pass information about sonde to
|
||||
// main loop (display update...)
|
||||
|
@ -482,7 +483,7 @@ void Sonde::receive() {
|
|||
}
|
||||
}
|
||||
res = (action<<8) | (res&0xff);
|
||||
Serial.printf("receive Result is %04x\n", res);
|
||||
Serial.printf("receive(): Result is %04x (action %d, res %d)\n", res, action, res&0xff);
|
||||
// let waitRXcomplete resume...
|
||||
rxtask.receiveResult = res;
|
||||
}
|
||||
|
@ -499,7 +500,7 @@ rxloop:
|
|||
}
|
||||
if( rxtask.receiveResult == RX_UPDATERSSI ) {
|
||||
rxtask.receiveResult = 0xFFFF;
|
||||
Serial.print("RSSI update: ");
|
||||
Serial.printf("RSSI update: %d/2\n", sonde.si()->rssi);
|
||||
disp.updateDisplayRSSI();
|
||||
goto rxloop;
|
||||
}
|
||||
|
@ -537,12 +538,11 @@ rxloop:
|
|||
uint8_t Sonde::timeoutEvent(SondeInfo *si) {
|
||||
uint32_t now = millis();
|
||||
#if 1
|
||||
Serial.printf("Timeout check: %d - %d vs %d; %d - %d vs %d; %d - %d vs %d\n",
|
||||
Serial.printf("Timeout check: %d - %d vs %d; %d - %d vs %d; %d - %d vs %d; lastState: %d\n",
|
||||
now, si->viewStart, disp.layout->timeouts[0],
|
||||
now, si->rxStart, disp.layout->timeouts[1],
|
||||
now, si->norxStart, disp.layout->timeouts[2]);
|
||||
now, si->norxStart, disp.layout->timeouts[2], si->lastState);
|
||||
#endif
|
||||
Serial.printf("lastState is %d\n", si->lastState);
|
||||
if(disp.layout->timeouts[0]>=0 && now - si->viewStart >= disp.layout->timeouts[0]) {
|
||||
Serial.println("View timer expired");
|
||||
return EVT_VIEWTO;
|
||||
|
@ -650,9 +650,7 @@ void Sonde::updateDisplayIP() {
|
|||
|
||||
void Sonde::updateDisplay()
|
||||
{
|
||||
int t = millis();
|
||||
disp.updateDisplay();
|
||||
Serial.printf("updateDisplay took %d ms\n", (int)(millis()-t));
|
||||
}
|
||||
|
||||
void Sonde::clearDisplay() {
|
||||
|
|
|
@ -2,6 +2,13 @@
|
|||
#ifndef Sonde_h
|
||||
#define Sonde_h
|
||||
|
||||
enum DbgLevel { DEBUG_OFF=0, DEBUG_INFO=1, DEBUG_DISPLAY=8 }; // to be extended for configuring serial debug output
|
||||
extern uint8_t debug;
|
||||
|
||||
#define DebugPrint(l,x) if(debug&l) { Serial.print(x); }
|
||||
#define DebugPrintln(l,x) if(debug&l) { Serial.println(x); }
|
||||
#define DebugPrintf(l,...) if(debug&l) { Serial.printf(__VA_ARGS__); }
|
||||
|
||||
// RX_TIMEOUT: no header detected
|
||||
// RX_ERROR: header detected, but data not decoded (crc error, etc.)
|
||||
// RX_OK: header and data ok
|
||||
|
@ -49,6 +56,7 @@ extern const char *RXstr[];
|
|||
#define NSondeTypes 5
|
||||
enum SondeType { STYPE_DFM06, STYPE_DFM09, STYPE_RS41, STYPE_RS92, STYPE_M10 };
|
||||
extern const char *sondeTypeStr[NSondeTypes];
|
||||
extern const char *sondeTypeLongStr[NSondeTypes];
|
||||
|
||||
typedef struct st_sondeinfo {
|
||||
// receiver configuration
|
||||
|
|
|
@ -204,7 +204,7 @@ extern int aprsstr_mon2raw(const char *mon, char raw[], int raw_len)
|
|||
--n;
|
||||
}
|
||||
aprsstr_appcrc(raw, raw_len, p);
|
||||
fprintf(stderr,"results in %s\n",raw);
|
||||
//fprintf(stderr,"results in %s\n",raw);
|
||||
return p+2;
|
||||
} /* end mon2raw() */
|
||||
|
||||
|
|
Ładowanie…
Reference in New Issue