kopia lustrzana https://github.com/dl9rdz/rdz_ttgo_sonde
Merge branch 'dl9rdz:devel' into devel
commit
d174b198bd
|
@ -0,0 +1,18 @@
|
|||
|
||||
Important behaviour of WiFiClient:
|
||||
|
||||
If anything goes wrong in a read or write operation on a WiFiClient, it internally
|
||||
will call WiFiClient.stop(), which sets _rxBuffer to NULL and connected to false.
|
||||
|
||||
Subsequently, any function call to WiFiClient that uses _rxBuffer will cause an
|
||||
>>> Guru Meditation Error: Core 1 panic'ed (LoadProhibited). Exception was unhandled.
|
||||
error and subsequent reboot.
|
||||
|
||||
available() is safe to call (it checks that rxBuffer is not null)
|
||||
write() is safe to call (it checks that connected is true)
|
||||
but read() and peek() are not.
|
||||
|
||||
This has been fixed in newer versions of the esp library, see
|
||||
https://github.com/espressif/arduino-esp32/commit/cb7aef1e886ffe43213f9a090e0a8968205a41df#diff-0d8101826fd3df09b38bef2aeca6d093de76841daf38f65f4fefbf6b56da8f81
|
||||
|
||||
So there is at least one reason to eventually upgrade to 2.0.0. Currently we stick to 1.0.6.
|
|
@ -26,7 +26,7 @@ Manufacturer | Model | Position | Temperature | Humidity | Pressure
|
|||
Vaisala | RS92-SGP/NGP | :heavy_check_mark: | :heavy_check_mark: | :x: | :x:
|
||||
Vaisala | RS41-SG/SGP/SGM | :heavy_check_mark: | :heavy_check_mark: | :heavy_check_mark: | :heavy_check_mark:
|
||||
Graw | DFM06/09/17 | :heavy_check_mark: | :x: | :x: | :x:
|
||||
Meteomodem | M10 | :heavy_check_mark: | :x: | :x: | Not Sent
|
||||
Meteomodem | M10 | :heavy_check_mark: | :heavy_checkmark: | :x: | Not Sent
|
||||
Meteomodem | M20 | :heavy_check_mark: | :x: | :x: | Not Sent
|
||||
Meteo-Radiy | MP3-H1 (MRZ-H1) | :heavy_check_mark: | :x: | :x: | :x:
|
||||
|
||||
|
|
|
@ -503,7 +503,7 @@ void addSondeStatus(char *ptr, int i)
|
|||
struct tm ts;
|
||||
SondeInfo *s = &sonde.sondeList[i];
|
||||
strcat(ptr, "<table>");
|
||||
sprintf(ptr + strlen(ptr), "<tr><td id=\"sfreq\">%3.3f MHz, Type: %s</td><tr><td>ID: %s", s->freq, sondeTypeLongStr[s->type],
|
||||
sprintf(ptr + strlen(ptr), "<tr><td id=\"sfreq\">%3.3f MHz, Type: %s</td><tr><td>ID: %s", s->freq, sondeTypeLongStr[sonde.realType(s)],
|
||||
s->d.validID ? s->d.id : "<?""?>");
|
||||
if (s->d.validID && (TYPE_IS_DFM(s->type) || TYPE_IS_METEO(s->type) || s->type == STYPE_MP3H) ) {
|
||||
sprintf(ptr + strlen(ptr), " (ser: %s)", s->d.ser);
|
||||
|
@ -548,7 +548,7 @@ const char *createLiveJson() {
|
|||
|
||||
SondeInfo *s = &sonde.sondeList[sonde.currentSonde];
|
||||
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[s->type]);
|
||||
s->rssi, s->d.vframe, s->d.time, s->d.id, s->freq, sondeTypeStr[sonde.realType(s)]);
|
||||
|
||||
if ( !isnan(s->d.lat) && !isnan(s->d.lon) )
|
||||
sprintf(ptr + strlen(ptr), ", \"lat\": %.6f, \"lon\": %.6f", s->d.lat, s->d.lon);
|
||||
|
@ -1309,7 +1309,7 @@ void addSondeStatusKML(char *ptr, int i)
|
|||
sprintf(ptr + strlen(ptr), "<Placemark id=\"%s\"><name>%s</name><Point><altitudeMode>absolute</altitudeMode><coordinates>%.6f,%.6f,%.0f</coordinates></Point><description>%3.3f MHz, Type: %s, h=%.0fm</description></Placemark>",
|
||||
s->d.id, s->d.id,
|
||||
s->d.lon, s->d.lat, s->d.alt,
|
||||
s->freq, sondeTypeStr[s->type], s->d.alt);
|
||||
s->freq, sondeTypeStr[sonde.realType(s)], s->d.alt);
|
||||
}
|
||||
|
||||
const char *createKMLDynamic() {
|
||||
|
@ -2528,21 +2528,20 @@ void loopDecoder() {
|
|||
Serial.print("sending: "); Serial.println(raw);
|
||||
tncclient.write(raw, rawlen);
|
||||
}
|
||||
if(sonde.config.tcpfeed.active) {
|
||||
static unsigned long lasttcp = 0;
|
||||
static bool loginok = false;
|
||||
if( tcpclient.disconnected()) {
|
||||
tcpclient.connect(sonde.config.tcpfeed.host, sonde.config.tcpfeed.port);
|
||||
}
|
||||
else if( tcpclient.connected() ) {
|
||||
unsigned long now = millis();
|
||||
if( (now-lasttcp) > sonde.config.tcpfeed.highrate*1000L ) {
|
||||
strcat(str,"\r\n");
|
||||
Serial.print(str);
|
||||
tcpclient.write(str, strlen(str));
|
||||
lasttcp = now;
|
||||
}
|
||||
}
|
||||
if (sonde.config.tcpfeed.active) {
|
||||
static unsigned long lasttcp = 0;
|
||||
if ( tcpclient.disconnected()) {
|
||||
tcpclient.connect(sonde.config.tcpfeed.host, sonde.config.tcpfeed.port);
|
||||
}
|
||||
else if ( tcpclient.connected() ) {
|
||||
unsigned long now = millis();
|
||||
if ( (now - lasttcp) > sonde.config.tcpfeed.highrate * 1000L ) {
|
||||
strcat(str, "\r\n");
|
||||
Serial.print(str);
|
||||
tcpclient.write(str, strlen(str));
|
||||
lasttcp = now;
|
||||
}
|
||||
}
|
||||
}
|
||||
#if FEATURE_CHASEMAPPER
|
||||
if (sonde.config.cm.active) {
|
||||
|
@ -2574,7 +2573,7 @@ void loopDecoder() {
|
|||
char raw[1024];
|
||||
char gps[128];
|
||||
const char *typestr = s->d.typestr;
|
||||
if (*typestr == 0) typestr = sondeTypeStr[s->type];
|
||||
if (*typestr == 0) typestr = sondeTypeStr[sonde.realType(s)];
|
||||
// TODO: only if GPS is valid...
|
||||
if (gpsPos.valid) {
|
||||
snprintf(gps, 128, ", \"gpslat\": %f,"
|
||||
|
@ -2586,6 +2585,14 @@ void loopDecoder() {
|
|||
} else {
|
||||
*gps = 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,"
|
||||
|
@ -2623,12 +2630,12 @@ void loopDecoder() {
|
|||
s->d.ser,
|
||||
(int)s->d.validID,
|
||||
s->launchsite,
|
||||
s->d.lat,
|
||||
s->d.lon,
|
||||
s->d.alt,
|
||||
s->d.vs,
|
||||
s->d.hs,
|
||||
s->d.dir,
|
||||
lat,
|
||||
lon,
|
||||
alt,
|
||||
vs,
|
||||
hs,
|
||||
dir,
|
||||
s->d.sats,
|
||||
s->d.validPos,
|
||||
s->d.time,
|
||||
|
@ -2776,13 +2783,13 @@ void enableNetwork(bool enable) {
|
|||
MDNS.end();
|
||||
connected = false;
|
||||
}
|
||||
tcpclient.onConnect([](void *arg, AsyncClient *s) {
|
||||
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) {
|
||||
tcpclient.onData([](void *arg, AsyncClient * c, void *data, size_t len) {
|
||||
Serial.write((const uint8_t *)data, len);
|
||||
});
|
||||
Serial.println("enableNetwork done");
|
||||
|
@ -3511,9 +3518,16 @@ void sondehub_station_update(WiFiClient * client, struct st_sondehub * conf) {
|
|||
Serial.println(data);
|
||||
Serial.println("Waiting for response");
|
||||
// TODO: better do this asyncrhonously
|
||||
String response = client->readString();
|
||||
Serial.println(response);
|
||||
Serial.println("Response done...");
|
||||
// At least, do this safely. See Notes-on-Using-WiFiClient.txt for details
|
||||
// If any of the client->print failed before (remote end closed connection),
|
||||
// then calling client->read will cause a LoadProhibited exception
|
||||
if(client->connected()) {
|
||||
String response = client->readString();
|
||||
Serial.println(response);
|
||||
Serial.println("Response done...");
|
||||
} else {
|
||||
Serial.println("SH client connection closed\n");
|
||||
}
|
||||
//client->stop();
|
||||
}
|
||||
|
||||
|
@ -3647,11 +3661,8 @@ void sondehub_send_data(WiFiClient * client, SondeInfo * s, struct st_sondehub *
|
|||
char rs_msg[MSG_SIZE];
|
||||
char *w;
|
||||
struct tm ts;
|
||||
uint8_t realtype = s->type;
|
||||
// config setting M10 and M20 will both decode both types, so use the real type that was decoded
|
||||
if (TYPE_IS_METEO(realtype)) {
|
||||
realtype = s->d.subtype == 1 ? STYPE_M10 : STYPE_M20;
|
||||
}
|
||||
uint8_t realtype = sonde.realType(s);
|
||||
|
||||
// For DFM, s->d.time is data from subframe DAT8 (gps date/hh/mm), and sec is from DAT1 (gps sec/usec)
|
||||
// For all others, sec should always be 0 and time the exact time in seconds
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
# S scan list entry info: l/empty: launch site name, #=entry nr, t=total entries, a=active entries, /: #/t
|
||||
# K RS41 kill timer values: Kl launch timer, Kb burst timer, Kc kill countdown
|
||||
# format: K_4: h:mm k_6: h:mm:ss k_s: sssss, nothing shown for other sonde
|
||||
# Mx telemetry value x (t temp p preassure h hyg) [not yet implemented, maybe some day in future]
|
||||
# Mx telemetry value x (t temp p preassure h hyg b battery)
|
||||
# Gx GPS-related data
|
||||
# raw data from GPS: GA, GO, GH, GC: LAtitude, lOngitude, Altutide(Height), Course over ground
|
||||
# relative to sonde: GD, GI, GB: Distance, dIrection (absolute), relative Bearing
|
||||
|
@ -203,7 +203,7 @@ timeaction=#,#,#
|
|||
7,0=gV
|
||||
7,2=xd=
|
||||
7,4=gD
|
||||
7,12=gI°
|
||||
7,12=gI°
|
||||
|
||||
############
|
||||
@BatteryOLED
|
||||
|
@ -224,3 +224,18 @@ fonts=0,1
|
|||
6,0=xTemp:
|
||||
6,5=bT C
|
||||
|
||||
#############
|
||||
@Meteo
|
||||
timer=-1,-1,-1
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,#
|
||||
fonts=0,1
|
||||
0,0=Is
|
||||
0,9=f
|
||||
1,12=t
|
||||
2,0=xTelemetry Data
|
||||
4,0=Mt°C
|
||||
4,9=Mh%rH
|
||||
6,0=MphPa
|
||||
6,11=MbV
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
# S scan list entry info: l/empty: launch site name, #=entry nr, t=total entries, a=active entries, /: #/t
|
||||
# K RS41 kill timer values: Kl launch timer, Kb burst timer, Kc kill countdown
|
||||
# format: K_4: h:mm k_6: h:mm:ss k_s: sssss, nothing shown for other sonde
|
||||
# Mx telemetry value x (t temp p preassure h hyg) [not yet implemented, maybe some day in future]
|
||||
# Mx telemetry value x (t temp p preassure h hyg b batt)
|
||||
# Gx GPS-related data
|
||||
# raw data from GPS: GA, GO, GH, GC: LAtitude, lOngitude, Altutide(Height), Course over ground
|
||||
# relative to sonde: GD, GI, GB: Distance, dIrection (absolute), relative Bearing
|
||||
|
@ -571,3 +571,32 @@ color=639AFF
|
|||
color=FF0000,000000
|
||||
12.7,0.4=Q4
|
||||
12.7,18=bVV
|
||||
|
||||
#################
|
||||
@TelemetryData
|
||||
scale=22,13
|
||||
timer=-1,-1,N
|
||||
key1action=+,0,F,W
|
||||
key2action=>,#,#,#
|
||||
timeaction=#,#,0
|
||||
fonts=5,6
|
||||
color=FFD700
|
||||
0,0,10.5=Is
|
||||
color=0000FF
|
||||
0,11,-5.5=f
|
||||
1,0,4=t
|
||||
1,10.5,-6=c
|
||||
color=00ff00
|
||||
2,0,7=L
|
||||
3,0,7=O
|
||||
color=FFA500
|
||||
2,9.5,-7=a
|
||||
2.8,9.5,-7=vm/s
|
||||
color=AA5522
|
||||
3.6,9.5,-7=hkkm/h
|
||||
color=FFFFFF
|
||||
4.4,0=xTelemetry Data:
|
||||
5.3,0=Mt C
|
||||
5.3,9=Mh%rH
|
||||
6.5,0=MphPa
|
||||
6.5,11=MbV
|
||||
|
|
|
@ -809,6 +809,10 @@ void Display::parseDispElement(char *text, DispEntry *de)
|
|||
de->extra = strdup(text+1);
|
||||
//Serial.printf("parsing 'f' entry: extra is '%s'\n", de->extra);
|
||||
break;
|
||||
case 'm':
|
||||
de->func = disp.drawTelemetry;
|
||||
de->extra = strdup(text+1);
|
||||
break;
|
||||
case 'n':
|
||||
// IP address / small always uses tiny font on TFT for backward compatibility
|
||||
// Large font can be used arbitrarily
|
||||
|
@ -1283,6 +1287,45 @@ void Display::drawSite(DispEntry *de) {
|
|||
drawString(de, buf);
|
||||
}
|
||||
void Display::drawTelemetry(DispEntry *de) {
|
||||
rdis->setFont(de->fmt);
|
||||
float value=0;
|
||||
memset(buf, ' ', 16);
|
||||
switch(de->extra[0]) {
|
||||
case 't':
|
||||
value = sonde.si()->d.temperature;
|
||||
if(!isnan(value)) {
|
||||
sprintf(buf, "%5.1f", value);
|
||||
strcat(buf, de->extra+1);
|
||||
}
|
||||
buf[5+strlen(de->extra+1)] = 0;
|
||||
break;
|
||||
case 'p':
|
||||
value = sonde.si()->d.pressure;
|
||||
if(!isnan(value)) {
|
||||
if(value>=1000) sprintf(buf, "%6.1f", value);
|
||||
else sprintf(buf, "%6.2f", value);
|
||||
strcat(buf, de->extra+1);
|
||||
}
|
||||
buf[6+strlen(de->extra+1)] = 0;
|
||||
break;
|
||||
case 'h':
|
||||
value = sonde.si()->d.relativeHumidity;
|
||||
if(!isnan(value)) {
|
||||
sprintf(buf, "%4.1f", value);
|
||||
strcat(buf, de->extra+1);
|
||||
}
|
||||
buf[4+strlen(de->extra+1)] = 0;
|
||||
break;
|
||||
case 'b':
|
||||
value = sonde.si()->d.batteryVoltage;
|
||||
if(!isnan(value)) {
|
||||
snprintf(buf, 5, "%4.2f", value);
|
||||
strcat(buf, de->extra+1);
|
||||
}
|
||||
buf[5+strlen(de->extra+1)] = 0;
|
||||
break;
|
||||
}
|
||||
drawString(de,buf);
|
||||
}
|
||||
|
||||
void Display::drawKilltimer(DispEntry *de) {
|
||||
|
@ -1320,7 +1363,6 @@ void Display::drawKilltimer(DispEntry *de) {
|
|||
#define PI (3.1415926535897932384626433832795)
|
||||
#endif
|
||||
// defined by Arduino.h #define radians(x) ( (x)*180.0F/PI )
|
||||
#define FAKEGPS 0
|
||||
|
||||
extern int lastCourse; // from RX_FSK.ino
|
||||
|
||||
|
@ -1333,42 +1375,22 @@ float calcLatLonDist(float lat1, float lon1, float lat2, float lon2) {
|
|||
}
|
||||
|
||||
void Display::calcGPS() {
|
||||
// base data
|
||||
#if 0
|
||||
#if FAKEGPS
|
||||
gpsValid = true;
|
||||
gpsLat = 48.9;
|
||||
gpsLon = 13.3;
|
||||
gpsAlt = 33000;
|
||||
static int tmpc=0;
|
||||
tmpc = (tmpc+5)%360;
|
||||
gpsCourse = tmpc;
|
||||
#else
|
||||
gpsValid = nmea.isValid();
|
||||
gpsLon = nmea.getLongitude()*0.000001;
|
||||
gpsLat = nmea.getLatitude()*0.000001;
|
||||
long alt = 0;
|
||||
nmea.getAltitude(alt); gpsAlt=(int)(alt/1000);
|
||||
gpsCourse = (int)(nmea.getCourse()/1000);
|
||||
gpsCourseOld = false;
|
||||
if(gpsCourse==0) {
|
||||
// either north or not new
|
||||
if(lastCourse!=0) // use old value...
|
||||
{
|
||||
gpsCourseOld = true;
|
||||
gpsCourse = lastCourse;
|
||||
}
|
||||
float mylat = sonde.config.rxlat;
|
||||
float mylon = sonde.config.rxlon;
|
||||
bool valid = !(isnan(mylat)||isnan(mylon));
|
||||
if( gpsPos.valid) {
|
||||
mylat = gpsPos.lat;
|
||||
mylon = gpsPos.lon;
|
||||
valid = true;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
// distance
|
||||
if( gpsPos.valid && (sonde.si()->d.validPos&0x03)==0x03 && (layout->usegps&GPSUSE_DIST)) {
|
||||
if( valid && (sonde.si()->d.validPos&0x03)==0x03 && (layout->usegps&GPSUSE_DIST)) {
|
||||
gpsDist = (int)calcLatLonDist(gpsPos.lat, gpsPos.lon, sonde.si()->d.lat, sonde.si()->d.lon);
|
||||
} else {
|
||||
gpsDist = -1;
|
||||
}
|
||||
// bearing
|
||||
if( gpsPos.valid && (sonde.si()->d.validPos&0x03)==0x03 && (layout->usegps&GPSUSE_BEARING)) {
|
||||
if( valid && (sonde.si()->d.validPos&0x03)==0x03 && (layout->usegps&GPSUSE_BEARING)) {
|
||||
float lat1 = radians(gpsPos.lat);
|
||||
float lat2 = radians(sonde.si()->d.lat);
|
||||
float lon1 = radians(gpsPos.lon);
|
||||
|
@ -1428,7 +1450,7 @@ void Display::drawGPS(DispEntry *de) {
|
|||
if( (sonde.si()->d.validPos&0x03)!=0x03 ) {
|
||||
snprintf(buf, 16, "no pos ");
|
||||
if(de->extra && *de->extra=='5') buf[5]=0;
|
||||
} else if(!gpsPos.valid) {
|
||||
} else if( disp.gpsDist < 0 ) {
|
||||
snprintf(buf, 16, "no gps ");
|
||||
if(de->extra && *de->extra=='5') buf[5]=0;
|
||||
} else {
|
||||
|
@ -1448,7 +1470,7 @@ void Display::drawGPS(DispEntry *de) {
|
|||
break;
|
||||
case 'I':
|
||||
// dIrection
|
||||
if( (!gpsPos.valid) || ((sonde.si()->d.validPos&0x03)!=0x03 ) ) {
|
||||
if( disp.gpsDir<0 ) { // 0..360 valid, -1 invalid
|
||||
drawString(de, "---");
|
||||
break;
|
||||
}
|
||||
|
@ -1460,7 +1482,7 @@ void Display::drawGPS(DispEntry *de) {
|
|||
break;
|
||||
case 'B':
|
||||
// relative bearing
|
||||
if( (!gpsPos.valid) || ((sonde.si()->d.validPos&0x03)!=0x03 ) ) {
|
||||
if( disp.gpsBear < 0 ) { // 0..360 valid, -1 invalid
|
||||
drawString(de, "---");
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -328,6 +328,25 @@ int M10M20::decodeframeM10(uint8_t *data) {
|
|||
if(dir<0) dir+=360;
|
||||
si->dir = dir;
|
||||
si->validPos = 0x3f;
|
||||
// m10 temp
|
||||
const float p0 = 1.07303516e-03, p1 = 2.41296733e-04, p2 = 2.26744154e-06, p3 = 6.52855181e-08;
|
||||
const float Rs[3] = { 12.1e3 , 36.5e3 , 475.0e3 };
|
||||
const float Rp[3] = { 1e20 , 330.0e3 , 2000.0e3 };
|
||||
uint8_t sct = data[62];
|
||||
float rt = getint16_r(data+63) & (0xFFF);
|
||||
float T = NAN;
|
||||
if(rt!=0 && sct<3) {
|
||||
rt = (4095-rt)/rt - (Rs[sct]/Rp[sct]);
|
||||
if(rt>0) {
|
||||
rt = Rs[sct] / rt;
|
||||
if(rt>0) {
|
||||
rt = log(rt);
|
||||
rt = 1/( p0 + p1*rt + p2*rt*rt + p3*rt*rt*rt ) - 273.15;
|
||||
if(rt>-99 && rt<50) { T = rt; }
|
||||
}
|
||||
}
|
||||
}
|
||||
si->temperature = T;
|
||||
|
||||
uint32_t gpstime = getint32(data+10);
|
||||
uint16_t gpsweek = getint16(data+32);
|
||||
|
|
|
@ -716,4 +716,9 @@ void Sonde::clearDisplay() {
|
|||
disp.rdis->clear();
|
||||
}
|
||||
|
||||
SondeType Sonde::realType(SondeInfo *si) {
|
||||
if(TYPE_IS_METEO(si->type)) { return si->d.subtype==1 ? STYPE_M10:STYPE_M20; }
|
||||
else return si->type;
|
||||
}
|
||||
|
||||
Sonde sonde = Sonde();
|
||||
|
|
|
@ -319,6 +319,8 @@ public:
|
|||
// moved to heap, saving space in .bss
|
||||
//SondeInfo sondeList[MAXSONDE+1];
|
||||
SondeInfo *sondeList;
|
||||
// helper function for type string
|
||||
static SondeType realType(SondeInfo *si);
|
||||
|
||||
Sonde();
|
||||
void defaultConfig();
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
#include <inttypes.h>
|
||||
#include "aprs.h"
|
||||
|
||||
extern const char *version_name;
|
||||
#if 0
|
||||
int openudp(const char *ip, int port, struct sockaddr_in *si) {
|
||||
int fd;
|
||||
|
@ -255,11 +256,10 @@ static uint32_t dao91(double x)
|
|||
} /* end dao91() */
|
||||
|
||||
|
||||
char b[201];
|
||||
char b[251];
|
||||
//char raw[201];
|
||||
|
||||
char *aprs_senddata(SondeInfo *si, const char *usercall, const char *sym) {
|
||||
// float lat, float lon, float alt, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym, const char *comm)
|
||||
SondeData *s = &(si->d);
|
||||
*b=0;
|
||||
aprsstr_append(b, usercall);
|
||||
|
@ -288,7 +288,7 @@ char *aprs_senddata(SondeInfo *si, const char *usercall, const char *sym) {
|
|||
snprintf(b+i, APRS_MAXLEN-i, "%03d%02d.%02d%c%c", loni, lonm/100, lonm%100, s->lon<0?'W':'E', sym[1]);
|
||||
if(s->hs>0.5) {
|
||||
i=strlen(b);
|
||||
snprintf(b+i, APRS_MAXLEN-i, "%03d/%03d", realcard(s->dir+1.5), realcard(s->hs*1.0/KNOTS+0.5));
|
||||
snprintf(b+i, APRS_MAXLEN-i, "%03d/%03d", realcard(s->dir+1.5), realcard(s->hs*3.6/KNOTS+0.5));
|
||||
}
|
||||
if(s->alt>0.5) {
|
||||
i=strlen(b);
|
||||
|
@ -299,13 +299,25 @@ char *aprs_senddata(SondeInfo *si, const char *usercall, const char *sym) {
|
|||
snprintf(b+i, APRS_MAXLEN-i, "!w%c%c!", 33+dao91(s->lat), 33+dao91(s->lon));
|
||||
|
||||
// ??? strcat(b, "&");
|
||||
char comm[100];
|
||||
snprintf(comm, 100, "Clb=%.1fm/s %.3fMHz Type=%s", s->vs, si->freq, sondeTypeStr[si->type]);
|
||||
strcat(b, comm);
|
||||
if( TYPE_IS_DFM(si->type) || TYPE_IS_METEO(si->type) ) {
|
||||
snprintf(comm, 100, " ser=%s", s->ser);
|
||||
strcat(b, comm);
|
||||
i=strlen(b);
|
||||
i += snprintf(b+i, APRS_MAXLEN-i, "Clb=%.1fm/s ", s->vs );
|
||||
if( !isnan(s->pressure) ) {
|
||||
sprintf(b+strlen(b), "p=%.1fhPa ", s->pressure);
|
||||
}
|
||||
if( !isnan(s->temperature) ) {
|
||||
sprintf(b+strlen(b), "t=%.1fC ", s->temperature);
|
||||
}
|
||||
if( !isnan(s->relativeHumidity) ) {
|
||||
sprintf(b+strlen(b), "h=%.1f%% ", s->relativeHumidity);
|
||||
}
|
||||
sprintf(b+strlen(b), "%.3fMHz Type=%s ", si->freq, sondeTypeStr[sonde.realType(si)]);
|
||||
if( s->countKT != 0xffff && s->vframe - s->crefKT < 51 ) {
|
||||
sprintf(b+strlen(b), "TxOff=%dh%dm ", s->countKT/3600, (s->countKT-s->countKT/3600*3600)/60);
|
||||
}
|
||||
if( TYPE_IS_DFM(si->type) || TYPE_IS_METEO(si->type) ) {
|
||||
sprintf(b + strlen(b), "ser=%s ", s->ser);
|
||||
}
|
||||
sprintf(b + strlen(b), "%s", version_name);
|
||||
return b;
|
||||
}
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
const char *version_name = "rdzTTGOsonde";
|
||||
const char *version_id = "devel20210923";
|
||||
const char *version_id = "devel20210925";
|
||||
const int SPIFFS_MAJOR=2;
|
||||
const int SPIFFS_MINOR=16;
|
||||
|
|
Ładowanie…
Reference in New Issue