more status tab refinements
This commit is contained in:
parent
f1a8bff160
commit
5f00d3b970
|
|
@ -57,6 +57,7 @@
|
|||
#include "src/conn-system.h"
|
||||
|
||||
Conn *connectors[] = { &connSystem,
|
||||
&connGPS,
|
||||
#if FEATURE_APRS
|
||||
&connAPRS,
|
||||
#endif
|
||||
|
|
@ -66,6 +67,9 @@ Conn *connectors[] = { &connSystem,
|
|||
#if FEATURE_CHASEMAPPER
|
||||
&connChasemapper,
|
||||
#endif
|
||||
#if FEATURE_MQTT
|
||||
&connMQTT,
|
||||
#endif
|
||||
#if FEATURE_SDCARD
|
||||
&connSDCard,
|
||||
#endif
|
||||
|
|
@ -648,13 +652,12 @@ struct st_configitems config_list[] = {
|
|||
/* 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},
|
||||
{"axudp.ratelimit", 0, &sonde.config.udpfeed.ratelimit},
|
||||
/* 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.host2", 63, &sonde.config.tcpfeed.host2},
|
||||
{"tcp.chase", 0, &sonde.config.chase},
|
||||
{"tcp.comment", 30, sonde.config.comment},
|
||||
{"tcp.objcall", 9, sonde.config.objcall},
|
||||
|
|
|
|||
|
|
@ -38,13 +38,12 @@ var cfgs = [
|
|||
[ "passcode", "Passcode"],
|
||||
[ "kisstnc.active", "KISS TNC (port 14590) (needs reboot)"],
|
||||
[ "axudp.active", "AXUDP active"],
|
||||
[ "axudp.host", "AXUDP host"],
|
||||
[ "axudp.port", "AXUDP port"],
|
||||
[ "axudp.host", "AXUDP host[: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.host", "APRS TCP host[:port] (default port 14580)"],
|
||||
[ "tcp.host2", "APRS TCP host2[:port]"],
|
||||
[ "tcp.highrate", "Rate limit"],
|
||||
[ "tcp.objcall", "APRS object call"],
|
||||
[ "tcp.beaconsym", "APRS tracker symbol"],
|
||||
|
|
|
|||
|
|
@ -10,20 +10,60 @@
|
|||
<body>
|
||||
<div class="wrapper"><div class="header">
|
||||
<div class="topnav" id="myTopnav">
|
||||
<a href="#qrg" onclick="selTab(event,'QRG')" class="tablinks" id="defaultTab">QRG</a>
|
||||
<a href="#home" onclick="selTab(event,'Home');fetchStatus()" class="tablinks" id="defaultTab">Home</a>
|
||||
<a href="#qrg" onclick="selTab(event,'QRG')" class="tablinks">QRG</a>
|
||||
<a href="#data" onclick="selTab(event,'Data')" class="tablinks">Data</a>
|
||||
<a href="#map" onclick="selTab(event,'Map')" class="tablinks">Map</a>
|
||||
<a href="#livemap" onclick="document.location.href='livemap.html'" class="tablinks">LiveMap</a>
|
||||
<a href="#livemap" onclick="document.location.href='livemap.html'" class="tablinks">Livemap</a>
|
||||
<a href="#ctrl" onclick="selTab(event,'Control')" class="tablinks">Control</a>
|
||||
<a href="#config" onclick="selTab(event,'Config')" class="tablinks">Config</a>
|
||||
<a href="#wifi" onclick="selTab(event,'WiFi')" class="tablinks">WiFi</a>
|
||||
<a href="#about" onclick="selTab(event,'About');fetchStatus()" class="tablinks">About</a>
|
||||
<a href="javascript:void(0);" class="icon" onclick="myFunction()">
|
||||
<span class="hamburger"></span>
|
||||
</a>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<div id="Home" class="tabcontent">
|
||||
<div class="tci">
|
||||
<div class="system-info">
|
||||
<h1>%VERSION_NAME% version %VERSION_ID%</h1>
|
||||
<p>Copyright © 2019-2024 by Hansi Reiser, DL9RDZ and contributors</p>
|
||||
<p>
|
||||
This program is free software; you can redistribute it and/or
|
||||
modify it under the terms of the <a href="https://www.gnu.org/licenses/gpl-2.0.txt">GNU General Public License</a> as
|
||||
published by the Free Software Foundation; either version 2 of
|
||||
the License, or (at your option) any later version.
|
||||
See <a href="https://github.com/dl9rdz/rdz_ttgo_sonde/">https://github.com/dl9rdz/rdz_ttgo_sonde/</a>
|
||||
for details, contributors, and license exceptions of third-party components.
|
||||
</p>
|
||||
<p><br><a href="/upd.html">Check for update (requires TTGO internet connection via WiFi)</a><br></p>
|
||||
<table class="status-table">
|
||||
<thead>
|
||||
<tr>
|
||||
<th>Component</th><th>Status<button id="refresh-button" onclick="fetchStatus()">[refresh]</button></th>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody id="status-body">
|
||||
<tr>
|
||||
<td>TTGO</td>
|
||||
<td>Autodetect info: %AUTODETECT_INFO%</td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
<div class="external-links">
|
||||
<h2>External Sites</h2>
|
||||
<div class="link-buttons">
|
||||
<a href="https://www.wettersonde.net" target="_blank" class="button">wettersonde.net</a>
|
||||
<a href="https://www.radiosondy.info" target="_blank" class="button">radiosondy.info</a>
|
||||
<a href="https://www.sondehub.org" target="_blank" class="button">sondehub.org</a>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
<div class="footer"><span></span><span class="ttgoinfo">rdzTTGOserver %VERSION_ID%</span></div>
|
||||
|
||||
</div>
|
||||
|
||||
<div id="QRG" class="tabcontent" data-src="qrg.html">
|
||||
<iframe class="tci" src="" ></iframe>
|
||||
</div>
|
||||
|
|
@ -36,10 +76,6 @@
|
|||
<iframe class="tci" src="" ></iframe>
|
||||
</div>
|
||||
|
||||
<div id="Map" class="tabcontent" data-src="map.html">
|
||||
<iframe class="tci" src="" ></iframe>
|
||||
</div>
|
||||
|
||||
<div id="Config" class="tabcontent" data-src="config.html">
|
||||
<iframe class="tci" src="" ></iframe>
|
||||
</div>
|
||||
|
|
@ -48,35 +84,6 @@
|
|||
<iframe class="tci" src="" ></iframe>
|
||||
</div>
|
||||
|
||||
<div id="About" class="tabcontent">
|
||||
<div class="tci">
|
||||
<div class="system-info">
|
||||
<h1>%VERSION_NAME% version %VERSION_ID%</h1>
|
||||
<p>Autodetect info: %AUTODETECT_INFO%</p>
|
||||
<p>Copyright © 2019-2024 by Hansi Reiser, DL9RDZ and contributors</p>
|
||||
<p>
|
||||
This program is free software; you can redistribute it and/or
|
||||
modify it under the terms of the <a href="https://www.gnu.org/licenses/gpl-2.0.txt">GNU General Public License</a> as
|
||||
published by the Free Software Foundation; either version 2 of
|
||||
the License, or (at your option) any later version.
|
||||
See <a href="https://github.com/dl9rdz/rdz_ttgo_sonde/">https://github.com/dl9rdz/rdz_ttgo_sonde/</a>
|
||||
for details, contributors, and license exceptions of third-party components.
|
||||
</p>
|
||||
<p><a href="/upd.html">Check for update (requires TTGO internet connection via WiFi)</a></p>
|
||||
<table class="status-table">
|
||||
<thead>
|
||||
<tr>
|
||||
<th>Component</th><th>Status<button id="refresh-button" onclick="fetchStatus()">[refresh]</button></th>
|
||||
</tr>
|
||||
</thead>
|
||||
<tbody id="status-body">
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
</div>
|
||||
<div class="footer"><span></span><span class="ttgoinfo">rdzTTGOserver %VERSION_ID%</span></div>
|
||||
|
||||
</div>
|
||||
<script>
|
||||
function fetchStatus() {
|
||||
fetch('/status.json')
|
||||
|
|
|
|||
|
|
@ -39,6 +39,33 @@ body, html {
|
|||
color: #007BFF;
|
||||
}
|
||||
|
||||
.external-links {
|
||||
margin-top: 40px;
|
||||
text-align: center;
|
||||
}
|
||||
|
||||
.external-links h2 {
|
||||
font-size: 20px;
|
||||
margin-bottom: 15px;
|
||||
}
|
||||
|
||||
.link-buttons {
|
||||
display: flex;
|
||||
justify-content: center;
|
||||
gap: 20px;
|
||||
}
|
||||
|
||||
.link-buttons .button {
|
||||
background-color: #04AA6D;
|
||||
color: white;
|
||||
padding: 15px 20px;
|
||||
text-decoration: none;
|
||||
border-radius: 5px;
|
||||
font-size: 18px;
|
||||
transition: background-color 0.3s ease;
|
||||
}
|
||||
|
||||
|
||||
.active, .cfgheader:hover {
|
||||
background-color: #ccc;
|
||||
}
|
||||
|
|
|
|||
|
|
@ -264,16 +264,12 @@ void Sonde::defaultConfig() {
|
|||
config.mp3h.agcbw=12500;
|
||||
config.mp3h.rxbw=12500;
|
||||
config.udpfeed.active = 1;
|
||||
config.udpfeed.type = 0;
|
||||
strcpy(config.udpfeed.host, "192.168.42.20");
|
||||
strcpy(config.udpfeed.symbol, "/O");
|
||||
config.udpfeed.port = 9002;
|
||||
config.udpfeed.highrate = 1;
|
||||
strcpy(config.udpfeed.host, "192.168.42.20:9002");
|
||||
config.udpfeed.ratelimit= 1;
|
||||
config.tcpfeed.active = 0;
|
||||
config.tcpfeed.type = 1;
|
||||
strcpy(config.tcpfeed.host, "radiosondy.info");
|
||||
strcpy(config.tcpfeed.host, "wettersonde.net:14580");
|
||||
strcpy(config.tcpfeed.host2, "radiosondy.info:14580");
|
||||
strcpy(config.tcpfeed.symbol, "/O");
|
||||
config.tcpfeed.port = 12345;
|
||||
config.tcpfeed.highrate = 10;
|
||||
config.kisstnc.active = 0;
|
||||
strcpy(config.ephftp,DEFEPH);
|
||||
|
|
|
|||
|
|
@ -181,12 +181,16 @@ struct st_mp3hconfig {
|
|||
int rxbw;
|
||||
};
|
||||
|
||||
|
||||
struct st_feedinfo {
|
||||
struct st_axudpinfo {
|
||||
bool active;
|
||||
int type; // 0:UDP(axudp), 1:TCP(aprs.fi)
|
||||
char host[64];
|
||||
int port;
|
||||
int ratelimit;
|
||||
};
|
||||
|
||||
struct st_aprsinfo {
|
||||
bool active;
|
||||
char host[64];
|
||||
char host2[64];
|
||||
char symbol[3];
|
||||
int lowrate;
|
||||
int highrate;
|
||||
|
|
@ -300,8 +304,8 @@ typedef struct st_rdzconfig {
|
|||
char objcall[10]; // APRS object call (for wettersonde.net)
|
||||
char beaconsym[5]; // APRS beacon symbol
|
||||
char comment[32];
|
||||
struct st_feedinfo udpfeed; // target for AXUDP messages
|
||||
struct st_feedinfo tcpfeed; // target for APRS-IS TCP connections
|
||||
struct st_axudpinfo udpfeed; // target for AXUDP messages
|
||||
struct st_aprsinfo tcpfeed; // target for APRS-IS TCP connections
|
||||
struct st_kisstnc kisstnc; // target for KISS TNC (via TCP, mainly for APRSdroid)
|
||||
struct st_mqtt mqtt;
|
||||
struct st_sondehub sondehub;
|
||||
|
|
|
|||
|
|
@ -18,23 +18,37 @@ static WiFiServer tncserver(14580);
|
|||
static WiFiClient tncclient;
|
||||
|
||||
// APRS over TCP for radiosondy.info etc
|
||||
static int tcpclient = 0;
|
||||
// now we support up to two APRS connections (e.g. radiosondy.info, wettersonde.net)
|
||||
#define N_APRS 2
|
||||
struct st_aprs {
|
||||
int tcpclient;
|
||||
ip_addr_t tcpclient_ipaddr;
|
||||
int port;
|
||||
unsigned long last_in;
|
||||
uint8_t tcpclient_state;
|
||||
} aprs[2]={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;
|
||||
|
||||
char udphost[64];
|
||||
int udpport;
|
||||
|
||||
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();
|
||||
aprs_gencrctab();
|
||||
|
||||
strncpy(udphost, sonde.config.udpfeed.host, 63);
|
||||
char *colon = strchr(udphost, ':');
|
||||
if(colon) {
|
||||
*colon = 0;
|
||||
udpport = atoi(colon+1);
|
||||
}
|
||||
}
|
||||
|
||||
void ConnAPRS::netsetup() {
|
||||
|
|
@ -52,7 +66,7 @@ void ConnAPRS::netsetup() {
|
|||
|
||||
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);
|
||||
char *str = aprs_senddata(si, sonde.config.call, sonde.config.objcall, sonde.config.tcpfeed.symbol);
|
||||
|
||||
// Output via AXUDP
|
||||
if(sonde.config.udpfeed.active) {
|
||||
|
|
@ -60,7 +74,7 @@ void ConnAPRS::updateSonde( SondeInfo *si ) {
|
|||
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.beginPacket(udphost, udpport);
|
||||
udp.write((const uint8_t *)raw, rawlen);
|
||||
udp.endPacket();
|
||||
}
|
||||
|
|
@ -76,14 +90,17 @@ void ConnAPRS::updateSonde( SondeInfo *si ) {
|
|||
if (sonde.config.tcpfeed.active) {
|
||||
static unsigned long lasttcp = 0;
|
||||
tcpclient_fsm();
|
||||
if(tcpclient_state == TCS_CONNECTED) {
|
||||
if(aprs[0].tcpclient_state == TCS_CONNECTED || aprs[1].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));
|
||||
if(aprs[0].tcpclient_state == TCS_CONNECTED)
|
||||
write(aprs[0].tcpclient, str, strlen(str));
|
||||
if(aprs[1].tcpclient_state == TCS_CONNECTED)
|
||||
write(aprs[1].tcpclient, str, strlen(str));
|
||||
lasttcp = now;
|
||||
} else {
|
||||
Serial.printf("Sending APRS in %d s\n", (int)(tts/1000));
|
||||
|
|
@ -94,17 +111,22 @@ void ConnAPRS::updateSonde( SondeInfo *si ) {
|
|||
|
||||
#define APRS_TIMEOUT 25000
|
||||
|
||||
static void check_timeout(st_aprs *a) {
|
||||
Serial.printf("Checking APRS timeout: last_in - new: %ld\n", millis() - a->last_in);
|
||||
if ( a->last_in && ( (millis() - a->last_in) > sonde.config.tcpfeed.timeout*1000 ) ) {
|
||||
Serial.println("APRS timeout - closing connection");
|
||||
close(a->tcpclient);
|
||||
a->tcpclient_state = TCS_DISCONNECTED;
|
||||
}
|
||||
}
|
||||
|
||||
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*1000 ) ) {
|
||||
Serial.println("APRS timeout - closing connection");
|
||||
close(tcpclient);
|
||||
tcpclient_state = TCS_DISCONNECTED;
|
||||
}
|
||||
check_timeout(aprs);
|
||||
check_timeout(aprs+1);
|
||||
}
|
||||
|
||||
// If available, read data from tcpclient; then send update (if its time for that)
|
||||
|
|
@ -129,6 +151,14 @@ void ConnAPRS::updateStation( PosInfo *pi ) {
|
|||
}
|
||||
}
|
||||
|
||||
static void aprs_beacon(char *bcn, st_aprs *aprs) {
|
||||
if(aprs->tcpclient_state == TCS_CONNECTED) {
|
||||
strcat(bcn, "\r\n");
|
||||
Serial.printf("APRS TCP BEACON: %s", bcn);
|
||||
write(aprs->tcpclient, bcn, strlen(bcn));
|
||||
}
|
||||
}
|
||||
|
||||
void ConnAPRS::aprs_station_update() {
|
||||
int chase = sonde.config.chase;
|
||||
if (chase == SH_LOC_OFF) // do not send any location
|
||||
|
|
@ -160,67 +190,84 @@ void ConnAPRS::aprs_station_update() {
|
|||
}
|
||||
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;
|
||||
}
|
||||
aprs_beacon(bcn, aprs);
|
||||
aprs_beacon(bcn, aprs+1);
|
||||
time_last_aprs_update = time_now;
|
||||
}
|
||||
|
||||
static void _tcp_dns_found(const char * name, const ip_addr_t *ipaddr, void * arg) {
|
||||
st_aprs *a = (st_aprs *)arg;
|
||||
if (ipaddr) {
|
||||
tcpclient_ipaddr = *ipaddr;
|
||||
tcpclient_state = TCS_DNSRESOLVED; // DNS lookup success
|
||||
a->tcpclient_ipaddr = *ipaddr;
|
||||
a->tcpclient_state = TCS_DNSRESOLVED; // DNS lookup success
|
||||
} else {
|
||||
memset(&tcpclient_ipaddr, 0, sizeof(tcpclient_ipaddr));
|
||||
tcpclient_state = TCS_DISCONNECTED; // DNS lookup failed
|
||||
memset(&a->tcpclient_ipaddr, 0, sizeof(a->tcpclient_ipaddr));
|
||||
a->tcpclient_state = TCS_DISCONNECTED; // DNS lookup failed
|
||||
}
|
||||
}
|
||||
|
||||
void tcpclient_sendlogin() {
|
||||
void tcpclient_sendlogin(st_aprs *a) {
|
||||
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));
|
||||
int res = write(a->tcpclient, buf, strlen(buf));
|
||||
Serial.printf("APRS login: %s, res=%d\n", buf, res);
|
||||
last_in = millis();
|
||||
a->last_in = millis();
|
||||
if(res<=0) {
|
||||
close(tcpclient);
|
||||
tcpclient_state = TCS_DISCONNECTED;
|
||||
close(a->tcpclient);
|
||||
a->tcpclient_state = TCS_DISCONNECTED;
|
||||
}
|
||||
}
|
||||
|
||||
static void tcpclient_fsm_single(st_aprs *a);
|
||||
|
||||
void tcpclient_fsm() {
|
||||
for(int i=0; i<N_APRS; i++) {
|
||||
tcpclient_fsm_single(aprs+i);
|
||||
}
|
||||
}
|
||||
|
||||
static void tcpclient_fsm_single(st_aprs *a) {
|
||||
if(!sonde.config.tcpfeed.active)
|
||||
return;
|
||||
Serial.printf("TCS: %d\n", tcpclient_state);
|
||||
|
||||
Serial.printf("TCS[%d]: %d\n", a==aprs?0:1, a->tcpclient_state);
|
||||
|
||||
fd_set fdset;
|
||||
FD_ZERO(&fdset);
|
||||
FD_SET(tcpclient, &fdset);
|
||||
FD_SET(a->tcpclient, &fdset);
|
||||
fd_set fdeset;
|
||||
FD_ZERO(&fdeset);
|
||||
FD_SET(tcpclient, &fdeset);
|
||||
FD_SET(a->tcpclient, &fdeset);
|
||||
|
||||
struct timeval selto = {0};
|
||||
int res;
|
||||
|
||||
switch(tcpclient_state) {
|
||||
switch(a->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 );
|
||||
a->last_in = millis();
|
||||
char host[256];
|
||||
strcpy(host, a==aprs ? sonde.config.tcpfeed.host : sonde.config.tcpfeed.host2 );
|
||||
char *colon =strchr(host, ':');
|
||||
if(colon) {
|
||||
*colon = 0;
|
||||
a->port = atoi(colon+1);
|
||||
} else {
|
||||
a->port = 14580;
|
||||
}
|
||||
Serial.printf("aprs %d: host is '%s', port %d\n", a==aprs?0:1, host, a->port);
|
||||
err_t res = dns_gethostbyname( host, &a->tcpclient_ipaddr, /*(dns_found_callback)*/_tcp_dns_found, a );
|
||||
|
||||
if(res == ERR_OK) { // Returns immediately of host is IP or in cache
|
||||
tcpclient_state = TCS_DNSRESOLVED;
|
||||
a->tcpclient_state = TCS_DNSRESOLVED;
|
||||
/* fall through */
|
||||
} else if(res == ERR_INPROGRESS) {
|
||||
tcpclient_state = TCS_DNSLOOKUP;
|
||||
a->tcpclient_state = TCS_DNSLOOKUP;
|
||||
break;
|
||||
} else { // failed
|
||||
tcpclient_state = TCS_DISCONNECTED;
|
||||
a->tcpclient_state = TCS_DISCONNECTED;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
@ -228,35 +275,35 @@ void tcpclient_fsm() {
|
|||
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) {
|
||||
a->tcpclient = socket(AF_INET, SOCK_STREAM, 0);
|
||||
int flags = fcntl(a->tcpclient, F_GETFL);
|
||||
if (fcntl(a->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));
|
||||
sock_info.sin_addr.s_addr = a->tcpclient_ipaddr.u_addr.ip4.addr;
|
||||
sock_info.sin_port = htons( a->port );
|
||||
err_t res = connect(a->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;
|
||||
a->tcpclient_state = TCS_CONNECTING;
|
||||
} else {
|
||||
close(tcpclient);
|
||||
tcpclient_state = TCS_DISCONNECTED;
|
||||
close(a->tcpclient);
|
||||
a->tcpclient_state = TCS_DISCONNECTED;
|
||||
}
|
||||
} else {
|
||||
tcpclient_state = TCS_CONNECTED;
|
||||
tcpclient_sendlogin();
|
||||
a->tcpclient_state = TCS_CONNECTED;
|
||||
tcpclient_sendlogin(a);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TCS_CONNECTING:
|
||||
{
|
||||
// Poll to see if we are now connected
|
||||
res = select(tcpclient+1, NULL, &fdset, &fdeset, &selto);
|
||||
res = select(a->tcpclient+1, NULL, &fdset, &fdeset, &selto);
|
||||
if(res<0) {
|
||||
Serial.println("TNS_CONNECTING: select error");
|
||||
goto error;
|
||||
|
|
@ -267,22 +314,22 @@ void tcpclient_fsm() {
|
|||
|
||||
int sockerr;
|
||||
socklen_t len = (socklen_t)sizeof(int);
|
||||
if (getsockopt(tcpclient, SOL_SOCKET, SO_ERROR, (void*)(&sockerr), &len) < 0) {
|
||||
if (getsockopt(a->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);
|
||||
Serial.printf("select returing %d. isset:%d iseset:%d sockerr:%d\n", res, FD_ISSET(a->tcpclient, &fdset), FD_ISSET(a->tcpclient, &fdeset), sockerr);
|
||||
if(sockerr) {
|
||||
Serial.printf("APRS connect error: %s\n", strerror(sockerr));
|
||||
goto error;
|
||||
}
|
||||
tcpclient_state = TCS_CONNECTED;
|
||||
tcpclient_sendlogin();
|
||||
a->tcpclient_state = TCS_CONNECTED;
|
||||
tcpclient_sendlogin(a);
|
||||
}
|
||||
break;
|
||||
|
||||
case TCS_CONNECTED:
|
||||
{
|
||||
res = select(tcpclient+1, &fdset, NULL, NULL, &selto);
|
||||
res = select(a->tcpclient+1, &fdset, NULL, NULL, &selto);
|
||||
if(res<0) {
|
||||
Serial.println("TCS_CONNECTING: select error");
|
||||
goto error;
|
||||
|
|
@ -291,15 +338,15 @@ void tcpclient_fsm() {
|
|||
}
|
||||
// Read data
|
||||
char buf[512+1];
|
||||
res = read(tcpclient, buf, 512);
|
||||
res = read(a->tcpclient, buf, 512);
|
||||
if(res<=0) {
|
||||
close(tcpclient);
|
||||
tcpclient_state = TCS_DISCONNECTED;
|
||||
close(a->tcpclient);
|
||||
a->tcpclient_state = TCS_DISCONNECTED;
|
||||
} else {
|
||||
buf[res] = 0;
|
||||
Serial.printf("tcpclient data (len=%d):", res);
|
||||
Serial.write( (uint8_t *)buf, res );
|
||||
last_in = millis();
|
||||
a->last_in = millis();
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
|
@ -311,8 +358,8 @@ void tcpclient_fsm() {
|
|||
return;
|
||||
|
||||
error:
|
||||
close(tcpclient);
|
||||
tcpclient_state = TCS_DISCONNECTED;
|
||||
close(a->tcpclient);
|
||||
a->tcpclient_state = TCS_DISCONNECTED;
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
@ -338,7 +385,10 @@ String ConnAPRS::getStatus() {
|
|||
else strlcat(buf, "KISS TNC: server active, idle<br>", 1024 );
|
||||
// APRS client
|
||||
if(sonde.config.tcpfeed.active==0) strlcat(buf, "APRS: disabled", 1024);
|
||||
else snprintf( buf+strlen(buf), 1024-strlen(buf), "APRS: %s [%s]", aprsstate2str(tcpclient_state), sonde.config.tcpfeed.host);
|
||||
else {
|
||||
snprintf( buf+strlen(buf), 1024-strlen(buf), "APRS: %s [%s]<br>", aprsstate2str(aprs[0].tcpclient_state), sonde.config.tcpfeed.host);
|
||||
snprintf( buf+strlen(buf), 1024-strlen(buf), "APRS2: %s [%s]", aprsstate2str(aprs[1].tcpclient_state), sonde.config.tcpfeed.host2);
|
||||
}
|
||||
return String(buf);
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -142,7 +142,9 @@ void MQTT::publishPacket(SondeInfo *si)
|
|||
}
|
||||
|
||||
String MQTT::getStatus() {
|
||||
return String("");
|
||||
if(!sonde.config.mqtt.active) return String("disabled");
|
||||
if(mqttClient.connected()) return String("connected");
|
||||
else return String("not connected");
|
||||
}
|
||||
|
||||
String MQTT::getName() {
|
||||
|
|
|
|||
|
|
@ -39,9 +39,9 @@ String ConnSystem::getStatus() {
|
|||
|
||||
uint32_t nuptime = uptime - netup_time;
|
||||
uint16_t nup_d = nuptime / (24*3600);
|
||||
netup_time -= (24*3600) * nup_d;
|
||||
nuptime -= (24*3600) * nup_d;
|
||||
uint16_t nup_h = nuptime / 3600;
|
||||
netup_time -= 3600 * nup_h;
|
||||
nuptime -= 3600 * nup_h;
|
||||
uint16_t nup_m = nuptime / 60;
|
||||
uint16_t nup_s = nuptime - 60 * nup_m;
|
||||
|
||||
|
|
|
|||
|
|
@ -11,6 +11,7 @@ struct StationPos gpsPos;
|
|||
// Station position to use (from GPS or fixed)
|
||||
struct StationPos posInfo;
|
||||
|
||||
static int gotNMEA = 0;
|
||||
|
||||
/* SH_LOC_OFF: never send position information to SondeHub
|
||||
SH_LOC_FIXED: send fixed position (if specified in config) to sondehub
|
||||
|
|
@ -100,9 +101,11 @@ void gpsTask(void *parameter) {
|
|||
|
||||
while (1) {
|
||||
while (Serial2.available()) {
|
||||
if(gotNMEA == 0) gotNMEA = -1; // at least we got *something*
|
||||
char c = Serial2.read();
|
||||
//Serial.print(c);
|
||||
if (nmea.process(c)) {
|
||||
gotNMEA = 1;
|
||||
gpsPos.valid = nmea.isValid();
|
||||
if (gpsPos.valid) {
|
||||
gpsPos.lon = nmea.getLongitude() * 0.000001;
|
||||
|
|
@ -278,3 +281,33 @@ void parseGpsJson(char *data, int len) {
|
|||
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);
|
||||
}
|
||||
|
||||
|
||||
|
||||
// We implement the interface for showing the status only, the other functions remain empty...
|
||||
void ConnGPS::init() { }
|
||||
void ConnGPS::netsetup() { }
|
||||
void ConnGPS::updateSonde( SondeInfo *si ) { }
|
||||
void ConnGPS::updateStation( PosInfo *pi ) { }
|
||||
|
||||
String ConnGPS::getName() {
|
||||
return String("GPS");
|
||||
}
|
||||
|
||||
String ConnGPS::getStatus() {
|
||||
char status[256];
|
||||
|
||||
strlcpy(status, "On-board GPS: ", 256);
|
||||
if(sonde.config.gps_rxd==-1) strlcat(status, "disabled<br>", 256);
|
||||
else if(gotNMEA==0) strlcat(status, "no data<br>", 256);
|
||||
else if(gotNMEA<0) strlcat(status, "no NMEA data<br>", 256);
|
||||
else strlcat(status, "ok<br>", 256);
|
||||
int pos = strlen(status);
|
||||
snprintf(status + pos, 256-pos, "GPS: valid=%d lat=%.6f lon=%.6f alt=%d<br>", gpsPos.valid, gpsPos.lat, gpsPos.lon, gpsPos.alt);
|
||||
pos = strlen(status);
|
||||
snprintf(status + pos, 256-pos, "Using station position: valid=%d lat=%.6f lon=%.6f<br>", posInfo.valid, posInfo.lat, posInfo.lon);
|
||||
return String(status);
|
||||
}
|
||||
|
||||
|
||||
ConnGPS connGPS;
|
||||
|
|
|
|||
|
|
@ -5,6 +5,8 @@
|
|||
#include <inttypes.h>
|
||||
#include "Sonde.h"
|
||||
|
||||
#include "conn.h"
|
||||
|
||||
enum { SH_LOC_OFF, SH_LOC_FIXED, SH_LOC_CHASE, SH_LOC_AUTO };
|
||||
|
||||
|
||||
|
|
@ -25,7 +27,6 @@ struct StationPos {
|
|||
|
||||
extern struct StationPos gpsPos, posInfo;
|
||||
|
||||
|
||||
// Initialize GPS chip
|
||||
void initGPS();
|
||||
|
||||
|
|
@ -35,4 +36,29 @@ void parseGpsJson(char *data, int len);
|
|||
// Update position from static config
|
||||
void fixedToPosInfo();
|
||||
|
||||
|
||||
// We implement the connector interface for the GPS position just to provide the status in a uniform way....
|
||||
class ConnGPS : 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 );
|
||||
|
||||
String getStatus();
|
||||
|
||||
String getName();
|
||||
};
|
||||
|
||||
extern ConnGPS connGPS;
|
||||
|
||||
|
||||
#endif
|
||||
|
|
|
|||
|
|
@ -1,4 +1,4 @@
|
|||
const char *version_name = "rdzTTGOsonde";
|
||||
const char *version_id = "dev20240813";
|
||||
const char *version_id = "dev20240814";
|
||||
const int SPIFFS_MAJOR=3;
|
||||
const int SPIFFS_MINOR=0;
|
||||
const int SPIFFS_MINOR=1;
|
||||
|
|
|
|||
Loading…
Reference in New Issue