gps init bugfix, less debug messages, gps for android w/o gps (+GPGST parser), merge kml live view

This commit is contained in:
Hansi, dl9rdz 2021-03-14 18:12:07 +01:00
parent db3f62c243
commit 8df0859f1c
9 changed files with 324 additions and 280 deletions

View File

@ -27,9 +27,9 @@ int e;
enum MainState { ST_DECODER, ST_SPECTRUM, ST_WIFISCAN, ST_UPDATE, ST_TOUCHCALIB };
static MainState mainState = ST_WIFISCAN; // ST_WIFISCAN;
const char *mainStateStr[5] = {"DECODER", "SPECTRUM", "WIFISCAN", "UPDATE", "TOUCHCALIB" };
AsyncWebServer server(80);
AsyncWebSocket ws("/ws");
AXP20X_Class axp;
#define PMU_IRQ 35
@ -742,7 +742,9 @@ const char *createControlForm() {
strcat(ptr, "\" value=\"");
strcat(ptr, ctrllabel[i]);
strcat(ptr, "\"></input>");
if(i==3) { strcat(ptr, "<p></p>"); }
if (i == 3) {
strcat(ptr, "<p></p>");
}
}
HTMLBODYEND(ptr);
Serial.printf("Control form: size=%d bytes\n", strlen(message));
@ -1021,6 +1023,9 @@ const char *sendGPX(AsyncWebServerRequest * request) {
return message;
}
#if 0
// no longer supported
// tcp socket / json for android app is used now
void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventType type, void * arg, uint8_t *data, size_t len) {
if (type == WS_EVT_CONNECT) {
Serial.println("Websocket client connection received");
@ -1029,6 +1034,7 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT
Serial.println("Client disconnected");
}
}
#endif
const char* PARAM_MESSAGE = "message";
@ -1154,10 +1160,6 @@ void SetupAsyncServer() {
}
});
// Set up web socket
ws.onEvent(onWsEvent);
server.addHandler(&ws);
// Start server
server.begin();
}
@ -1168,18 +1170,10 @@ int fetchWifiIndex(const char *id) {
Serial.printf("Match for %s at %d\n", id, i);
return i;
}
Serial.printf("No match: '%s' vs '%s'\n", id, networks[i].id.c_str());
//Serial.printf("No match: '%s' vs '%s'\n", id, networks[i].id.c_str());
const char *cfgid = networks[i].id.c_str();
int len = strlen(cfgid);
if (strlen(id) > len) len = strlen(id);
Serial.print("SSID: ");
for (int i = 0; i < len; i++) {
Serial.printf("%02x ", id[i]);
} Serial.println("");
Serial.print("Conf: ");
for (int i = 0; i < len; i++) {
Serial.printf("%02x ", cfgid[i]);
} Serial.println("");
}
return -1;
}
@ -1285,6 +1279,36 @@ void unkHandler(T nmea) {
if (*s == ',') return; /// no new course data
int lastCourse = nmea.parseFloat(s, 0, NULL);
Serial.printf("Course update: %d\n", lastCourse);
} else if (strcmp(nmea.getMessageID(), "GST") == 0) {
// get horizontal accuracy for android app on devices without gps
// GPGST,time,rms,-,-,-,stdlat,stdlon,stdalt,cs
const char *s = nmea.getSentence();
while (*s && *s != ',') s++; // #0: GST
if (*s == ',') s++; else return;
while (*s && *s != ',') s++; // #1: time: skip
if (*s == ',') s++; else return;
while (*s && *s != ',') s++; // #1: rms: skip
if (*s == ',') s++; else return;
while (*s && *s != ',') s++; // #1: (-): skip
if (*s == ',') s++; else return;
while (*s && *s != ',') s++; // #1: (-): skip
if (*s == ',') s++; else return;
while (*s && *s != ',') s++; // #1: (-): skip
if (*s == ',') s++; else return;
// stdlat
int stdlat = nmea.parseFloat(s, 1, NULL);
while (*s && *s != ',') s++;
if (*s == ',') s++; else return;
// stdlong
int stdlon = nmea.parseFloat(s, 1, NULL);
// calculate position error as 1-signma horizontal RMS
// I guess that is equivalent to Androids getAccurac()?
int poserr = 0;
if (stdlat < 10000 && stdlon < 10000) { // larger errors: no GPS fix, avoid overflow in *
poserr = (int)(sqrt(0.5 * (stdlat * stdlat + stdlon * stdlon)));
}
//Serial.printf("\nHorizontal accuracy: %d, %d => %.1fm\n", stdlat, stdlon, 0.1*poserr);
gpsPos.accuracy = poserr;
}
}
@ -1332,6 +1356,8 @@ void gpsTask(void *parameter) {
uint8_t ubx_set9k6[] = {UBX_SYNCH_1, UBX_SYNCH_2, 0x06, 0x00, 0x14, 0x00, 0x01, 0x00, 0x00, 0x00, 0xC0, 0x08, 0x00, 0x00, 0x80, 0x25, 0x00, 0x00, 0x03, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x8D, 0x8F};
uint8_t ubx_factorydef[] = {UBX_SYNCH_1, UBX_SYNCH_2, 0x06, 0x09, 13, 0, 0xff, 0xff, 0xff, 0xff, 0, 0, 0, 0, 0, 0, 0, 0, 0xff, 0x17, 0x8A };
uint8_t ubx_hardreset[] = {UBX_SYNCH_1, UBX_SYNCH_2, 0x06, 0x04, 4, 0, 0xff, 0xff, 0, 0, 0x0C, 0x5D };
// GPGST: Class 0xF0 Id 0x07
uint8_t ubx_enable_gpgst[] = {UBX_SYNCH_1, UBX_SYNCH_2, 0x06, 0x01, 3, 0, 0xF0, 0x07, 2, 0x03, 0x1F};
void initGPS() {
if (sonde.config.gps_rxd < 0) return; // GPS disabled
@ -1353,12 +1379,15 @@ void initGPS() {
Serial2.write(ubx_factorydef, sizeof(ubx_factorydef));
delay(100);
Serial2.write(ubx_hardreset, sizeof(ubx_hardreset));
//delay(5000);
delay(5000);
SPIFFS.remove("/GPSRESET");
} else if (testfile) {
Serial.println("GPS reset file: not found/isdir");
testfile.close();
Serial2.begin(9600, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
}
// Enable GPGST messages
Serial2.write(ubx_enable_gpgst, sizeof(ubx_enable_gpgst));
} else {
Serial2.begin(9600, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
}
@ -1369,6 +1398,12 @@ void initGPS() {
NULL); /* task handle*/
}
const char *getStateStr(int what) {
if(what<0 || what>=(sizeof(mainStateStr)/sizeof(const char *)))
return "--";
else
return mainStateStr[what];
}
void sx1278Task(void *parameter) {
/* new strategy:
@ -1384,13 +1419,12 @@ void sx1278Task(void *parameter) {
while (1) {
if (rxtask.activate >= 128) {
// activating sx1278 background task...
Serial.printf("rx task: activate=%d mainstate=%d\n", rxtask.activate, rxtask.mainState);
Serial.printf("RXtask: start DECODER for sonde %d (was %s)\n", rxtask.activate&0x7f, getStateStr(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);
Serial.printf("RXtask: start %s (was %s)\n", getStateStr(rxtask.activate), getStateStr(rxtask.mainState));
rxtask.mainState = rxtask.activate;
}
rxtask.activate = -1;
@ -1784,7 +1818,7 @@ void setup()
sonde.clearDisplay();
setupWifiList();
Serial.printf("before disp.initFromFile... layouts is %p", disp.layouts);
Serial.printf("before disp.initFromFile... layouts is %p\n", disp.layouts);
disp.initFromFile(sonde.config.screenfile);
Serial.printf("disp.initFromFile... layouts is %p", disp.layouts);
@ -1958,10 +1992,18 @@ void parseGpsJson(char *data) {
// get value
double val = strtod(value, NULL);
// get data
if(strncmp(key,"lat",3)==0) { gpsPos.lat = val; }
else if(strncmp(key,"lon",3)==0) { gpsPos.lon = val; }
else if(strncmp(key,"alt",3)==0) { gpsPos.alt = (int)val; }
else if(strncmp(key,"course",6)==0) { gpsPos.course = (int)val; }
if (strncmp(key, "lat", 3) == 0) {
gpsPos.lat = val;
}
else if (strncmp(key, "lon", 3) == 0) {
gpsPos.lon = val;
}
else if (strncmp(key, "alt", 3) == 0) {
gpsPos.alt = (int)val;
}
else if (strncmp(key, "course", 6) == 0) {
gpsPos.course = (int)val;
}
gpsPos.valid = true;
// next item:
@ -1985,9 +2027,9 @@ void loopDecoder() {
// TODO: update displayed sonde?
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);
int newact = sonde.updateState(action);
Serial.printf("MAIN: loopDecoder: action %s (%d) => %d [current: main=%d, rxtask=%d]\n", action2text(action), action, newact, sonde.currentSonde, rxtask.currentSonde);
action = newact;
if (action != 255) {
if (action == ACT_DISPLAY_SPECTRUM) {
enterMode(ST_SPECTRUM);
@ -1997,10 +2039,7 @@ void loopDecoder() {
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 (!tncclient.connected()) {
@ -2017,20 +2056,11 @@ void loopDecoder() {
}
Serial.println("");
}
#if 0
if (!rdzclient.connected()) {
rdzclient = rdzserver.available();
if(rdzclient.connected()) {
Serial.println("RDZ JSON socket: new connection");
}
}
#else
if (rdzserver.hasClient()) {
Serial.println("TCP JSON socket: new connection");
if (rdzclient) rdzclient.stop();
rdzclient = rdzserver.available();
}
#endif
if (rdzclient.available()) {
Serial.print("RDZ JSON socket: received ");
while (rdzclient.available()) {
@ -2080,16 +2110,26 @@ void loopDecoder() {
Serial.println("Sending sonde info via MQTT");
mqttclient.publishPacket(s);
}
// also send to web socket
//TODO
}
// always send data, even if not valid....
if (rdzclient.connected()) {
Serial.println("Sending position via TCP as rdzJSON");
char raw[1024];
char gps[128];
const char *typestr = s->typestr;
if (*typestr == 0) typestr = sondeTypeStr[s->type];
// TODO: only if GPS is valid...
if (gpsPos.valid) {
snprintf(gps, 128, ", \"gpslat\": %f"
"\"gpslon\": %f,"
"\"gpsalt\": %d,"
"\"gpsacc\": %d,"
"\"gpsdir\": %d",
gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.accuracy, gpsPos.course);
} else {
*gps = 0;
}
//
int len = snprintf(raw, 1024, "{"
"\"res\": %d,"
"\"type\": \"%s\","
@ -2117,6 +2157,7 @@ void loopDecoder() {
"\"burstKT\": %d,"
"\"countKT\": %d,"
"\"crefKT\": %d"
"%s"
"}\n",
res & 0xff,
typestr,
@ -2143,7 +2184,8 @@ void loopDecoder() {
s->launchKT,
s->burstKT,
s->countKT,
s->crefKT
s->crefKT,
gps
);
//Serial.println("Writing rdzclient...");
if (len > 1024) len = 1024;
@ -2155,7 +2197,7 @@ void loopDecoder() {
}
//Serial.println("Writing rdzclient OK");
}
Serial.print("updateDisplay started... ");
Serial.print("MAIN: updateDisplay started\n");
if (forceReloadScreenConfig) {
disp.initFromFile(sonde.config.screenfile);
sonde.clearDisplay();
@ -2163,7 +2205,7 @@ void loopDecoder() {
}
int t = millis();
sonde.updateDisplay();
Serial.printf("updateDisplay done (after %d ms)\n", (int)(millis() - t));
Serial.printf("MAIN: updateDisplay done (after %d ms)\n", (int)(millis() - t));
}
void setCurrentDisplay(int value) {
@ -2540,19 +2582,12 @@ void loopWifiScan() {
int index = -1;
int n = WiFi.scanNetworks();
for (int i = 0; i < n; i++) {
Serial.print("Network name: ");
String ssid = WiFi.SSID(i);
Serial.println(ssid);
disp.rdis->drawString(0, dispys * (1 + line), ssid.c_str());
line = (line + 1) % (disph / dispys);
Serial.print("Signal strength: ");
Serial.println(WiFi.RSSI(i));
Serial.print("MAC address: ");
Serial.println(WiFi.BSSIDstr(i));
Serial.print("Encryption type: ");
String mac = WiFi.BSSIDstr(i);
String encryptionTypeDescription = translateEncryptionType(WiFi.encryptionType(i));
Serial.println(encryptionTypeDescription);
Serial.println("-----------------------");
Serial.printf("Network %s: RSSI %d, MAC %s, enc: %s\n", ssid.c_str(), WiFi.RSSI(i), mac.c_str(), encryptionTypeDescription.c_str());
int curidx = fetchWifiIndex(ssid.c_str());
if (curidx >= 0 && index == -1) {
index = curidx;
@ -2790,8 +2825,8 @@ void execOTA() {
void loop() {
Serial.printf("\nRunning main loop in state %d [currentDisp:%d, lastDiso:%d]. free heap: %d;\n",
mainState, currentDisplay, lastDisplay, ESP.getFreeHeap());
Serial.printf("\nMAIN: Running loop in state %d [currentDisp:%d, lastDisp:%d]. free heap: %d, unused stack: %d\n",
mainState, currentDisplay, lastDisplay, ESP.getFreeHeap(), uxTaskGetStackHighWaterMark(0));
switch (mainState) {
case ST_DECODER:
#ifndef DISABLE_MAINRX
@ -2828,5 +2863,4 @@ void loop() {
lastMqttUptime = now;
}
Serial.printf("Unused stack: %d\n", uxTaskGetStackHighWaterMark(0));
}

View File

@ -113,7 +113,7 @@ tcp.idformat=0
# data not sanitized / quality checked, outliers not filtered out
mqtt.active=0
mqtt.id=rdz_sonde_server
mqtt.ip=
mqtt.host=
mqtt.port=1883
mqtt.username=
mqtt.password=

View File

@ -1,4 +1,4 @@
const char *version_name = "rdzTTGOsonde";
const char *version_id = "devel20210302";
const char *version_id = "devel20210314";
const int SPIFFS_MAJOR=2;
const int SPIFFS_MINOR=10;

View File

@ -339,6 +339,7 @@ static int ngfx = sizeof(gfl)/sizeof(GFXfont *);
void ILI9225Display::begin() {
tft = new MY_ILI9225(sonde.config.oled_rst, sonde.config.tft_rs, sonde.config.tft_cs,
sonde.config.oled_sda, sonde.config.oled_scl, TFT_LED, TFT_BRIGHTNESS);
tft->setModeFlip(sonde.config.tft_modeflip);
tft->begin(spiDisp);
tft->setOrientation(sonde.config.tft_orient);
}
@ -665,7 +666,7 @@ int Display::allocDispInfo(int entries, DispInfo *d, char *label)
d->timeouts = (int16_t *)mem;
d->label = label;
Serial.printf("allocated %d bytes (%d entries) for %p (addr=%p)\n", totalsize, entries, d, d->de);
Serial.printf("%s: alloc %d bytes (%d entries) for %p (addr=%p)\n", label, totalsize, entries, d, d->de);
return 0;
}
@ -726,7 +727,7 @@ void Display::parseDispElement(char *text, DispEntry *de)
case 'f':
de->func = disp.drawFreq;
de->extra = strdup(text+1);
Serial.printf("parsing 'f' entry: extra is '%s'\n", de->extra);
//Serial.printf("parsing 'f' entry: extra is '%s'\n", de->extra);
break;
case 'n':
// IP address / small always uses tiny font on TFT for backward compatibility
@ -780,7 +781,7 @@ void Display::parseDispElement(char *text, DispEntry *de)
de->extra = (char *)circinfo;
} else {
de->extra = strdup(text+1);
Serial.printf("parsing 'g' entry: extra is '%s'\n", de->extra);
//Serial.printf("parsing 'g' entry: extra is '%s'\n", de->extra);
}
break;
case 'r':
@ -848,7 +849,7 @@ void Display::initFromFile(int index) {
if(index>0) {
char file[20];
snprintf(file, 20, "/screens%d.txt", index);
Serial.printf("Trying %i (%s)\n", index, file);
Serial.printf("Reading %s\n", file);
d = SPIFFS.open(file, "r");
if(!d || d.available()==0 ) { Serial.printf("%s not found, using /screens.txt\n", file); }
}
@ -888,6 +889,7 @@ void Display::initFromFile(int index) {
case -1: // wait for start of screen (@)
{
if(*s != '@') {
if(*s==0 || *s==10 || *s==13) continue;
Serial.printf("Illegal start of screen: %s\n", s);
continue;
}
@ -896,7 +898,6 @@ void Display::initFromFile(int index) {
DebugPrintf(DEBUG_SPARSER,"Reading entry with %d elements\n", entrysize);
idx++;
int res = allocDispInfo(entrysize, &newlayouts[idx], label);
Serial.printf("allocDispInfo: idx %d: label is %p - %s\n",idx,newlayouts[idx].label, newlayouts[idx].label);
if(res<0) {
Serial.println("Error allocating memory for disp info");
continue;
@ -917,7 +918,7 @@ void Display::initFromFile(int index) {
if(newlayouts[idx].timeouts[1]>0) newlayouts[idx].timeouts[1]*=1000;
if(newlayouts[idx].timeouts[2]>0) newlayouts[idx].timeouts[2]*=1000;
//sscanf(s+6, "%hd,%hd,%hd", newlayouts[idx].timeouts, newlayouts[idx].timeouts+1, newlayouts[idx].timeouts+2);
Serial.printf("timer values: %d, %d, %d\n", newlayouts[idx].timeouts[0], newlayouts[idx].timeouts[1], newlayouts[idx].timeouts[2]);
//Serial.printf("timer values: %d, %d, %d\n", newlayouts[idx].timeouts[0], newlayouts[idx].timeouts[1], newlayouts[idx].timeouts[2]);
} else if(strncmp(s, "key1action=",11)==0) { // key 1 actions
char c1,c2,c3,c4;
sscanf(s+11, "%c,%c,%c,%c", &c1, &c2, &c3, &c4);
@ -932,7 +933,7 @@ void Display::initFromFile(int index) {
newlayouts[idx].actions[6] = ACTION(c2);
newlayouts[idx].actions[7] = ACTION(c3);
newlayouts[idx].actions[8] = ACTION(c4);
Serial.printf("parsing key2action: %c %c %c %c\n", c1, c2, c3, c4);
//Serial.printf("parsing key2action: %c %c %c %c\n", c1, c2, c3, c4);
} else if(strncmp(s, "timeaction=",11)==0) { // timer actions
char c1,c2,c3;
sscanf(s+11, "%c,%c,%c", &c1, &c2, &c3);

View File

@ -15,6 +15,7 @@ struct GpsPos {
double lon;
int alt;
int course;
int accuracy;
int valid;
};
extern struct GpsPos gpsPos;

View File

@ -135,8 +135,10 @@ int RS41::setup(float frequency)
RS41_DBG(Serial.println("Setting Packet config FAILED"));
return 1;
}
#if RS41_DEBUG
Serial.print("RS41: setting RX frequency to ");
Serial.println(frequency);
#endif
int retval = sx1278.setFrequency(frequency);
dpos = 0;
@ -524,7 +526,7 @@ 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);
if(e) { Serial.println("TIMEOUT"); return RX_TIMEOUT; }
if(e) { /*Serial.println("TIMEOUT");*/ return RX_TIMEOUT; }
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]; }

