(sync with master)

some code reorganization, preliminary SD card code (not active)
APRS timeout added
pmu
Hansi, dl9rdz 2023-07-09 12:10:53 +02:00
rodzic 27d342ae0e
commit deec0d362f
30 zmienionych plików z 1169 dodań i 2590 usunięć

Wyświetl plik

@ -9,7 +9,6 @@
#include <SPI.h>
#include <Update.h>
#include <ESPmDNS.h>
#include <MicroNMEA.h>
#include <Ticker.h>
#include "esp_heap_caps.h"
#include "soc/rtc_wdt.h"
@ -18,22 +17,29 @@
#include "src/Sonde.h"
#include "src/Display.h"
#include "src/Scanner.h"
#include "src/geteph.h"
#if FEATURE_RS92
#include "src/geteph.h"
#include "src/rs92gps.h"
#endif
#include "src/aprs.h"
// Not needed here, included by connector #include "src/aprs.h"
#include "src/ShFreqImport.h"
#include "src/RS41.h"
#include "src/DFM.h"
#include "src/json.h"
#if FEATURE_CHASEMAPPER
#include "src/Chasemapper.h"
#endif
//#include "NimBLEDevice.h"
#include "src/posinfo.h"
/* Data exchange connectors */
#if FEATURE_CHASEMAPPER
#include "src/conn-chasemapper.h"
#endif
#if FEATURE_MQTT
#include "src/mqtt.h"
#include "src/conn-mqtt.h"
#endif
#if FEATURE_SDCARD
#include "src/conn-sdcard.h"
#endif
#if FEATURE_APRS
#include "src/conn-aprs.h"
#endif
//#define ESP_MEM_DEBUG 1
@ -72,24 +78,6 @@ WiFiClient client;
/* Sonde.h: enum SondeType { STYPE_DFM,, STYPE_RS41, STYPE_RS92, STYPE_M10M20, STYPE_M10, STYPE_M20, STYPE_MP3H }; */
const char *sondeTypeStrSH[NSondeTypes] = { "DFM", "RS41", "RS92", "Mxx"/*never sent*/, "M10", "M20", "MRZ" };
#if 0
// not used any more
const char *dfmSubtypeStrSH[16] = { NULL, NULL, NULL, NULL, NULL, NULL,
"DFM06", // 0x06
"PS15", // 0x07
NULL, NULL,
"DFM09", // 0x0A
"DFM17", // 0x0B
"DFM09P", // 0x0C
"DFM17", // 0x0D
NULL, NULL
};
#endif
// Times in ms, i.e. station: 10 minutes, mobile: 20 seconds
#define APRS_STATION_UPDATE_TIME (10*60*1000)
#define APRS_MOBILE_STATION_UPDATE_TIME (20*1000)
unsigned long time_last_aprs_update = -APRS_STATION_UPDATE_TIME;
#if FEATURE_SONDEHUB
#define SONDEHUB_STATION_UPDATE_TIME (60*60*1000) // 60 min
@ -99,34 +87,15 @@ int shImportInterval = 0;
char shImport = 0;
unsigned long time_last_update = 0;
#endif
/* SH_LOC_OFF: never send position information to SondeHub
SH_LOC_FIXED: send fixed position (if specified in config) to sondehub
SH_LOC_CHASE: always activate chase mode and send GPS position (if available)
SH_LOC_AUTO: if there is no valid GPS position, or GPS position < MIN_LOC_AUTO_DIST away from known fixed position: use FIXED mode
otherwise, i.e. if there is a valid GPS position and (either no fixed position in config, or GPS position is far away from fixed position), use CHASE mode.
*/
// same constants used for SondeHub and APRS
enum { SH_LOC_OFF, SH_LOC_FIXED, SH_LOC_CHASE, SH_LOC_AUTO };
/* auto mode is chase if valid GPS position and (no fixed location entered OR valid GPS position and distance in lat/lon deg to fixed location > threshold) */
#define MIN_LOC_AUTO_DIST 200 /* meter */
#define SH_LOC_AUTO_IS_CHASE ( gpsPos.valid && ( (isnan(sonde.config.rxlat) || isnan(sonde.config.rxlon) ) || \
calcLatLonDist( gpsPos.lat, gpsPos.lon, sonde.config.rxlat, sonde.config.rxlon ) > MIN_LOC_AUTO_DIST ) )
extern float calcLatLonDist(float lat1, float lon1, float lat2, float lon2);
// KISS over TCP for communicating with APRSdroid
WiFiServer tncserver(14580);
WiFiClient tncclient;
// JSON over TCP for communicating with the rdzSonde (rdzwx-go) Android app
WiFiServer rdzserver(14570);
WiFiClient rdzclient;
// APRS over TCP for radiosondy.info etc
AsyncClient tcpclient;
#if FEATURE_MQTT
unsigned long lastMqttUptime = 0;
boolean mqttEnabled;
MQTT mqttclient;
#endif
boolean forceReloadScreenConfig = false;
enum KeyPress { KP_NONE = 0, KP_SHORT, KP_DOUBLE, KP_MID, KP_LONG };
@ -153,8 +122,7 @@ static unsigned long specTimer;
void enterMode(int mode);
void WiFiEvent(WiFiEvent_t event);
char buffer[85];
MicroNMEA nmea(buffer, sizeof(buffer));
// Read line from file, independent of line termination (LF or CR LF)
String readLine(Stream &stream) {
@ -183,6 +151,7 @@ int readLine(Stream &stream, char *buffer, int maxlen) {
String processor(const String& var) {
Serial.println(var);
if (var == "MAPCENTER") {
#if 0
double lat, lon;
if (gpsPos.valid) {
lat = gpsPos.lat;
@ -193,8 +162,10 @@ String processor(const String& var) {
lon = sonde.config.rxlon;
}
if ( !isnan(lat) && !isnan(lon) ) {
#endif
if ( posInfo.valid ) {
char p[40];
snprintf(p, 40, "%g,%g", lat, lon);
snprintf(p, 40, "%g,%g", posInfo.lat, posInfo.lon);
return String(p);
} else {
return String("48,13");
@ -225,7 +196,11 @@ String processor(const String& var) {
return String(tmpstr);
}
if (var == "EPHSTATE") {
#if FEATURE_RS92
return String(ephtxt[ephstate]);
#else
return String("Not supported");
#endif
}
return String();
}
@ -250,7 +225,7 @@ const String sondeTypeSelect(int activeType) {
//trying to work around
//"assertion "heap != NULL && "free() target pointer is outside heap areas"" failed:"
// which happens if request->send is called in createQRGForm!?!??
char message[10240 * 4-2048]; //needs to be large enough for all forms (not checked in code)
char message[10240 * 3 - 2048]; //needs to be large enough for all forms (not checked in code)
// QRG form is currently about 24kb with 100 entries
///////////////////////// Functions for Reading / Writing QRG list from/to qrg.txt
@ -317,7 +292,7 @@ void HTMLBODYEND(char *ptr) {
}
void HTMLSAVEBUTTON(char *ptr) {
strcat(ptr, "</div><div class=\"footer\"><input type=\"submit\" class=\"save\" value=\"Save changes\"/>"
"<span class=\"ttgoinfo\">rdzTTGOserver ");
"<span class=\"ttgoinfo\">rdzTTGOserver ");
strcat(ptr, version_id);
strcat(ptr, "</span>");
}
@ -451,7 +426,7 @@ const char *createWIFIForm() {
}
#if 0
// moved to map.html (active warning is still TODO
// moved to map.html (active warning is still TODO
const char *createSondeHubMap() {
SondeInfo *s = &sonde.sondeList[0];
char *ptr = message;
@ -557,7 +532,7 @@ const char *createStatusForm() {
}
}
strcat(ptr, "</div><div class=\"footer\"><span></span>"
"<span class=\"ttgoinfo\">rdzTTGOserver ");
"<span class=\"ttgoinfo\">rdzTTGOserver ");
strcat(ptr, version_id);
strcat(ptr, "</span>");
@ -572,7 +547,7 @@ const char *createLiveJson() {
strcpy(ptr, "{\"sonde\": {");
// use the same JSON format here as for MQTT and for the Android App
sonde2json( ptr+strlen(ptr), 1024, s );
sonde2json( ptr + strlen(ptr), 1024, s );
#if 0
sprintf(ptr + strlen(ptr), "\"sonde\": {\"rssi\": %d, \"vframe\": %d, \"time\": %d,\"id\": \"%s\", \"freq\": %3.3f, \"type\": \"%s\"",
s->rssi, s->d.vframe, s->d.time, s->d.id, s->freq, sondeTypeStr[sonde.realType(s)]);
@ -591,15 +566,10 @@ const char *createLiveJson() {
sprintf(ptr + strlen(ptr), ", \"launchsite\": \"%s\", \"res\": %d }", s->launchsite, s->rxStat[0]);
#endif
strcat(ptr, " }");
if (gpsPos.valid) {
sprintf(ptr + strlen(ptr), ", \"gps\": {\"lat\": %g, \"lon\": %g, \"alt\": %d, \"sat\": %d, \"speed\": %g, \"dir\": %d, \"hdop\": %d }", gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.sat, gpsPos.speed, gpsPos.course, gpsPos.hdop);
if (posInfo.valid) {
sprintf(ptr + strlen(ptr), ", \"gps\": {\"lat\": %g, \"lon\": %g, \"alt\": %d, \"sat\": %d, \"speed\": %g, \"dir\": %d, \"hdop\": %d }", posInfo.lat, posInfo.lon, posInfo.alt, posInfo.sat, posInfo.speed, posInfo.course, posInfo.hdop);
//}
} else {
// no GPS position, but maybe a fixed position
if ((!isnan(sonde.config.rxlat)) && (!isnan(sonde.config.rxlon))) {
int alt = isnan(sonde.config.rxalt) ? 0 : (int)sonde.config.rxalt;
sprintf(ptr + strlen(ptr), ", \"gps\": {\"lat\": %g, \"lon\": %g, \"alt\": %d, \"sat\": 0, \"speed\": 0, \"dir\": 0, \"hdop\": 0 }", sonde.config.rxlat, sonde.config.rxlon, alt);
}
}
strcat(ptr, "}");
@ -661,13 +631,15 @@ struct st_configitems config_list[] = {
{"passcode", 0, &sonde.config.passcode},
/* KISS tnc settings */
{"kisstnc.active", 0, &sonde.config.kisstnc.active},
#if FEATURE_APRS
/* AXUDP settings */
{"axudp.active", -3, &sonde.config.udpfeed.active},
{"axudp.host", 63, sonde.config.udpfeed.host},
{"axudp.port", 0, &sonde.config.udpfeed.port},
{"axudp.highrate", 0, &sonde.config.udpfeed.highrate},
/* APRS TCP settings, current not used */
/* APRS TCP settings */
{"tcp.active", -3, &sonde.config.tcpfeed.active},
{"tcp.timeout", 0, &sonde.config.tcpfeed.timeout},
{"tcp.host", 63, sonde.config.tcpfeed.host},
{"tcp.port", 0, &sonde.config.tcpfeed.port},
{"tcp.chase", 0, &sonde.config.chase},
@ -675,6 +647,7 @@ struct st_configitems config_list[] = {
{"tcp.objcall", 9, sonde.config.objcall},
{"tcp.beaconsym", 4, sonde.config.beaconsym},
{"tcp.highrate", 0, &sonde.config.tcpfeed.highrate},
#endif
#if FEATURE_CHASEMAPPER
/* Chasemapper settings */
{"cm.active", -3, &sonde.config.cm.active},
@ -865,7 +838,7 @@ const char *createControlForm() {
}
}
strcat(ptr, "</div><div class=\"footer\"><span></span>"
"<span class=\"ttgoinfo\">rdzTTGOserver ");
"<span class=\"ttgoinfo\">rdzTTGOserver ");
strcat(ptr, version_id);
strcat(ptr, "</span>");
HTMLBODYEND(ptr);
@ -1209,13 +1182,13 @@ void SetupAsyncServer() {
});
// server.on("/map.html", HTTP_GET, [](AsyncWebServerRequest * request) {
// request->send(200, "text/html", createSondeHubMap());
// });
// server.on("/map.html", HTTP_POST, [](AsyncWebServerRequest * request) {
// handleWIFIPost(request);
// request->send(200, "text/html", createSondeHubMap());
// });
// server.on("/map.html", HTTP_GET, [](AsyncWebServerRequest * request) {
// request->send(200, "text/html", createSondeHubMap());
// });
// server.on("/map.html", HTTP_POST, [](AsyncWebServerRequest * request) {
// handleWIFIPost(request);
// request->send(200, "text/html", createSondeHubMap());
// });
server.on("/config.html", HTTP_GET, [](AsyncWebServerRequest * request) {
request->send(200, "text/html", createConfigForm());
@ -1434,167 +1407,6 @@ void initTouch() {
/// Arrg. MicroNMEA changes type definition... so lets auto-infer type
template<typename T>
//void unkHandler(const MicroNMEA& nmea) {
void unkHandler(T nmea) {
if (strcmp(nmea.getMessageID(), "VTG") == 0) {
const char *s = nmea.getSentence();
while (*s && *s != ',') s++;
if (*s == ',') s++; else return;
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;
}
}
//#define DEBUG_GPS
static bool gpsCourseOld;
static int lastCourse;
void gpsTask(void *parameter) {
nmea.setUnknownSentenceHandler(unkHandler);
while (1) {
while (Serial2.available()) {
char c = Serial2.read();
//Serial.print(c);
if (nmea.process(c)) {
gpsPos.valid = nmea.isValid();
if (gpsPos.valid) {
gpsPos.lon = nmea.getLongitude() * 0.000001;
gpsPos.lat = nmea.getLatitude() * 0.000001;
long alt = 0;
nmea.getAltitude(alt);
gpsPos.alt = (int)(alt / 1000);
gpsPos.course = (int)(nmea.getCourse() / 1000);
gpsCourseOld = false;
if (gpsPos.course == 0) {
// either north or not new
if (lastCourse != 0) // use old value...
{
gpsCourseOld = true;
gpsPos.course = lastCourse;
}
}
if(gpsPos.lon == 0 && gpsPos.lat == 0) gpsPos.valid = false;
}
gpsPos.hdop = nmea.getHDOP();
gpsPos.sat = nmea.getNumSatellites();
gpsPos.speed = nmea.getSpeed() / 1000.0 * 0.514444; // speed is in m/s nmea.getSpeed is in 0.001 knots
#ifdef DEBUG_GPS
uint8_t hdop = nmea.getHDOP();
Serial.printf(" =>: valid: %d N %f E %f alt %d course:%d dop:%d\n", gpsPos.valid ? 1 : 0, gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.course, hdop);
#endif
}
}
delay(50);
}
}
#define UBX_SYNCH_1 0xB5
#define UBX_SYNCH_2 0x62
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, 0xff, 0xff, 0xff, 0xff, 0xff, 0x13, 0x7c };
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 dumpGPS() {
while (Serial2.available()) {
char c = Serial2.read();
Serial.printf("%02x ", (uint8_t)c);
}
}
void initGPS() {
if (sonde.config.gps_rxd < 0) return; // GPS disabled
if (sonde.config.gps_txd >= 0) { // TX enable, thus try setting baud to 9600 and do a factory reset
File testfile = SPIFFS.open("/GPSRESET", FILE_READ);
if (testfile && !testfile.isDirectory()) {
testfile.close();
Serial.println("GPS resetting baud to 9k6...");
/* TODO: debug:
Sometimes I have seen the Serial2.begin to cause a reset
Guru Meditation Error: Core 1 panic'ed (Interrupt wdt timeout on CPU1)
Backtrace: 0x40081d2f:0x3ffc11b0 0x40087969:0x3ffc11e0 0x4000bfed:0x3ffb1db0 0x4008b7dd:0x3ffb1dc0 0x4017afee:0x3ffb1de0 0x4017b04b:0x3ffb1e20 0x4010722b:0x3ffb1e50 0x40107303:0x3ffb1e70 0x4010782d:0x3ffb1e90 0x40103814:0x3ffb1ed0 0x400d8772:0x3ffb1f10 0x400d9057:0x3ffb1f60 0x40107aca:0x3ffb1fb0 0x4008a63e:0x3ffb1fd0
#0 0x40081d2f:0x3ffc11b0 in _uart_isr at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/esp32-hal-uart.c:464
#1 0x40087969:0x3ffc11e0 in _xt_lowint1 at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/xtensa_vectors.S:1154
#2 0x4000bfed:0x3ffb1db0 in ?? ??:0
#3 0x4008b7dd:0x3ffb1dc0 in vTaskExitCritical at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/tasks.c:3507
#4 0x4017afee:0x3ffb1de0 in esp_intr_alloc_intrstatus at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/esp32/intr_alloc.c:784
#5 0x4017b04b:0x3ffb1e20 in esp_intr_alloc at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/esp32/intr_alloc.c:784
#6 0x4010722b:0x3ffb1e50 in uartEnableInterrupt at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/esp32-hal-uart.c:464
#7 0x40107303:0x3ffb1e70 in uartAttachRx at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/esp32-hal-uart.c:464
#8 0x4010782d:0x3ffb1e90 in uartBegin at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/esp32-hal-uart.c:464
#9 0x40103814:0x3ffb1ed0 in HardwareSerial::begin(unsigned long, unsigned int, signed char, signed char, bool, unsigned long) at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/HardwareSerial.cpp:190
*/
Serial2.begin(115200, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
delay(200);
Serial2.begin(38400, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
delay(200);
Serial2.begin(19200, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
Serial2.begin(9600, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
delay(1000);
dumpGPS();
Serial.println("GPS factory reset...");
Serial2.write(ubx_factorydef, sizeof(ubx_factorydef));
delay(1000);
dumpGPS();
delay(1000);
dumpGPS();
delay(1000);
dumpGPS();
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);
}
xTaskCreate( gpsTask, "gpsTask",
5000, /* stack size */
NULL, /* paramter */
1, /* priority */
NULL); /* task handle*/
}
const char *getStateStr(int what) {
if (what < 0 || what >= (sizeof(mainStateStr) / sizeof(const char *)))
return "--";
@ -1909,7 +1721,6 @@ void setup()
}
Serial.println(" (before setup)");
sonde.defaultConfig(); // including autoconfiguration
aprs_gencrctab();
Serial.println("Initializing SPIFFS");
// Initialize SPIFFS
@ -1944,33 +1755,33 @@ void setup()
// Display backlight on M5 Core2
axp.setPowerOutPut(AXP192_DCDC3, AXP202_ON);
axp.setDCDC3Voltage(3300);
// SetBusPowerMode(0):
// #define AXP192_GPIO0_CTL (0x90)
// #define AXP192_GPIO0_VOL (0x91)
// #define AXP202_LDO234_DC23_CTL (0x12)
// SetBusPowerMode(0):
// #define AXP192_GPIO0_CTL (0x90)
// #define AXP192_GPIO0_VOL (0x91)
// #define AXP202_LDO234_DC23_CTL (0x12)
// The axp class lacks a functino to set GPIO0 VDO to 3.3V (as is done by original M5Stack software)
// so do this manually (default value 2.8V did not have the expected effect :))
// data = Read8bit(0x91);
// The axp class lacks a functino to set GPIO0 VDO to 3.3V (as is done by original M5Stack software)
// so do this manually (default value 2.8V did not have the expected effect :))
// data = Read8bit(0x91);
// write1Byte(0x91, (data & 0X0F) | 0XF0);
uint8_t reg;
Wire.beginTransmission((uint8_t)AXP192_SLAVE_ADDRESS);
Wire.write(AXP192_GPIO0_VOL);
Wire.endTransmission();
Wire.requestFrom(AXP192_SLAVE_ADDRESS, 1);
reg = Wire.read();
reg = (reg&0x0F) | 0xF0;
Wire.beginTransmission((uint8_t)AXP192_SLAVE_ADDRESS);
Wire.write(AXP192_GPIO0_VOL);
Wire.write(reg);
Wire.endTransmission();
// data = Read8bit(0x90);
uint8_t reg;
Wire.beginTransmission((uint8_t)AXP192_SLAVE_ADDRESS);
Wire.write(AXP192_GPIO0_VOL);
Wire.endTransmission();
Wire.requestFrom(AXP192_SLAVE_ADDRESS, 1);
reg = Wire.read();
reg = (reg & 0x0F) | 0xF0;
Wire.beginTransmission((uint8_t)AXP192_SLAVE_ADDRESS);
Wire.write(AXP192_GPIO0_VOL);
Wire.write(reg);
Wire.endTransmission();
// data = Read8bit(0x90);
// Write1Byte(0x90, (data & 0XF8) | 0X02)
axp.setGPIOMode(AXP_GPIO_0, AXP_IO_LDO_MODE); // disable AXP supply from VBUS
axp.setGPIOMode(AXP_GPIO_0, AXP_IO_LDO_MODE); // disable AXP supply from VBUS
pmu_irq = 2; // IRQ pin is not connected on Core2
// data = Read8bit(0x12); //read reg 0x12
// data = Read8bit(0x12); //read reg 0x12
// Write1Byte(0x12, data | 0x40); // enable 3,3V => 5V booster
// this is done below anyway: axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
// this is done below anyway: axp.setPowerOutPut(AXP192_EXTEN, AXP202_ON);
axp.adc1Enable(AXP202_ACIN_VOL_ADC1, 1);
axp.adc1Enable(AXP202_ACIN_CUR_ADC1, 1);
@ -2165,6 +1976,9 @@ void setup()
#endif
sonde.setup();
initGPS();
#if FEATURE_APRS
connAPRS.init();
#endif
WiFi.onEvent(WiFiEvent);
getKeyPress(); // clear key buffer
@ -2190,6 +2004,7 @@ void enterMode(int mode) {
} else if (mainState == ST_WIFISCAN) {
sonde.clearDisplay();
}
if (mode == ST_DECODER) {
// trigger activation of background task
// currentSonde should be set before enterMode()
@ -2219,52 +2034,6 @@ static const char *action2text(uint8_t action) {
}
#define RDZ_DATA_LEN 128
void parseGpsJson(char *data) {
char *key = NULL;
char *value = NULL;
// very simple json parser: look for ", then key, then ", then :, then number, then , or } or \0
for (int i = 0; i < RDZ_DATA_LEN; i++) {
if (key == NULL) {
if (data[i] != '"') continue;
key = data + i + 1;
i += 2;
continue;
}
if (value == NULL) {
if (data[i] != ':') continue;
value = data + i + 1;
i += 2;
continue;
}
if (data[i] == ',' || data[i] == '}' || data[i] == 0) {
// 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;
}
gpsPos.valid = true;
// next item:
if (data[i] != ',') break;
key = NULL;
value = NULL;
}
}
if(gpsPos.lat == 0 && gpsPos.lon == 0) gpsPos.valid = false;
Serial.printf("Parse result: lat=%f, lon=%f, alt=%d, valid=%d\n", gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.valid);
}
static char rdzData[RDZ_DATA_LEN];
static int rdzDataPos = 0;
@ -2303,20 +2072,7 @@ void loopDecoder() {
}
}
if (!tncclient.connected()) {
//Serial.println("TNC client not connected");
tncclient = tncserver.available();
if (tncclient.connected()) {
Serial.println("new TCP KISS connection");
}
}
if (tncclient.available()) {
Serial.print("TCP KISS socket: recevied ");
while (tncclient.available()) {
Serial.print(tncclient.read()); // Check if we receive anything from from APRSdroid
}
Serial.println("");
}
if (rdzserver.hasClient()) {
Serial.println("TCP JSON socket: new connection");
rdzclient.stop();
@ -2330,7 +2086,7 @@ void loopDecoder() {
if (c == '\n' || c == '}' || rdzDataPos >= RDZ_DATA_LEN) {
// parse GPS position from phone
rdzData[rdzDataPos] = c;
if (rdzDataPos > 2) parseGpsJson(rdzData);
if (rdzDataPos > 2) parseGpsJson(rdzData, rdzDataPos+1);
rdzDataPos = 0;
}
else {
@ -2351,6 +2107,11 @@ void loopDecoder() {
// first check if ID and position lat+lonis ok
if (s->d.validID && ((s->d.validPos & 0x03) == 0x03)) {
#if FEATURE_APRS
connAPRS.updateSonde(s);
#endif
#if 0
// moved to conn-aprs.cpp
char *str = aprs_senddata(s, sonde.config.call, sonde.config.objcall, sonde.config.udpfeed.symbol);
char raw[201];
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
@ -2373,7 +2134,7 @@ void loopDecoder() {
}
else if ( tcpclient.connected() ) {
unsigned long now = millis();
Serial.printf("aprs: now-last = %ld\n", (now-lasttcp));
Serial.printf("aprs: now-last = %ld\n", (now - lasttcp));
if ( (now - lasttcp) > sonde.config.tcpfeed.highrate * 1000L ) {
strcat(str, "\r\n");
Serial.print(str);
@ -2382,9 +2143,11 @@ void loopDecoder() {
}
}
}
#endif
#if FEATURE_CHASEMAPPER
if (sonde.config.cm.active) {
Chasemapper::send(udp, s);
connChasemapper.updateSonde( s );
}
#endif
}
@ -2395,21 +2158,26 @@ void loopDecoder() {
#endif
#if FEATURE_MQTT
// send to MQTT if enabledson
if (connected && mqttEnabled) {
Serial.println("Sending sonde info via MQTT");
mqttclient.publishPacket(s);
}
connMQTT.updateSonde( s ); // send to MQTT if enabled
#endif
} else {
#if FEATURE_SONDEHUB
sondehub_finish_data(&shclient, s, &sonde.config.sondehub);
#endif
}
// Send own position periodically
if (sonde.config.tcpfeed.active) {
aprs_station_update();
}
#if FEATURE_MQTT
connMQTT.updateStation( NULL );
#endif
#if FEATURE_APRS
connAPRS.updateStation( NULL );
//if (sonde.config.tcpfeed.active) {
// aprs_station_update();
//}
#endif
// always send data, even if not valid....
if (rdzclient.connected()) {
Serial.println("Sending position via TCP as rdzJSON");
@ -2431,82 +2199,18 @@ void loopDecoder() {
//
raw[0] = '{';
// Use same JSON format as for MQTT and HTML map........
sonde2json(raw+1, 1023, s);
sprintf(raw+strlen(raw),
",\"active\":%d"
",\"validId\":%d"
",\"validPos\":%d"
" %s}\n",
(int)s->active,
s->d.validID,
s->d.validPos,
gps);
sonde2json(raw + 1, 1023, s);
sprintf(raw + strlen(raw),
",\"active\":%d"
",\"validId\":%d"
",\"validPos\":%d"
" %s}\n",
(int)s->active,
s->d.validID,
s->d.validPos,
gps);
int len = strlen(raw);
#if 0
//maintain backwords compatibility
float lat = isnan(s->d.lat) ? 0 : s->d.lat;
float lon = isnan(s->d.lon) ? 0 : s->d.lon;
float alt = isnan(s->d.alt) ? -1 : s->d.alt;
float vs = isnan(s->d.vs) ? 0 : s->d.vs;
float hs = isnan(s->d.hs) ? 0 : s->d.hs;
float dir = isnan(s->d.dir) ? 0 : s->d.dir;
int len = snprintf(raw, 1024, "{"
"\"res\": %d,"
"\"type\": \"%s\","
"\"active\": %d,"
"\"freq\": %.2f,"
"\"id\": \"%s\","
"\"ser\": \"%s\","
"\"validId\": %d,"
"\"launchsite\": \"%s\","
"\"lat\": %.5f,"
"\"lon\": %.5f,"
"\"alt\": %.1f,"
"\"vs\": %.1f,"
"\"hs\": %.1f,"
"\"dir\": %.1f,"
"\"sats\": %d,"
"\"validPos\": %d,"
"\"time\": %d,"
"\"frame\": %d,"
"\"validTime\": %d,"
"\"rssi\": %d,"
"\"afc\": %d,"
"\"launchKT\": %d,"
"\"burstKT\": %d,"
"\"countKT\": %d,"
"\"crefKT\": %d"
"%s"
"}\n",
res & 0xff,
typestr,
(int)s->active,
s->freq,
s->d.id,
s->d.ser,
(int)s->d.validID,
s->launchsite,
lat,
lon,
alt,
vs,
hs,
dir,
s->d.sats,
s->d.validPos,
s->d.time,
s->d.frame,
(int)s->d.validTime,
s->rssi,
s->afc,
s->d.launchKT,
s->d.burstKT,
s->d.countKT,
s->d.crefKT,
gps
);
#endif
//Serial.println("Writing rdzclient...");
if (len > 1024) len = 1024;
@ -2619,17 +2323,14 @@ void enableNetwork(bool enable) {
SetupAsyncServer();
udp.begin(WiFi.localIP(), LOCALUDPPORT);
MDNS.addService("http", "tcp", 80);
MDNS.addService("kiss-tnc", "tcp", 14580);
// => moved to conn-aprs MDNS.addService("kiss-tnc", "tcp", 14580);
MDNS.addService("jsonrdz", "tcp", 14570);
if (sonde.config.kisstnc.active) {
tncserver.begin();
//if (sonde.config.kisstnc.active) {
// tncserver.begin();
rdzserver.begin();
}
//}
#if FEATURE_MQTT
if (sonde.config.mqtt.active && strlen(sonde.config.mqtt.host) > 0) {
mqttEnabled = true;
mqttclient.init(sonde.config.mqtt.host, sonde.config.mqtt.port, sonde.config.mqtt.id, sonde.config.mqtt.username, sonde.config.mqtt.password, sonde.config.mqtt.prefix);
}
connMQTT.netsetup();
#endif
#if FEATURE_SONDEHUB
if (sonde.config.sondehub.active && wifi_state != WIFI_APMODE) {
@ -2643,15 +2344,11 @@ void enableNetwork(bool enable) {
MDNS.end();
connected = false;
}
tcpclient.onConnect([](void *arg, AsyncClient * s) {
Serial.write("APRS: TCP connected\n");
char buf[128];
snprintf(buf, 128, "user %s pass %d vers %s %s\r\n", sonde.config.call, sonde.config.passcode, version_name, version_id);
s->write(buf, strlen(buf));
});
tcpclient.onData([](void *arg, AsyncClient * c, void *data, size_t len) {
Serial.write((const uint8_t *)data, len);
});
#if FEATURE_APRS
connAPRS.netsetup();
#endif
Serial.println("enableNetwork done");
}
@ -3263,58 +2960,11 @@ void loop() {
lastDisplay = currentDisplay;
}
#if FEATURE_MQTT
int now = millis();
if (mqttEnabled && (lastMqttUptime == 0 || (lastMqttUptime + 60000 < now) || (lastMqttUptime > now))) {
mqttclient.publishUptime();
lastMqttUptime = now;
}
#endif
}
void aprs_station_update() {
int chase = sonde.config.chase;
// automatically decided if CHASE or FIXED mode is used (for config AUTO)
if (chase == SH_LOC_AUTO) {
if (SH_LOC_AUTO_IS_CHASE) chase = SH_LOC_CHASE; else chase = SH_LOC_FIXED;
}
unsigned long time_now = millis();
unsigned long time_delta = time_now - time_last_aprs_update;
unsigned long update_time = (chase == SH_LOC_CHASE) ? APRS_MOBILE_STATION_UPDATE_TIME : APRS_STATION_UPDATE_TIME;
Serial.printf("aprs_station_update: delta: %ld, update in %ld\n", time_delta, update_time);
if (time_delta < update_time) return;
Serial.println("Update is due!!");
float lat, lon;
if (chase == SH_LOC_FIXED) {
// fixed location
lat = sonde.config.rxlat;
lon = sonde.config.rxlon;
if (isnan(lat) || isnan(lon)) return;
} else {
if (gpsPos.valid) {
lat = gpsPos.lat;
lon = gpsPos.lon;
} else {
return;
}
}
Serial.printf("Really updating!! (objcall is %s)", sonde.config.objcall);
char *bcn = aprs_send_beacon(sonde.config.call, lat, lon, sonde.config.beaconsym + ((chase==SH_LOC_CHASE)?2:0), sonde.config.comment);
if ( tcpclient.disconnected()) {
tcpclient.connect(sonde.config.tcpfeed.host, sonde.config.tcpfeed.port);
}
if ( tcpclient.connected() ) {
strcat(bcn, "\r\n");
Serial.println("****BEACON****");
Serial.print(bcn);
tcpclient.write(bcn, strlen(bcn));
time_last_aprs_update = time_now;
}
}
#if FEATURE_SONDEHUB
// Sondehub v2 DB related codes
/*
Update station data to the sondehub v2 DB
@ -3335,7 +2985,7 @@ void sondehub_station_update(WiFiClient * client, struct st_sondehub * conf) {
int chase = conf->chase;
// automatically decided if CHASE or FIXED mode is used (for config AUTO)
if (chase == SH_LOC_AUTO) {
if (SH_LOC_AUTO_IS_CHASE) chase = SH_LOC_CHASE; else chase = SH_LOC_FIXED;
if (posInfo.chase) chase = SH_LOC_CHASE; else chase = SH_LOC_FIXED;
}
// Use 30sec update time in chase mode, 60 min in station mode.
@ -3565,7 +3215,7 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub *
int chase = conf->chase;
// automatically decided if CHASE or FIXED mode is used (for config AUTO)
if (chase == SH_LOC_AUTO) {
if (SH_LOC_AUTO_IS_CHASE) chase = SH_LOC_CHASE; else chase = SH_LOC_FIXED;
if (posInfo.chase) chase = SH_LOC_CHASE; else chase = SH_LOC_FIXED;
}
@ -3579,7 +3229,7 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub *
}
// Check if current sonde data is valid. If not, don't do anything....
if (*s->d.ser == 0 || s->d.validID==0 ) return; // Don't send anything without serial number
if (*s->d.ser == 0 || s->d.validID == 0 ) return; // Don't send anything without serial number
if (((int)s->d.lat == 0) && ((int)s->d.lon == 0)) return; // Sometimes these values are zeroes. Don't send those to the sondehub
if ((int)s->d.alt > 50000) return; // If alt is too high don't send to SondeHub
// M20 data does not include #sat information
@ -3655,12 +3305,12 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub *
/* if there is a subtype (DFM only) */
if ( TYPE_IS_DFM(s->type) && s->d.subtype > 0 ) {
if( (s->d.subtype&0xF) != DFM_UNK) {
const char *t = dfmSubtypeLong[s->d.subtype&0xF];
if ( (s->d.subtype & 0xF) != DFM_UNK) {
const char *t = dfmSubtypeLong[s->d.subtype & 0xF];
sprintf(w, "\"subtype\": \"%s\",", t);
}
else {
sprintf(w, "\"subtype\": \"DFMx%X\",", s->d.subtype>>4); // Unknown subtype
sprintf(w, "\"subtype\": \"DFMx%X\",", s->d.subtype >> 4); // Unknown subtype
}
w += strlen(w);
} else if ( s->type == STYPE_RS41 ) {

Wyświetl plik

@ -42,6 +42,7 @@ var cfgs = [
[ "axudp.port", "AXUDP port"],
[ "axudp.highrate", "Rate limit"],
[ "tcp.active", "APRS TCP active"],
[ "tcp.timeout", "APRS TCP timeout [s] (0=off, 25=on)"],
[ "tcp.host", "APRS TCP host"],
[ "tcp.port", "APRS TCP port"],
[ "tcp.highrate", "Rate limit"],

Wyświetl plik

@ -2,12 +2,17 @@
// Configuration flags for including/excluding fuctionality from the compiled binary
// set flag to 0 for exclude/1 for include
/* data feed to sondehubv2 */
/* needs about 4k4 code, 200b data, 200b stack, 200b heap */
// Selection of data output connectors to be included in firmware
// APRS includes AXUDP (e.g. for aprsmap) and APRS-IS (TCP) (e.g. for wettersonde.net, radiosondy.info)
#define FEATURE_SONDEHUB 1
#define FEATURE_CHASEMAPPER 1
#define FEATURE_MQTT 1
#define FEATURE_SDCARD 0
#define FEATURE_APRS 1
// Additional optional components
#define FEATURE_RS92 1
/* Most recent version support fonts in a dedicated flash parition "fonts".

Wyświetl plik

@ -1,13 +0,0 @@
#ifndef _CHASEMAPPER_H
#define _CHASEMAPPER_H
#include "Sonde.h"
//#include <WiFi.h>
#include <WiFiUdp.h>
#include <time.h>
class Chasemapper {
public:
static int send(WiFiUDP &udb, SondeInfo *si);
};
#endif

Wyświetl plik

@ -33,8 +33,6 @@ extern xSemaphoreHandle globalLock;
} while (xSemaphoreTake(globalLock, portMAX_DELAY) != pdPASS)
#define SPI_MUTEX_UNLOCK() xSemaphoreGive(globalLock)
struct GpsPos gpsPos;
//SPIClass spiDisp(HSPI);
byte myIP_tiles[8*11];

Wyświetl plik

@ -9,18 +9,7 @@
#include <U8x8lib.h>
#include <SPIFFS.h>
struct GpsPos {
double lat;
double lon;
int alt;
int course;
float speed;
int sat;
int accuracy;
int hdop;
int valid;
};
extern struct GpsPos gpsPos;
#include "posinfo.h"
#define WIDTH_AUTO 9999
struct DispEntry {

Wyświetl plik

@ -1,3 +1,5 @@
#include "../features.h"
#if FEATURE_RS92
/* RS92 decoder functions */
#include "RS92.h"
@ -587,3 +589,4 @@ int RS92::waitRXcomplete() {
RS92 rs92 = RS92();
#endif

Wyświetl plik

@ -191,6 +191,7 @@ struct st_feedinfo {
int lowrate;
int highrate;
int lowlimit;
int timeout;
};
// maybe extend for external Bluetooth interface?

Wyświetl plik

@ -1,471 +0,0 @@
// SPDX-License-Identifier: GPL-3.0
// original source: https://github.com/Nkawu/TFT22_ILI9225
#ifndef TFT22_ILI9225_h
#define TFT22_ILI9225_h
#ifdef __STM32F1__
#define ARDUINO_STM32_FEATHER
#define PROGMEM
// if 'SPI_CHANNEL' is not defined, 'SPI' is used, only valid for STM32F1
//#define SPI_CHANNEL SPI_2
#endif
#define USE_STRING_CLASS
#ifdef USE_STRING_CLASS
#define STRING String
#else
#define STRING const char *
#endif
#if ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#include <SPI.h>
#include "gfxfont.h"
#if defined(ARDUINO_STM32_FEATHER) || defined(ARDUINO_ARCH_STM32) || defined(ARDUINO_ARCH_STM32F1) || defined(STM32F1)
typedef volatile uint32 RwReg;
#endif
#if defined(ARDUINO_FEATHER52)
typedef volatile uint32_t RwReg;
#endif
/* ILI9225 screen size */
#define ILI9225_LCD_WIDTH 176
#define ILI9225_LCD_HEIGHT 220
/* ILI9225 LCD Registers */
#define ILI9225_DRIVER_OUTPUT_CTRL (0x01u) // Driver Output Control
#define ILI9225_LCD_AC_DRIVING_CTRL (0x02u) // LCD AC Driving Control
#define ILI9225_ENTRY_MODE (0x03u) // Entry Mode
#define ILI9225_DISP_CTRL1 (0x07u) // Display Control 1
#define ILI9225_BLANK_PERIOD_CTRL1 (0x08u) // Blank Period Control
#define ILI9225_FRAME_CYCLE_CTRL (0x0Bu) // Frame Cycle Control
#define ILI9225_INTERFACE_CTRL (0x0Cu) // Interface Control
#define ILI9225_OSC_CTRL (0x0Fu) // Osc Control
#define ILI9225_POWER_CTRL1 (0x10u) // Power Control 1
#define ILI9225_POWER_CTRL2 (0x11u) // Power Control 2
#define ILI9225_POWER_CTRL3 (0x12u) // Power Control 3
#define ILI9225_POWER_CTRL4 (0x13u) // Power Control 4
#define ILI9225_POWER_CTRL5 (0x14u) // Power Control 5
#define ILI9225_VCI_RECYCLING (0x15u) // VCI Recycling
#define ILI9225_RAM_ADDR_SET1 (0x20u) // Horizontal GRAM Address Set
#define ILI9225_RAM_ADDR_SET2 (0x21u) // Vertical GRAM Address Set
#define ILI9225_GRAM_DATA_REG (0x22u) // GRAM Data Register
#define ILI9225_GATE_SCAN_CTRL (0x30u) // Gate Scan Control Register
#define ILI9225_VERTICAL_SCROLL_CTRL1 (0x31u) // Vertical Scroll Control 1 Register
#define ILI9225_VERTICAL_SCROLL_CTRL2 (0x32u) // Vertical Scroll Control 2 Register
#define ILI9225_VERTICAL_SCROLL_CTRL3 (0x33u) // Vertical Scroll Control 3 Register
#define ILI9225_PARTIAL_DRIVING_POS1 (0x34u) // Partial Driving Position 1 Register
#define ILI9225_PARTIAL_DRIVING_POS2 (0x35u) // Partial Driving Position 2 Register
#define ILI9225_HORIZONTAL_WINDOW_ADDR1 (0x36u) // Horizontal Address Start Position
#define ILI9225_HORIZONTAL_WINDOW_ADDR2 (0x37u) // Horizontal Address End Position
#define ILI9225_VERTICAL_WINDOW_ADDR1 (0x38u) // Vertical Address Start Position
#define ILI9225_VERTICAL_WINDOW_ADDR2 (0x39u) // Vertical Address End Position
#define ILI9225_GAMMA_CTRL1 (0x50u) // Gamma Control 1
#define ILI9225_GAMMA_CTRL2 (0x51u) // Gamma Control 2
#define ILI9225_GAMMA_CTRL3 (0x52u) // Gamma Control 3
#define ILI9225_GAMMA_CTRL4 (0x53u) // Gamma Control 4
#define ILI9225_GAMMA_CTRL5 (0x54u) // Gamma Control 5
#define ILI9225_GAMMA_CTRL6 (0x55u) // Gamma Control 6
#define ILI9225_GAMMA_CTRL7 (0x56u) // Gamma Control 7
#define ILI9225_GAMMA_CTRL8 (0x57u) // Gamma Control 8
#define ILI9225_GAMMA_CTRL9 (0x58u) // Gamma Control 9
#define ILI9225_GAMMA_CTRL10 (0x59u) // Gamma Control 10
#define ILI9225C_INVOFF 0x20
#define ILI9225C_INVON 0x21
// autoincrement modes (register ILI9225_ENTRY_MODE, bit 5..3 )
enum autoIncMode_t { R2L_BottomUp, BottomUp_R2L, L2R_BottomUp, BottomUp_L2R, R2L_TopDown, TopDown_R2L, L2R_TopDown, TopDown_L2R };
/* RGB 16-bit color table definition (RG565) */
#define COLOR_BLACK 0x0000 /* 0, 0, 0 */
#define COLOR_WHITE 0xFFFF /* 255, 255, 255 */
#define COLOR_BLUE 0x001F /* 0, 0, 255 */
#define COLOR_GREEN 0x07E0 /* 0, 255, 0 */
#define COLOR_RED 0xF800 /* 255, 0, 0 */
#define COLOR_NAVY 0x000F /* 0, 0, 128 */
#define COLOR_DARKBLUE 0x0011 /* 0, 0, 139 */
#define COLOR_DARKGREEN 0x03E0 /* 0, 128, 0 */
#define COLOR_DARKCYAN 0x03EF /* 0, 128, 128 */
#define COLOR_CYAN 0x07FF /* 0, 255, 255 */
#define COLOR_TURQUOISE 0x471A /* 64, 224, 208 */
#define COLOR_INDIGO 0x4810 /* 75, 0, 130 */
#define COLOR_DARKRED 0x8000 /* 128, 0, 0 */
#define COLOR_OLIVE 0x7BE0 /* 128, 128, 0 */
#define COLOR_GRAY 0x8410 /* 128, 128, 128 */
#define COLOR_GREY 0x8410 /* 128, 128, 128 */
#define COLOR_SKYBLUE 0x867D /* 135, 206, 235 */
#define COLOR_BLUEVIOLET 0x895C /* 138, 43, 226 */
#define COLOR_LIGHTGREEN 0x9772 /* 144, 238, 144 */
#define COLOR_DARKVIOLET 0x901A /* 148, 0, 211 */
#define COLOR_YELLOWGREEN 0x9E66 /* 154, 205, 50 */
#define COLOR_BROWN 0xA145 /* 165, 42, 42 */
#define COLOR_DARKGRAY 0x7BEF /* 128, 128, 128 */
#define COLOR_DARKGREY 0x7BEF /* 128, 128, 128 */
#define COLOR_SIENNA 0xA285 /* 160, 82, 45 */
#define COLOR_LIGHTBLUE 0xAEDC /* 172, 216, 230 */
#define COLOR_GREENYELLOW 0xAFE5 /* 173, 255, 47 */
#define COLOR_SILVER 0xC618 /* 192, 192, 192 */
#define COLOR_LIGHTGRAY 0xC618 /* 192, 192, 192 */
#define COLOR_LIGHTGREY 0xC618 /* 192, 192, 192 */
#define COLOR_LIGHTCYAN 0xE7FF /* 224, 255, 255 */
#define COLOR_VIOLET 0xEC1D /* 238, 130, 238 */
#define COLOR_AZUR 0xF7FF /* 240, 255, 255 */
#define COLOR_BEIGE 0xF7BB /* 245, 245, 220 */
#define COLOR_MAGENTA 0xF81F /* 255, 0, 255 */
#define COLOR_TOMATO 0xFB08 /* 255, 99, 71 */
#define COLOR_GOLD 0xFEA0 /* 255, 215, 0 */
#define COLOR_ORANGE 0xFD20 /* 255, 165, 0 */
#define COLOR_SNOW 0xFFDF /* 255, 250, 250 */
#define COLOR_YELLOW 0xFFE0 /* 255, 255, 0 */
/* Font defines */
#define FONT_HEADER_SIZE 4 // 1: pixel width of 1 font character, 2: pixel height,
#define readFontByte(x) pgm_read_byte(&cfont.font[x])
extern uint8_t Terminal6x8[];
extern uint8_t Terminal11x16[];
extern uint8_t Terminal12x16[];
extern uint8_t Trebuchet_MS16x21[];
struct _currentFont
{
uint8_t* font;
uint8_t width;
uint8_t height;
uint8_t offset;
uint8_t numchars;
uint8_t nbrows;
bool monoSp;
};
#define MONOSPACE 1
#if defined (ARDUINO_STM32_FEATHER)
#undef USE_FAST_PINIO
#elif defined (__AVR__) || defined(TEENSYDUINO) || defined(ESP8266) || defined(__arm__)
#define USE_FAST_PINIO
#endif
/// Main and core class
class TFT22_ILI9225 {
public:
TFT22_ILI9225(int8_t RST, int8_t RS, int8_t CS, int8_t SDI, int8_t CLK, int8_t LED);
TFT22_ILI9225(int8_t RST, int8_t RS, int8_t CS, int8_t LED);
TFT22_ILI9225(int8_t RST, int8_t RS, int8_t CS, int8_t SDI, int8_t CLK, int8_t LED, uint8_t brightness);
TFT22_ILI9225(int8_t RST, int8_t RS, int8_t CS, int8_t LED, uint8_t brightness);
/// Initialization
#ifndef ESP32
void begin(void);
#else
void begin(SPIClass &spi=SPI);
#endif
/// Clear the screen
void clear(void);
/// Invert screen
/// @param flag true to invert, false for normal screen
void invert(boolean flag);
/// Switch backlight on or off
/// @param flag true=on, false=off
void setBacklight(boolean flag);
/// Set backlight brightness
/// @param brightness sets backlight brightness 0-255
void setBacklightBrightness(uint8_t brightness);
/// Switch display on or off
/// @param flag true=on, false=off
void setDisplay(boolean flag);
/// Set orientation
/// @param orientation orientation, 0=portrait, 1=right rotated landscape, 2=reverse portrait, 3=left rotated landscape
void setOrientation(uint8_t orientation);
/// Get orientation
/// @return orientation orientation, 0=portrait, 1=right rotated landscape, 2=reverse portrait, 3=left rotated landscape
uint8_t getOrientation(void);
/// Font size, x-axis
/// @return horizontal size of current font, in pixels
// uint8_t fontX(void);
/// Font size, y-axis
/// @return vertical size of current font, in pixels
// uint8_t fontY(void);
/// Screen size, x-axis
/// @return horizontal size of the screen, in pixels
/// @note 240 means 240 pixels and thus 0..239 coordinates (decimal)
uint16_t maxX(void);
/// Screen size, y-axis
/// @return vertical size of the screen, in pixels
/// @note 220 means 220 pixels and thus 0..219 coordinates (decimal)
uint16_t maxY(void);
/// Draw circle
/// @param x0 center, point coordinate, x-axis
/// @param y0 center, point coordinate, y-axis
/// @param radius radius
/// @param color 16-bit color
void drawCircle(uint16_t x0, uint16_t y0, uint16_t radius, uint16_t color);
/// Draw solid circle
/// @param x0 center, point coordinate, x-axis
/// @param y0 center, point coordinate, y-axis
/// @param radius radius
/// @param color 16-bit color
void fillCircle(uint8_t x0, uint8_t y0, uint8_t radius, uint16_t color);
/// Set background color
/// @param color background color, default=black
void setBackgroundColor(uint16_t color = COLOR_BLACK);
/// Draw line, rectangle coordinates
/// @param x1 start point coordinate, x-axis
/// @param y1 start point coordinate, y-axis
/// @param x2 end point coordinate, x-axis
/// @param y2 end point coordinate, y-axis
/// @param color 16-bit color
void drawLine(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t color);
/// Draw rectangle, rectangle coordinates
/// @param x1 top left coordinate, x-axis
/// @param y1 top left coordinate, y-axis
/// @param x2 bottom right coordinate, x-axis
/// @param y2 bottom right coordinate, y-axis
/// @param color 16-bit color
void drawRectangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t color);
/// Draw solid rectangle, rectangle coordinates
/// @param x1 top left coordinate, x-axis
/// @param y1 top left coordinate, y-axis
/// @param x2 bottom right coordinate, x-axis
/// @param y2 bottom right coordinate, y-axis
/// @param color 16-bit color
void fillRectangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t color);
/// Draw pixel
/// @param x1 point coordinate, x-axis
/// @param y1 point coordinate, y-axis
/// @param color 16-bit color
void drawPixel(uint16_t x1, uint16_t y1, uint16_t color);
/// Draw ASCII Text (pixel coordinates)
/// @param x point coordinate, x-axis
/// @param y point coordinate, y-axis
/// @param s text string
/// @param color 16-bit color, default=white
/// @return x-position behind text
uint16_t drawText(uint16_t x, uint16_t y, STRING s, uint16_t color = COLOR_WHITE);
/// width of an ASCII Text (pixel )
/// @param s text string
uint16_t getTextWidth( STRING s ) ;
/// Calculate 16-bit color from 8-bit Red-Green-Blue components
/// @param red red component, 0x00..0xff
/// @param green green component, 0x00..0xff
/// @param blue blue component, 0x00..0xff
/// @return 16-bit color
uint16_t setColor(uint8_t red, uint8_t green, uint8_t blue);
/// Calculate 8-bit Red-Green-Blue components from 16-bit color
/// @param rgb 16-bit color
/// @param red red component, 0x00..0xff
/// @param green green component, 0x00..0xff
/// @param blue blue component, 0x00..0xff
void splitColor(uint16_t rgb, uint8_t &red, uint8_t &green, uint8_t &blue);
/// Draw triangle, triangle coordinates
/// @param x1 corner 1 coordinate, x-axis
/// @param y1 corner 1 coordinate, y-axis
/// @param x2 corner 2 coordinate, x-axis
/// @param y2 corner 2 coordinate, y-axis
/// @param x3 corner 3 coordinate, x-axis
/// @param y3 corner 3 coordinate, y-axis
/// @param color 16-bit color
void drawTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color);
/// Draw solid triangle, triangle coordinates
/// @param x1 corner 1 coordinate, x-axis
/// @param y1 corner 1 coordinate, y-axis
/// @param x2 corner 2 coordinate, x-axis
/// @param y2 corner 2 coordinate, y-axis
/// @param x3 corner 3 coordinate, x-axis
/// @param y3 corner 3 coordinate, y-axis
/// @param color 16-bit color
void fillTriangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color);
/// Set current font
/// @param font Font name
void setFont(uint8_t* font, bool monoSp=false ); // default = proportional
/// Get current font
_currentFont getFont();
/// Draw single character (pixel coordinates)
/// @param x point coordinate, x-axis
/// @param y point coordinate, y-axis
/// @param ch ASCII character
/// @param color 16-bit color, default=white
/// @return width of character in display pixels
uint16_t drawChar(uint16_t x, uint16_t y, uint16_t ch, uint16_t color = COLOR_WHITE);
/// width of an ASCII character (pixel )
/// @param ch ASCII character
uint16_t getCharWidth( uint16_t ch ) ;
/// Draw bitmap
/// @param x point coordinate, x-axis
/// @param y point coordinate, y-axis
/// @param bitmap
/// @param w width
/// @param h height
/// @param color 16-bit color, default=white
/// @param bg 16-bit color, background
void drawBitmap(int16_t x, int16_t y, const uint8_t *bitmap, int16_t w, int16_t h, uint16_t color);
void drawBitmap(int16_t x, int16_t y, const uint8_t *bitmap, int16_t w, int16_t h, uint16_t color, uint16_t bg);
void drawBitmap(int16_t x, int16_t y, uint8_t *bitmap, int16_t w, int16_t h, uint16_t color);
void drawBitmap(int16_t x, int16_t y, uint8_t *bitmap, int16_t w, int16_t h, uint16_t color, uint16_t bg);
void drawXBitmap(int16_t x, int16_t y, const uint8_t *bitmap, int16_t w, int16_t h, uint16_t color);
void drawXBitmap(int16_t x, int16_t y, const uint8_t *bitmap, int16_t w, int16_t h, uint16_t color, uint16_t bg);
/// Draw bitmap
/// @param x point coordinate, x-axis
/// @param y point coordinate, y-axis
/// @param bitmap, 2D 16bit color bitmap
/// @param w width
/// @param h height
void drawBitmap(uint16_t x, uint16_t y, const uint16_t** bitmap, int16_t w, int16_t h);
void drawBitmap(uint16_t x, uint16_t y, uint16_t** bitmap, int16_t w, int16_t h);
/// Draw bitmap
/// @param x point coordinate, x-axis
/// @param y point coordinate, y-axis
/// @param bitmap, 1D 16bit color bitmap
/// @param w width
/// @param h height
void drawBitmap(uint16_t x, uint16_t y, const uint16_t* bitmap, int16_t w, int16_t h);
void drawBitmap(uint16_t x, uint16_t y, uint16_t* bitmap, int16_t w, int16_t h);
/// Set current GFX font
/// @param f GFX font name defined in include file
void setGFXFont(const GFXfont *f = NULL);
/// Draw a string with the current GFX font
/// @param x point coordinate, x-axis
/// @param y point coordinate, y-axis
/// @param s string to print
/// @param color 16-bit color
void drawGFXText(int16_t x, int16_t y, STRING s, uint16_t color);
/// Get the width & height of a text string with the current GFX font
/// @param str string to analyze
/// @param x point coordinate, x-axis
/// @param y point coordinate, y-axis
/// @param w width in pixels of string
/// @param h height in pixels of string
void getGFXTextExtent(STRING str, int16_t x, int16_t y, int16_t *w, int16_t *h);
/// Draw a single character with the current GFX font
/// @param x point coordinate, x-axis
/// @param y point coordinate, y-axis
/// @param c character to draw
/// @param color 16-bit color
/// @return width of character in display pixels
uint16_t drawGFXChar(int16_t x, int16_t y, unsigned char c, uint16_t color);
uint16_t drawGFXcharBM(int16_t x, int16_t y, unsigned char c, uint16_t color, uint16_t *bm, int bmwidth, int bmheight);
void getGFXCharExtent(uint8_t c, int16_t *gw, int16_t *gh, int16_t *xa);
void setModeFlip(uint16_t m);
private:
void _spiWrite(uint8_t v);
void _spiWrite16(uint16_t v);
void _spiWriteCommand(uint8_t c);
void _spiWriteData(uint8_t d);
void _swap(uint16_t &a, uint16_t &b);
void _setWindow(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1);
void _setWindow(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1, autoIncMode_t mode);
void _resetWindow();
void _drawBitmap(int16_t x, int16_t y, const uint8_t *bitmap, int16_t w, int16_t h,
uint16_t color, uint16_t bg, bool transparent, bool progmem, bool Xbit );
void _orientCoordinates(uint16_t &x1, uint16_t &y1);
void _writeRegister(uint16_t reg, uint16_t data);
void _writeData(uint8_t HI, uint8_t LO);
void _writeData16(uint16_t HILO);
void _writeCommand(uint8_t HI, uint8_t LO);
void _writeCommand16(uint16_t HILO);
uint16_t _maxX, _maxY, _bgColor;
#if defined (__AVR__) || defined(TEENSYDUINO)
int8_t _rst, _rs, _cs, _sdi, _clk, _led;
#ifdef USE_FAST_PINIO
volatile uint8_t *mosiport, *clkport, *dcport, *rsport, *csport;
uint8_t mosipinmask, clkpinmask, cspinmask, dcpinmask;
#endif
#elif defined (__arm__)
int32_t _rst, _rs, _cs, _sdi, _clk, _led;
#ifdef USE_FAST_PINIO
volatile RwReg *mosiport, *clkport, *dcport, *rsport, *csport;
uint32_t mosipinmask, clkpinmask, cspinmask, dcpinmask;
#endif
#elif defined (ESP8266) || defined (ESP32)
int8_t _rst, _rs, _cs, _sdi, _clk, _led;
#ifdef USE_FAST_PINIO
volatile uint32_t *mosiport, *clkport, *dcport, *rsport, *csport;
uint32_t mosipinmask, clkpinmask, cspinmask, dcpinmask;
#endif
#else
int8_t _rst, _rs, _cs, _sdi, _clk, _led;
#endif
uint8_t _orientation, _brightness;
uint16_t _modeFlip;
// correspondig modes if orientation changed:
const autoIncMode_t modeTab [3][8] = {
// { R2L_BottomUp, BottomUp_R2L, L2R_BottomUp, BottomUp_L2R, R2L_TopDown, TopDown_R2L, L2R_TopDown, TopDown_L2R }//
/* 90° */ { BottomUp_L2R, L2R_BottomUp, TopDown_L2R, L2R_TopDown, BottomUp_R2L, R2L_BottomUp, TopDown_R2L, R2L_TopDown },
/*180° */ { L2R_TopDown , TopDown_L2R, R2L_TopDown, TopDown_R2L, L2R_BottomUp, BottomUp_L2R, R2L_BottomUp, BottomUp_R2L},
/*270° */ { TopDown_R2L , R2L_TopDown, BottomUp_R2L, R2L_BottomUp, TopDown_L2R, L2R_TopDown, BottomUp_L2R, L2R_BottomUp}
};
bool hwSPI, blState;
_currentFont cfont;
#ifdef ESP32
SPIClass _spi;
#endif
protected:
uint32_t writeFunctionLevel;
void startWrite(void);
void endWrite(void);
GFXfont *gfxFont;
};
#endif

Wyświetl plik

@ -16,6 +16,7 @@
#include <unistd.h>
#include <inttypes.h>
#include "aprs.h"
#include "RS41.h"
extern const char *version_name;
extern const char *version_id;

Wyświetl plik

@ -1,8 +1,8 @@
#ifndef _aprs_h
#define _aprs_h
#include "Sonde.h"
#include "RS41.h"
#define APRS_MAXLEN 201

Wyświetl plik

@ -0,0 +1,320 @@
#include "../features.h"
#if FEATURE_APRS
#include "conn-aprs.h"
#include "aprs.h"
#include "posinfo.h"
#include <ESPmDNS.h>
#include <WiFiUdp.h>
#include <sys/socket.h>
#include <lwip/dns.h>
#include <ESPAsyncWebServer.h>
// KISS over TCP for communicating with APRSdroid
static WiFiServer tncserver(14580);
static WiFiClient tncclient;
// APRS over TCP for radiosondy.info etc
static int tcpclient = 0;
enum { TCS_DISCONNECTED, TCS_DNSLOOKUP, TCS_DNSRESOLVED, TCS_CONNECTING, TCS_LOGIN, TCS_CONNECTED };
static uint8_t tcpclient_state = TCS_DISCONNECTED;
ip_addr_t tcpclient_ipaddr;
extern const char *version_name;
extern const char *version_id;
extern WiFiUDP udp;
static unsigned long last_in = 0;
void tcpclient_fsm();
void ConnAPRS::init() {
aprs_gencrctab();
}
void ConnAPRS::netsetup() {
// Setup for KISS TCP server
if(sonde.config.kisstnc.active) {
MDNS.addService("kiss-tnc", "tcp", 14580);
tncserver.begin();
}
if(sonde.config.tcpfeed.active) {
// start the FSM
tcpclient_fsm();
}
}
void ConnAPRS::updateSonde( SondeInfo *si ) {
// prepare data (for UDP and TCP output)
char *str = aprs_senddata(si, sonde.config.call, sonde.config.objcall, sonde.config.udpfeed.symbol);
// Output via AXUDP
if(sonde.config.udpfeed.active) {
char raw[201];
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
Serial.println("Sending AXUDP");
//Serial.println(raw);
udp.beginPacket(sonde.config.udpfeed.host, sonde.config.udpfeed.port);
udp.write((const uint8_t *)raw, rawlen);
udp.endPacket();
}
// KISS via TCP (incoming connection, e.g. from APRSdroid
if (tncclient.connected()) {
Serial.println("Sending position via TCP");
char raw[201];
int rawlen = aprsstr_mon2kiss(str, raw, APRS_MAXLEN);
Serial.print("sending: "); Serial.println(raw);
tncclient.write(raw, rawlen);
}
// APRS via TCP (outgoing connection to aprs-is, e.g. radiosonde.info or wettersonde.net
if (sonde.config.tcpfeed.active) {
static unsigned long lasttcp = 0;
tcpclient_fsm();
if(tcpclient_state == TCS_CONNECTED) {
unsigned long now = millis();
long tts = sonde.config.tcpfeed.highrate * 1000L - (now-lasttcp);
Serial.printf("aprs: now-last = %ld\n", (now - lasttcp));
if ( tts < 0 ) {
strcat(str, "\r\n");
Serial.printf("Sending APRS: %s",str);
write(tcpclient, str, strlen(str));
lasttcp = now;
} else {
Serial.printf("Sending APRS in %d s\n", (int)(tts/1000));
}
}
}
}
#define APRS_TIMEOUT 25000
void ConnAPRS::updateStation( PosInfo *pi ) {
// This funciton is called peridocally.
// We check for stalled connection and possibly close it
Serial.printf("last_in - now: %ld\n", millis() - last_in);
if ( sonde.config.tcpfeed.timeout > 0) {
if ( last_in && ( (millis() - last_in) > sonde.config.tcpfeed.timeout ) ) {
Serial.println("APRS timeout - closing connection");
close(tcpclient);
tcpclient_state = TCS_DISCONNECTED;
}
}
// If available, read data from tcpclient; then send update (if its time for that)
tcpclient_fsm();
if(sonde.config.tcpfeed.active) {
aprs_station_update();
}
// We check for new connections or new data (tnc port)
if (!tncclient.connected()) {
tncclient = tncserver.available();
if (tncclient.connected()) {
Serial.println("new TCP KISS connection");
}
}
if (tncclient.available()) {
Serial.print("TCP KISS socket: recevied ");
while (tncclient.available()) {
Serial.print(tncclient.read()); // Check if we receive anything from from APRSdroid
}
Serial.println("");
}
}
void ConnAPRS::aprs_station_update() {
int chase = sonde.config.chase;
// automatically decided if CHASE or FIXED mode is used (for config AUTO)
if (chase == SH_LOC_AUTO) {
if (posInfo.chase) chase = SH_LOC_CHASE; else chase = SH_LOC_FIXED;
}
unsigned long time_now = millis();
unsigned long time_delta = time_now - time_last_aprs_update;
unsigned long update_time = (chase == SH_LOC_CHASE) ? APRS_MOBILE_STATION_UPDATE_TIME : APRS_STATION_UPDATE_TIME;
long tts = update_time - time_delta;
Serial.printf("aprs_statio_update due in %d s", (int)(tts/1000));
if (tts>0) return;
float lat, lon;
if (chase == SH_LOC_FIXED) {
// fixed location
lat = sonde.config.rxlat;
lon = sonde.config.rxlon;
if (isnan(lat) || isnan(lon)) return;
} else {
if (gpsPos.valid) {
lat = gpsPos.lat;
lon = gpsPos.lon;
} else {
return;
}
}
char *bcn = aprs_send_beacon(sonde.config.call, lat, lon, sonde.config.beaconsym + ((chase == SH_LOC_CHASE) ? 2 : 0), sonde.config.comment);
tcpclient_fsm();
if(tcpclient_state == TCS_CONNECTED) {
strcat(bcn, "\r\n");
Serial.printf("APRS TCP BEACON: %s", bcn);
write(tcpclient, bcn, strlen(bcn));
time_last_aprs_update = time_now;
}
}
static void _tcp_dns_found(const char * name, const ip_addr_t *ipaddr, void * arg) {
if (ipaddr) {
tcpclient_ipaddr = *ipaddr;
tcpclient_state = TCS_DNSRESOLVED; // DNS lookup success
} else {
memset(&tcpclient_ipaddr, 0, sizeof(tcpclient_ipaddr));
tcpclient_state = TCS_DISCONNECTED; // DNS lookup failed
}
}
void tcpclient_sendlogin() {
char buf[128];
snprintf(buf, 128, "user %s pass %d vers %s %s\r\n", sonde.config.call, sonde.config.passcode, version_name, version_id);
int res = write(tcpclient, buf, strlen(buf));
Serial.printf("APRS login: %s, res=%d\n", buf, res);
last_in = millis();
if(res<=0) {
close(tcpclient);
tcpclient_state = TCS_DISCONNECTED;
}
}
void tcpclient_fsm() {
if(!sonde.config.tcpfeed.active)
return;
Serial.printf("TCS: %d\n", tcpclient_state);
fd_set fdset;
FD_ZERO(&fdset);
FD_SET(tcpclient, &fdset);
fd_set fdeset;
FD_ZERO(&fdeset);
FD_SET(tcpclient, &fdeset);
struct timeval selto = {0};
int res;
switch(tcpclient_state) {
case TCS_DISCONNECTED:
/* We are disconnected. Try to connect, starting with a DNS lookup */
{
// Restart timeout
last_in = millis();
err_t res = dns_gethostbyname( sonde.config.tcpfeed.host, &tcpclient_ipaddr, /*(dns_found_callback)*/_tcp_dns_found, NULL );
if(res == ERR_OK) { // Returns immediately of host is IP or in cache
tcpclient_state = TCS_DNSRESOLVED;
/* fall through */
} else if(res == ERR_INPROGRESS) {
tcpclient_state = TCS_DNSLOOKUP;
break;
} else { // failed
tcpclient_state = TCS_DISCONNECTED;
break;
}
}
case TCS_DNSRESOLVED:
{
/* We have got the IP address, start the connection */
tcpclient = socket(AF_INET, SOCK_STREAM, 0);
int flags = fcntl(tcpclient, F_GETFL);
if (fcntl(tcpclient, F_SETFL, flags | O_NONBLOCK) == -1) {
Serial.println("Setting O_NONBLOCK failed");
}
struct sockaddr_in sock_info;
memset(&sock_info, 0, sizeof(struct sockaddr_in));
sock_info.sin_family = AF_INET;
sock_info.sin_addr.s_addr = tcpclient_ipaddr.u_addr.ip4.addr;
sock_info.sin_port = htons( sonde.config.tcpfeed.port );
err_t res = connect(tcpclient, (struct sockaddr *)&sock_info, sizeof(sock_info));
if(res) {
if (errno == EINPROGRESS) { // Should be the usual case, go to connecting state
tcpclient_state = TCS_CONNECTING;
} else {
close(tcpclient);
tcpclient_state = TCS_DISCONNECTED;
}
} else {
tcpclient_state = TCS_CONNECTED;
tcpclient_sendlogin();
}
}
break;
case TCS_CONNECTING:
{
// Poll to see if we are now connected
res = select(tcpclient+1, NULL, &fdset, &fdeset, &selto);
if(res<0) {
Serial.println("TNS_CONNECTING: select error");
goto error;
} else if (res==0) { // still pending
break;
}
// Socket has become ready (or something went wrong, check for error first)
int sockerr;
socklen_t len = (socklen_t)sizeof(int);
if (getsockopt(tcpclient, SOL_SOCKET, SO_ERROR, (void*)(&sockerr), &len) < 0) {
goto error;
}
Serial.printf("select returing %d. isset:%d iseset:%d sockerr:%d\n", res, FD_ISSET(tcpclient, &fdset), FD_ISSET(tcpclient, &fdeset), sockerr);
if(sockerr) {
Serial.printf("APRS connect error: %s\n", strerror(sockerr));
goto error;
}
tcpclient_state = TCS_CONNECTED;
tcpclient_sendlogin();
}
break;
case TCS_CONNECTED:
{
res = select(tcpclient+1, &fdset, NULL, NULL, &selto);
if(res<0) {
Serial.println("TCS_CONNECTING: select error");
goto error;
} else if (res==0) { // still pending
break;
}
// Read data
char buf[512+1];
res = read(tcpclient, buf, 512);
if(res<=0) {
close(tcpclient);
tcpclient_state = TCS_DISCONNECTED;
} else {
buf[res] = 0;
Serial.printf("tcpclient data (len=%d):", res);
Serial.write( (uint8_t *)buf, res );
last_in = millis();
}
}
break;
case TCS_DNSLOOKUP:
Serial.println("DNS lookup in progress");
break; // DNS lookup in progress, do not do anything until callback is called, updating the state
}
return;
error:
close(tcpclient);
tcpclient_state = TCS_DISCONNECTED;
return;
}
ConnAPRS connAPRS;
#endif

Wyświetl plik

@ -0,0 +1,39 @@
#include "../features.h"
#if FEATURE_APRS
#ifndef conn_aprs_h
#define conn_aprs_h
#include "conn.h"
#include "aprs.h"
// Times in ms, i.e. station: 10 minutes, mobile: 20 seconds
#define APRS_STATION_UPDATE_TIME (10*60*1000)
#define APRS_MOBILE_STATION_UPDATE_TIME (20*1000)
static unsigned long time_last_aprs_update = -APRS_STATION_UPDATE_TIME;
class ConnAPRS : public Conn
{
public:
/* Called once on startup */
void init();
/* Called whenever the network becomes available */
void netsetup();
/* Called approx 1x / second (maybe only if good data is available) */
void updateSonde( SondeInfo *si );
/* Called approx 1x / second* */
void updateStation( PosInfo *pi );
private:
void aprs_station_update();
};
extern ConnAPRS connAPRS;
#endif
#endif

Wyświetl plik

@ -1,8 +1,20 @@
#include "Chasemapper.h"
#include "../features.h"
#if FEATURE_CHASEMAPPER
#include "conn-chasemapper.h"
#include <WiFiUdp.h>
extern const char *sondeTypeStrSH[];
extern WiFiUDP udp;
int Chasemapper::send(WiFiUDP &udp, SondeInfo *si) {
void ConnChasemapper::init() {
}
void ConnChasemapper::netsetup() {
}
void ConnChasemapper::updateSonde(SondeInfo *si) {
char buf[1024];
struct tm tim;
time_t t = si->d.time;
@ -38,6 +50,10 @@ int Chasemapper::send(WiFiUDP &udp, SondeInfo *si) {
udp.beginPacket(sonde.config.cm.host, sonde.config.cm.port);
udp.write((const uint8_t *)buf, strlen(buf));
udp.endPacket();
return 0;
}
void ConnChasemapper::updateStation(PosInfo *pi) {
}
ConnChasemapper connChasemapper;
#endif

Wyświetl plik

@ -0,0 +1,17 @@
#ifndef _CHASEMAPPER_H
#define _CHASEMAPPER_H
#include "Sonde.h"
#include "conn.h"
class ConnChasemapper : public Conn {
public:
void init();
void netsetup();
void updateSonde( SondeInfo *si );
void updateStation( PosInfo *pi );
};
extern ConnChasemapper connChasemapper;
#endif

Wyświetl plik

@ -0,0 +1,131 @@
#include "../features.h"
#if FEATURE_MQTT
#include <Arduino.h>
#include "conn-mqtt.h"
#include <WiFi.h>
#include <AsyncMqttClient.h>
#include <ESPmDNS.h>
#include "json.h"
extern const char *version_name;
extern const char *version_id;
/* configuration paramters are in the config, no need to duplicate :-)
{"mqtt.active", 0, &sonde.config.mqtt.active},
{"mqtt.id", 63, &sonde.config.mqtt.id},
{"mqtt.host", 63, &sonde.config.mqtt.host},
{"mqtt.port", 0, &sonde.config.mqtt.port},
{"mqtt.username", 63, &sonde.config.mqtt.username},
{"mqtt.password", 63, &sonde.config.mqtt.password},
{"mqtt.prefix", 63, &sonde.config.mqtt.prefix},
*/
TimerHandle_t mqttReconnectTimer;
/* Global initalization (on TTGO startup) */
void MQTT::init() {
}
// Internal helper function for netsetup
void mqttCallback(char* topic, byte* payload, unsigned int length) {
Serial.print("Message arrived [");
Serial.print(topic);
Serial.print("] ");
for (int i=0;i<length;i++) {
Serial.print((char)payload[i]);
}
Serial.println();
}
/* Network initialization (as soon as network becomes available) */
void MQTT::netsetup() {
if (!sonde.config.mqtt.active)
return;
if (strlen(sonde.config.mqtt.host)==0)
return;
WiFi.hostByName(sonde.config.mqtt.host, this->ip);
Serial.println("[MQTT] pubsub client");
mqttClient.setServer(ip, sonde.config.mqtt.port);
snprintf(clientID, 20, "%s%04d", sonde.config.mqtt.id, (int)random(0, 1000));
clientID[20] = 0;
Serial.print(clientID);
mqttClient.setClientId(clientID);
if (strlen(sonde.config.mqtt.password) > 0) {
mqttClient.setCredentials(sonde.config.mqtt.username, sonde.config.mqtt.password);
}
}
void MQTT::updateSonde( SondeInfo *si ) {
if(!sonde.config.mqtt.active)
return;
if(1 /*connected*/) {
Serial.println("Sending sonde info via MQTT");
// TODO: Check if si is good / fresh
publishPacket(si);
}
}
void MQTT::updateStation( PosInfo *pi ) {
if(!sonde.config.mqtt.active)
return;
int now = millis();
if ( (lastMqttUptime == 0 || (lastMqttUptime + 60000 < now) || (lastMqttUptime > now))) {
publishUptime();
lastMqttUptime = now;
}
}
// Internal (private) functions
//void MQTT::connectToMqtt() {
// Serial.println("Connecting to MQTT...");
// mqttClient.connect();
//}
void MQTT::publishUptime()
{
mqttClient.connect(); // ensure we've got connection
Serial.println("[MQTT] writing");
char payload[256];
// maybe TODO: Use dynamic position if GPS is available?
// rxlat, rxlon only if not empty
snprintf(payload, 256, "{\"uptime\": %lu, \"user\": \"%s\", ", millis(), sonde.config.mqtt.username);
if( !isnan(sonde.config.rxlat) && !isnan(sonde.config.rxlon) ) {
snprintf(payload, 256, "%s\"rxlat\": %.5f, \"rxlon\": %.5f, ", payload, sonde.config.rxlat, sonde.config.rxlon);
}
snprintf(payload, 256, "%s\"SW\": \"%s\", \"VER\": \"%s\"}", payload, version_name, version_id);
Serial.println(payload);
char topic[128];
snprintf(topic, 128, "%s%s", sonde.config.mqtt.prefix, "uptime");
mqttClient.publish(topic, 1, 1, payload);
}
void MQTT::publishPacket(SondeInfo *si)
{
SondeData *s = &(si->d);
mqttClient.connect(); // ensure we've got connection
char payload[1024];
payload[0] = '{';
int n = sonde2json(payload+1, 1023, si);
if(n<0) {
// ERROR
Serial.println("publishPacket: sonde2json failed, string too long");
}
strcat(payload, "}"); // terminate payload string
char topic[128];
snprintf(topic, 128, "%s%s", sonde.config.mqtt.prefix, "packet");
Serial.print(payload);
mqttClient.publish(topic, 1, 1, payload);
}
MQTT connMQTT;
#endif

Wyświetl plik

@ -0,0 +1,52 @@
#include "../features.h"
#if FEATURE_MQTT
#ifndef MQTT_h
#define MQTT_h
#include <WiFi.h>
#include <AsyncMqttClient.h>
#include "Sonde.h"
//#include "RS41.h"
#include "conn.h"
class MQTT : public Conn
{
public:
/* Called once on startup */
void init();
/* Called whenever the network becomes available */
void netsetup();
/* Called approx 1x / second (maybe only if good data is available) */
virtual void updateSonde( SondeInfo *si );
/* Called approx 1x / second* */
virtual void updateStation( PosInfo *pi );
private:
WiFiClient mqttWifiClient;
AsyncMqttClient mqttClient;
TimerHandle_t mqttReconnectTimer;
IPAddress ip;
//uint16_t port;
//const char *username;
//const char *password;
//const char *prefix;
char clientID[21];
//void init(const char *host, uint16_t port, const char *id, const char *username, const char *password, const char *prefix);
void publishPacket(SondeInfo *s);
void publishUptime();
//void connectToMqtt();
unsigned long lastMqttUptime = 0;
boolean mqttEnabled;
};
extern MQTT connMQTT;
#endif
#endif

Wyświetl plik

@ -0,0 +1,51 @@
#include "../features.h"
#if FEATURE_SDCARD
#include "conn-sdcard.h"
// TODO: Move into config
#define CS 13
#define SYNC_INTERVAL 10
void ConnSDCard::init() {
/* Initialize SD card */
initok = SD.begin(CS);
Serial.printf("SD card init: %s\n", initok?"OK":"Failed");
}
void ConnSDCard::netsetup() {
/* empty function, we don't use any network here */
}
void ConnSDCard::updateSonde( SondeInfo *si ) {
if (!initok) return;
if (!file) {
file = SD.open("/data.csv", FILE_APPEND);
}
if (!file) {
Serial.println("Error opening file");
return;
}
SondeData *sd = &si->d;
file.printf("%d,%s,%s,%d,"
"%f,%f,%f,%f,%f,%f,%d,%d,"
"%d,%d,%d,%d\n",
sd->validID, sd->ser, sd->typestr, sd->subtype,
sd->lat, sd->lon, sd->alt, sd->vs, sd->hs, sd->dir, sd->sats, sd->validPos,
sd->time, sd->frame, sd->vframe, sd->validTime);
wcount++;
if(wcount >= SYNC_INTERVAL) {
file.flush();
wcount = 0;
}
}
void ConnSDCard::updateStation( PosInfo *pi ) {
}
ConnSDCard connSDCard;
#endif

Wyświetl plik

@ -0,0 +1,42 @@
/*
* conn-sdcard.h
* Data exporter to SD card
* Copyright (c) 2023 Hansi Reiser, dl9rdz
*
* SPDX-License-Identifier: GPL-2.0+
*/
#ifndef conn_sdcard_h
#define conn_sdcard_h
#include "conn.h"
//#include "FS.h"
#include "SD.h"
class ConnSDCard : public Conn
{
public:
/* Called once on startup */
void init();
/* Called whenever the network becomes available */
void netsetup();
/* Called approx 1x / second (maybe only if good data is available) */
virtual void updateSonde( SondeInfo *si );
/* Called approx 1x / second* */
virtual void updateStation( PosInfo *pi );
private:
File file;
uint8_t initok = 0;
uint16_t wcount = 0;
};
#endif

38
RX_FSK/src/conn.h 100644
Wyświetl plik

@ -0,0 +1,38 @@
/*
* conn.h
* Interface for external data exporters
* Copyright (c) 2023 Hansi Reiser, dl9rdz
*/
#ifndef conn_h
#define conn_h
#include "Sonde.h"
// to be moved elsewhere
struct PosInfo {
public:
float lat;
float lon;
};
/* Interface for all data exporters */
class Conn
{
public:
/* Called once on startup */
virtual void init();
/* Called whenever the network becomes available */
virtual void netsetup();
/* Called approx 1x / second (maybe only if good data is available) */
virtual void updateSonde( SondeInfo *si );
/* Called approx 1x / second* */
virtual void updateStation( PosInfo *pi );
};
#endif

Wyświetl plik

@ -1,3 +1,6 @@
#include "../features.h"
#if FEATURE_RS92
#include "time.h"
#include "geteph.h"
#include <SPIFFS.h>
@ -236,3 +239,4 @@ void geteph() {
file.close();
ofile.close();
}
#endif

Wyświetl plik

@ -1,164 +0,0 @@
#include <Arduino.h>
#include "mqtt.h"
#include <WiFi.h>
#include <AsyncMqttClient.h>
#include <ESPmDNS.h>
#include "RS41.h"
#include "json.h"
extern const char *version_name;
extern const char *version_id;
TimerHandle_t mqttReconnectTimer;
void mqttCallback(char* topic, byte* payload, unsigned int length) {
Serial.print("Message arrived [");
Serial.print(topic);
Serial.print("] ");
for (int i=0;i<length;i++) {
Serial.print((char)payload[i]);
}
Serial.println();
}
static char buffer[21];
void MQTT::init(const char* host, uint16_t port, const char* id, const char *username, const char *password, const char *prefix)
{
WiFi.hostByName(host, this->ip);
this->port = port;
this->username = username;
this->password = password;
this->prefix = prefix;
Serial.println("[MQTT] pubsub client");
mqttClient.setServer(ip, port);
snprintf(buffer, 20, "%s%04d", id, (int)random(0, 1000));
buffer[20] = 0;
Serial.print(buffer);
mqttClient.setClientId(buffer);
if (strlen(password) > 0) {
mqttClient.setCredentials(username, password);
}
}
void MQTT::connectToMqtt() {
Serial.println("Connecting to MQTT...");
mqttClient.connect();
}
void MQTT::publishUptime()
{
mqttClient.connect(); // ensure we've got connection
Serial.println("[MQTT] writing");
char payload[256];
// maybe TODO: Use dynamic position if GPS is available?
// rxlat, rxlon only if not empty
snprintf(payload, 256, "{\"uptime\": %lu, \"user\": \"%s\", ", millis(), username);
if( !isnan(sonde.config.rxlat) && !isnan(sonde.config.rxlon) ) {
snprintf(payload, 256, "%s\"rxlat\": %.5f, \"rxlon\": %.5f, ", payload, sonde.config.rxlat, sonde.config.rxlon);
}
snprintf(payload, 256, "%s\"SW\": \"%s\", \"VER\": \"%s\"}", payload, version_name, version_id);
Serial.println(payload);
char topic[128];
snprintf(topic, 128, "%s%s", this->prefix, "uptime");
mqttClient.publish(topic, 1, 1, payload);
}
void MQTT::publishPacket(SondeInfo *si)
{
SondeData *s = &(si->d);
mqttClient.connect(); // ensure we've got connection
char payload[1024];
payload[0] = '{';
int n = sonde2json(payload+1, 1023, si);
if(n<0) {
// ERROR
Serial.println("publishPacket: sonde2json failed, string too long");
}
#if 0
snprintf(payload, 1024, "{"
"\"active\": %d,"
"\"freq\": %.2f,"
"\"id\": \"%s\","
"\"ser\": \"%s\","
"\"validId\": %d,"
"\"launchsite\": \"%s\","
"\"lat\": %.5f,"
"\"lon\": %.5f,"
"\"alt\": %.1f,"
"\"vs\": %.1f,"
"\"hs\": %.1f,"
"\"dir\": %.1f,"
"\"sats\": %d,"
"\"validPos\": %d,"
"\"time\": %u,"
"\"frame\": %u,"
"\"validTime\": %d,"
"\"rssi\": %d,"
"\"afc\": %d,"
"\"rxStat\": \"%s\","
"\"rxStart\": %u,"
"\"norxStart\": %u,"
"\"viewStart\": %u,"
"\"lastState\": %d,"
"\"launchKT\": %d,"
"\"burstKT\": %d,"
"\"countKT\": %d,"
"\"crefKT\": %d",
(int)si->active,
si->freq,
s->id,
s->ser,
(int)s->validID,
si->launchsite,
s->lat,
s->lon,
s->alt,
s->vs,
s->hs,
s->dir,
s->sats,
s->validPos,
s->time,
s->frame,
(int)s->validTime,
si->rssi,
si->afc,
si->rxStat,
si->rxStart,
si->norxStart,
si->viewStart,
si->lastState,
s->launchKT,
s->burstKT,
s->countKT,
s->crefKT
);
if ( !isnan( s->temperature ) ) {
snprintf(payload, 1024, "%s%s%.1f", payload, ",\"temp\": ", s->temperature );
}
if ( !isnan( s->relativeHumidity ) ) {
snprintf(payload, 1024, "%s%s%.1f", payload, ",\"humidity\": ", s->relativeHumidity );
}
if ( !isnan( s->pressure ) ) {
snprintf(payload, 1024, "%s%s%.1f", payload, ",\"pressure\": ", s->pressure );
}
if ( !isnan( s->batteryVoltage && s->batteryVoltage > 0 ) ) {
snprintf(payload, 1024, "%s%s%.1f", payload, ",\"batt\": ", s->batteryVoltage );
}
char subtype[11];
if ( RS41::getSubtype( subtype, 11, si) == 0 ) {
snprintf(payload, 1024, "%s%s%s%s", payload, ",\"subtype\": \"", subtype, "\"" );
}
snprintf(payload, 1024, "%s%s", payload, "}" ); // terminate payload string
#endif
strcat(payload, "}"); // terminate payload string
char topic[128];
snprintf(topic, 128, "%s%s", this->prefix, "packet");
Serial.print(payload);
mqttClient.publish(topic, 1, 1, payload);
}

Wyświetl plik

@ -1,28 +0,0 @@
#ifndef MQTT_h
#define MQTT_h
#include <WiFi.h>
#include <AsyncMqttClient.h>
#include "Sonde.h"
#include "RS41.h"
class MQTT
{
public:
WiFiClient mqttWifiClient;
AsyncMqttClient mqttClient;
TimerHandle_t mqttReconnectTimer;
IPAddress ip;
uint16_t port;
const char *username;
const char *password;
const char *prefix;
void init(const char *host, uint16_t port, const char *id, const char *username, const char *password, const char *prefix);
void publishPacket(SondeInfo *s);
void publishUptime();
private:
void connectToMqtt();
};
#endif

Wyświetl plik

@ -1,3 +1,6 @@
#include "../features.h"
#if FEATURE_RS92
/* SPDX-License-Identifier: GPL-3.0
* based on https://github.com/rs1729/RS/blob/master/rs92/nav_gps_vel.c
*
@ -1713,3 +1716,4 @@ int NAV_LinV(int N, SAT_t satv[], double pos_ecef[3],
return 0;
}
#endif

Wyświetl plik

@ -0,0 +1,270 @@
#include "posinfo.h"
#include <MicroNMEA.h>
// Sation position obtained from GPS (if available)
struct StationPos gpsPos;
// Station position to use (from GPS or fixed)
struct StationPos posInfo;
/* SH_LOC_OFF: never send position information to SondeHub
SH_LOC_FIXED: send fixed position (if specified in config) to sondehub
SH_LOC_CHASE: always activate chase mode and send GPS position (if available)
SH_LOC_AUTO: if there is no valid GPS position, or GPS position < MIN_LOC_AUTO_DIST away from known fixed position: use FIXED mode
otherwise, i.e. if there is a valid GPS position and (either no fixed position in config, or GPS position is far away from fixed position), use CHASE mode.
*/
// same constants used for SondeHub and APRS
/* auto mode is chase if valid GPS position and (no fixed location entered OR valid GPS position and distance in lat/lon deg to fixed location > threshold) */
//#define MIN_LOC_AUTO_DIST 200 /* meter */
//#define SH_LOC_AUTO_IS_CHASE ( gpsPos.valid && ( (isnan(sonde.config.rxlat) || isnan(sonde.config.rxlon) ) || \
// calcLatLonDist( gpsPos.lat, gpsPos.lon, sonde.config.rxlat, sonde.config.rxlon ) > MIN_LOC_AUTO_DIST ) )
//extern float calcLatLonDist(float lat1, float lon1, float lat2, float lon2);
/////
// set fixed position based on config
void fixedToPosInfo() {
memset(&posInfo, 0, sizeof(posInfo));
if( isnan(sonde.config.rxlat) || isnan(sonde.config.rxlon) )
return;
posInfo.lat = sonde.config.rxlat;
posInfo.lon = sonde.config.rxlon;
posInfo.alt = sonde.config.rxalt;
}
///// GPS handling functions
static char buffer[85];
static MicroNMEA nmea(buffer, sizeof(buffer));
/// Arrg. MicroNMEA changes type definition... so lets auto-infer type
template<typename T>
//void unkHandler(const MicroNMEA& nmea) {
void unkHandler(T nmea) {
if (strcmp(nmea.getMessageID(), "VTG") == 0) {
const char *s = nmea.getSentence();
while (*s && *s != ',') s++;
if (*s == ',') s++; else return;
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;
}
}
// 1 deg = aprox. 100 km ==> approx. 200m
#define AUTO_CHASE_THRESHOLD 0.002
//#define DEBUG_GPS
static bool gpsCourseOld;
static int lastCourse;
void gpsTask(void *parameter) {
nmea.setUnknownSentenceHandler(unkHandler);
while (1) {
while (Serial2.available()) {
char c = Serial2.read();
//Serial.print(c);
if (nmea.process(c)) {
gpsPos.valid = nmea.isValid();
if (gpsPos.valid) {
gpsPos.lon = nmea.getLongitude() * 0.000001;
gpsPos.lat = nmea.getLatitude() * 0.000001;
long alt = 0;
nmea.getAltitude(alt);
gpsPos.alt = (int)(alt / 1000);
gpsPos.course = (int)(nmea.getCourse() / 1000);
gpsCourseOld = false;
if (gpsPos.course == 0) {
// either north or not new
if (lastCourse != 0) // use old value...
{
gpsCourseOld = true;
gpsPos.course = lastCourse;
}
}
if (gpsPos.lon == 0 && gpsPos.lat == 0) gpsPos.valid = false;
}
/* Check if home */
if(gpsPos.valid) {
float d = fabs(gpsPos.lon - sonde.config.rxlon);
d += fabs(gpsPos.lat - sonde.config.rxlat);
if(!posInfo.chase && d > AUTO_CHASE_THRESHOLD) {
posInfo = gpsPos;
posInfo.chase = 1;
} else if ( posInfo.chase && d < AUTO_CHASE_THRESHOLD/2 ) {
fixedToPosInfo();
}
}
gpsPos.hdop = nmea.getHDOP();
gpsPos.sat = nmea.getNumSatellites();
gpsPos.speed = nmea.getSpeed() / 1000.0 * 0.514444; // speed is in m/s nmea.getSpeed is in 0.001 knots
#ifdef DEBUG_GPS
uint8_t hdop = nmea.getHDOP();
Serial.printf(" =>: valid: %d N %f E %f alt %d course:%d dop:%d\n", gpsPos.valid ? 1 : 0, gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.course, hdop);
#endif
}
}
delay(50);
}
}
#define UBX_SYNCH_1 0xB5
#define UBX_SYNCH_2 0x62
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, 0xff, 0xff, 0xff, 0xff, 0xff, 0x13, 0x7c };
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 dumpGPS() {
while (Serial2.available()) {
char c = Serial2.read();
Serial.printf("%02x ", (uint8_t)c);
}
}
void initGPS() {
if (sonde.config.gps_rxd < 0) return; // GPS disabled
if (sonde.config.gps_txd >= 0) { // TX enable, thus try setting baud to 9600 and do a factory reset
File testfile = SPIFFS.open("/GPSRESET", FILE_READ);
if (testfile && !testfile.isDirectory()) {
testfile.close();
Serial.println("GPS resetting baud to 9k6...");
/* TODO: debug:
Sometimes I have seen the Serial2.begin to cause a reset
Guru Meditation Error: Core 1 panic'ed (Interrupt wdt timeout on CPU1)
Backtrace: 0x40081d2f:0x3ffc11b0 0x40087969:0x3ffc11e0 0x4000bfed:0x3ffb1db0 0x4008b7dd:0x3ffb1dc0 0x4017afee:0x3ffb1de0 0x4017b04b:0x3ffb1e20 0x4010722b:0x3ffb1e50 0x40107303:0x3ffb1e70 0x4010782d:0x3ffb1e90 0x40103814:0x3ffb1ed0 0x400d8772:0x3ffb1f10 0x400d9057:0x3ffb1f60 0x40107aca:0x3ffb1fb0 0x4008a63e:0x3ffb1fd0
#0 0x40081d2f:0x3ffc11b0 in _uart_isr at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/esp32-hal-uart.c:464
#1 0x40087969:0x3ffc11e0 in _xt_lowint1 at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/xtensa_vectors.S:1154
#2 0x4000bfed:0x3ffb1db0 in ?? ??:0
#3 0x4008b7dd:0x3ffb1dc0 in vTaskExitCritical at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/freertos/tasks.c:3507
#4 0x4017afee:0x3ffb1de0 in esp_intr_alloc_intrstatus at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/esp32/intr_alloc.c:784
#5 0x4017b04b:0x3ffb1e20 in esp_intr_alloc at /home/runner/work/esp32-arduino-lib-builder/esp32-arduino-lib-builder/esp-idf/components/esp32/intr_alloc.c:784
#6 0x4010722b:0x3ffb1e50 in uartEnableInterrupt at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/esp32-hal-uart.c:464
#7 0x40107303:0x3ffb1e70 in uartAttachRx at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/esp32-hal-uart.c:464
#8 0x4010782d:0x3ffb1e90 in uartBegin at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/esp32-hal-uart.c:464
#9 0x40103814:0x3ffb1ed0 in HardwareSerial::begin(unsigned long, unsigned int, signed char, signed char, bool, unsigned long) at /Users/hansi/.platformio/packages/framework-arduinoespressif32/cores/esp32/HardwareSerial.cpp:190
*/
Serial2.begin(115200, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
delay(200);
Serial2.begin(38400, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
delay(200);
Serial2.begin(19200, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
Serial2.write(ubx_set9k6, sizeof(ubx_set9k6));
Serial2.begin(9600, SERIAL_8N1, sonde.config.gps_rxd, sonde.config.gps_txd);
delay(1000);
dumpGPS();
Serial.println("GPS factory reset...");
Serial2.write(ubx_factorydef, sizeof(ubx_factorydef));
delay(1000);
dumpGPS();
delay(1000);
dumpGPS();
delay(1000);
dumpGPS();
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);
}
xTaskCreate( gpsTask, "gpsTask",
5000, /* stack size */
NULL, /* paramter */
1, /* priority */
NULL); /* task handle*/
}
// Getting GPS data from App (phone)
void parseGpsJson(char *data, int len) {
char *key = NULL;
char *value = NULL;
// very simple json parser: look for ", then key, then ", then :, then number, then , or } or \0
for (int i = 0; i < len; i++) {
if (key == NULL) {
if (data[i] != '"') continue;
key = data + i + 1;
i += 2;
continue;
}
if (value == NULL) {
if (data[i] != ':') continue;
value = data + i + 1;
i += 2;
continue;
}
if (data[i] == ',' || data[i] == '}' || data[i] == 0) {
// 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;
}
gpsPos.valid = true;
// next item:
if (data[i] != ',') break;
key = NULL;
value = NULL;
}
}
if (gpsPos.lat == 0 && gpsPos.lon == 0) gpsPos.valid = false;
Serial.printf("Parse result: lat=%f, lon=%f, alt=%d, valid=%d\n", gpsPos.lat, gpsPos.lon, gpsPos.alt, gpsPos.valid);
}

Wyświetl plik

@ -0,0 +1,37 @@
#ifndef _posinfo_h
#define _posinfo_h
#include <inttypes.h>
#include "Sonde.h"
#include <SPIFFS.h>
enum { SH_LOC_OFF, SH_LOC_FIXED, SH_LOC_CHASE, SH_LOC_AUTO };
// Handling of station position (GPS, fixed location)
struct StationPos {
double lat;
double lon;
int alt;
float speed;
int16_t course;
int16_t accuracy;
int16_t hdop;
int8_t sat;
int8_t valid;
int8_t chase;
};
extern struct StationPos gpsPos, posInfo;
// Initialize GPS chip
void initGPS();
// Update position from app (if not local GPS chip)
void parseGpsJson(char *data, int len);
#endif

Wyświetl plik

@ -1,3 +1,6 @@
#include "../features.h"
#if FEATURE_RS92
/* SPDX-License-Identifier: GPL-3.0
* based on https://github.com/rs1729/RS/blob/master/rs92/rs92gps.c
*
@ -1202,3 +1205,4 @@ void get_eph(const char *file) {
if (!option_der) d_err = 1000;
}
#endif

Wyświetl plik

@ -1,4 +1,4 @@
const char *version_name = "rdzTTGOsonde";
const char *version_id = "devel20230427";
const char *version_id = "devel20230819";
const int SPIFFS_MAJOR=2;
const int SPIFFS_MINOR=17;

Wyświetl plik

@ -26,6 +26,7 @@ lib_deps_external =
[env:ttgo-lora32]
platform = https://github.com/platformio/platform-espressif32.git#v3.3.2
#platform = https://github.com/platformio/platform-espressif32.git#v6.3.2
#platform = https://github.com/platformio/platform-espressif32.git#v4.4.0
board = ttgo-lora32-v1
framework = arduino