View File

@ -448,7 +448,7 @@ void Sonde::setup() {
}
// update receiver config
Serial.print("\nSonde::setup() on sonde index ");
Serial.print("Sonde.setup() on sonde index ");
Serial.println(rxtask.currentSonde);
switch(sondeList[rxtask.currentSonde].type) {
case STYPE_RS41:
@ -468,9 +468,10 @@ void Sonde::setup() {
break;
}
// debug
float afcbw = sx1278.getAFCBandwidth();
float rxbw = sx1278.getRxBandwidth();
Serial.printf("AFC BW: %f RX BW: %f\n", afcbw, rxbw);
int freq = (int)sx1278.getFrequency();
int afcbw = (int)sx1278.getAFCBandwidth();
int rxbw = (int)sx1278.getRxBandwidth();
Serial.printf("Sonde.setup(): Freq %d, AFC BW: %d, RX BW: %d\n", freq, afcbw, rxbw);
// reset rxtimer / norxtimer state
sonde.sondeList[sonde.currentSonde].lastState = -1;
@ -508,7 +509,7 @@ void Sonde::receive() {
}
} else { // RX not ok
if(res==RX_ERROR) flashLed(100);
Serial.printf("RX result %d, laststate was %d\n", res, si->lastState);
Serial.printf("RX result %d (%s), laststate was %d\n", res, (res<=3)?RXstr[res]:"?", si->lastState);
if(si->lastState != 0) {
si->norxStart = millis();
si->lastState = 0;
@ -524,7 +525,7 @@ void Sonde::receive() {
int event = getKeyPressEvent();
if (!event) event = timeoutEvent(si);
int action = (event==EVT_NONE) ? ACT_NONE : disp.layout->actions[event];
if(action!=ACT_NONE) { 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...)
@ -546,7 +547,7 @@ void Sonde::receive() {
}
}
res = (action<<8) | (res&0xff);
Serial.printf("receive(): Result is %04x (action %d, res %d)\n", res, action, res&0xff);
Serial.printf("Sonde:receive(): Event %02x: action %02x, res %02x => %04x\n", event, action, res&0xff, res);
// let waitRXcomplete resume...
rxtask.receiveResult = res;
}
@ -602,22 +603,22 @@ rxloop:
uint8_t Sonde::timeoutEvent(SondeInfo *si) {
uint32_t now = millis();
#if 1
#if 0
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], si->lastState);
#endif
if(disp.layout->timeouts[0]>=0 && now - si->viewStart >= disp.layout->timeouts[0]) {
Serial.println("View timer expired");
Serial.println("Sonde.timeoutEvent: View");
return EVT_VIEWTO;
}
if(si->lastState==1 && disp.layout->timeouts[1]>=0 && now - si->rxStart >= disp.layout->timeouts[1]) {
Serial.println("RX timer expired");
Serial.println("Sonde.timeoutEvent: RX");
return EVT_RXTO;
}
if(si->lastState==0 && disp.layout->timeouts[2]>=0 && now - si->norxStart >= disp.layout->timeouts[2]) {
Serial.println("NORX timer expired");
Serial.println("Sonde.timeoutEvent: NORX");
return EVT_NORXTO;
}
return 0;

View File

@ -198,6 +198,7 @@ TFT22_ILI9225::TFT22_ILI9225(int8_t rst, int8_t rs, int8_t cs, int8_t sdi, int8_
hwSPI = false;
writeFunctionLevel = 0;
gfxFont = NULL;
_modeFlip = 0;
}
// Constructor when using software SPI. All output pins are configurable. Adds backlight brightness 0-255
@ -212,6 +213,7 @@ TFT22_ILI9225::TFT22_ILI9225(int8_t rst, int8_t rs, int8_t cs, int8_t sdi, int8_
hwSPI = false;
writeFunctionLevel = 0;
gfxFont = NULL;
_modeFlip = 0;
}
// Constructor when using hardware SPI. Faster, but must use SPI pins
@ -226,6 +228,7 @@ TFT22_ILI9225::TFT22_ILI9225(int8_t rst, int8_t rs, int8_t cs, int8_t led) {
hwSPI = true;
writeFunctionLevel = 0;
gfxFont = NULL;
_modeFlip = 0;
}
// Constructor when using hardware SPI. Faster, but must use SPI pins
@ -241,6 +244,7 @@ TFT22_ILI9225::TFT22_ILI9225(int8_t rst, int8_t rs, int8_t cs, int8_t led, uint8
hwSPI = true;
writeFunctionLevel = 0;
gfxFont = NULL;
_modeFlip = 0;
}
@ -584,7 +588,7 @@ void TFT22_ILI9225::setDisplay(boolean flag) {
}
}
void TFT22_ILI9225::setModeFlip(uint8_t m) {
void TFT22_ILI9225::setModeFlip(uint16_t m) {
_modeFlip = m;
}

View File

@ -393,7 +393,7 @@ class TFT22_ILI9225 {
void getGFXCharExtent(uint8_t c, int16_t *gw, int16_t *gh, int16_t *xa);
void setModeFlip(uint8_t m);
void setModeFlip(uint16_t m);
private:
@ -438,7 +438,8 @@ class TFT22_ILI9225 {
int8_t _rst, _rs, _cs, _sdi, _clk, _led;
#endif
uint8_t _orientation, _brightness, _modeflip;
uint8_t _orientation, _brightness;
uint16_t _modeFlip;
// correspondig modes if orientation changed:
const autoIncMode_t modeTab [3][8] = {