kopia lustrzana https://github.com/dl9rdz/rdz_ttgo_sonde
first test: tnc tcp/ip server for APRSdroid
rodzic
0053c95498
commit
079cb4980d
|
@ -45,6 +45,10 @@ boolean connected = false;
|
|||
WiFiUDP udp;
|
||||
WiFiClient client;
|
||||
|
||||
// KISS over TCP für communicating with APRSdroid
|
||||
WiFiServer tncserver(14580);
|
||||
WiFiClient tncclient;
|
||||
|
||||
|
||||
enum KeyPress { KP_NONE = 0, KP_SHORT, KP_DOUBLE, KP_MID, KP_LONG };
|
||||
|
||||
|
@ -397,6 +401,9 @@ struct st_configitems config_list[] = {
|
|||
{"call", "Call", 8, sonde.config.call},
|
||||
{"passcode", "Passcode", 8, sonde.config.passcode},
|
||||
{"---", "---", -1, NULL},
|
||||
/* KISS tnc settings */
|
||||
{"kisstnc", "KISS TNC (port 14590) (needs reboot)", 0, &sonde.config.kisstnc.active},
|
||||
{"kisstnc.idformat", "DFM ID Format", -2, &sonde.config.kisstnc.idformat},
|
||||
/* AXUDP settings */
|
||||
{"axudp.active", "AXUDP active", -3, &sonde.config.udpfeed.active},
|
||||
{"axudp.host", "AXUDP Host", 63, sonde.config.udpfeed.host},
|
||||
|
@ -631,7 +638,7 @@ const char *handleEditPost(AsyncWebServerRequest *request) {
|
|||
}
|
||||
file.print(content);
|
||||
file.close();
|
||||
if (strcmp(filename.c_str(), "screens.txt")==0) {
|
||||
if (strcmp(filename.c_str(), "screens.txt") == 0) {
|
||||
// screens update => reload
|
||||
disp.initFromFile();
|
||||
}
|
||||
|
@ -1201,6 +1208,9 @@ void setup()
|
|||
sonde.setup();
|
||||
initGPS();
|
||||
|
||||
if (sonde.config.kisstnc.active) {
|
||||
tncserver.begin();
|
||||
}
|
||||
WiFi.onEvent(WiFiEvent);
|
||||
getKeyPress(); // clear key buffer
|
||||
}
|
||||
|
@ -1275,21 +1285,44 @@ void loopDecoder() {
|
|||
Serial.printf("current main is %d, current rxtask is %d\n", sonde.currentSonde, rxtask.currentSonde);
|
||||
}
|
||||
|
||||
|
||||
if ((res & 0xff) == 0 && connected) {
|
||||
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 Bluetooth
|
||||
}
|
||||
Serial.println("");
|
||||
}
|
||||
// wifi (axudp) or bluetooth (bttnc) active => send packet
|
||||
if ((res & 0xff) == 0 && (connected || tncclient.connected() )) {
|
||||
//Send a packet with position information
|
||||
// first check if ID and position lat+lonis ok
|
||||
SondeInfo *s = &sonde.sondeList[rxtask.receiveSonde];
|
||||
if (s->validID && ((s->validPos & 0x03) == 0x03)) {
|
||||
Serial.println("Sending position via UDP");
|
||||
char raw[201];
|
||||
const char *str = aprs_senddata(s->lat, s->lon, s->alt, s->hs, s->dir, s->vs, sondeTypeStr[s->type], s->id, "TE0ST",
|
||||
sonde.config.udpfeed.symbol);
|
||||
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
|
||||
Serial.print("Sending: "); Serial.println(raw);
|
||||
udp.beginPacket(sonde.config.udpfeed.host, sonde.config.udpfeed.port);
|
||||
udp.write((const uint8_t *)raw, rawlen);
|
||||
udp.endPacket();
|
||||
if (connected) {
|
||||
char raw[201];
|
||||
int rawlen = aprsstr_mon2raw(str, raw, APRS_MAXLEN);
|
||||
Serial.println("Sending position via UDP");
|
||||
Serial.print("Sending: "); Serial.println(raw);
|
||||
udp.beginPacket(sonde.config.udpfeed.host, sonde.config.udpfeed.port);
|
||||
udp.write((const uint8_t *)raw, rawlen);
|
||||
udp.endPacket();
|
||||
}
|
||||
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);
|
||||
}
|
||||
}
|
||||
}
|
||||
sonde.updateDisplay();
|
||||
|
@ -1375,6 +1408,7 @@ void enableNetwork(bool enable) {
|
|||
SetupAsyncServer();
|
||||
udp.begin(WiFi.localIP(), LOCALUDPPORT);
|
||||
MDNS.addService("http", "tcp", 80);
|
||||
tncserver.begin();
|
||||
connected = true;
|
||||
} else {
|
||||
MDNS.end();
|
||||
|
|
|
@ -25,6 +25,9 @@ maxsonde=20
|
|||
debug=0
|
||||
# wifi mode: 1=client in background; 2=AP in background; 3=client on startup, ap if failure
|
||||
wifi=3
|
||||
# TCP/IP KISS TNC in port 14590 for APRSdroid (0=disabled, 1=enabled)
|
||||
kisstnc.active = 1
|
||||
|
||||
# display mode: 1=standard 2=fieldmode 3=field w/sondetype
|
||||
display=1
|
||||
#-------------------------------#
|
||||
|
|
|
@ -1,2 +1,2 @@
|
|||
const char *version_name = "RDZ_TTGO_SONDE";
|
||||
const char *version_id = "devel20190609";
|
||||
const char *version_id = "devel20190911";
|
||||
|
|
|
@ -112,6 +112,7 @@ typedef struct st_rdzconfig {
|
|||
// for now, one feed for each type is enough, but might get extended to more?
|
||||
struct st_feedinfo udpfeed; // target for AXUDP messages
|
||||
struct st_feedinfo tcpfeed; // target for APRS-IS TCP connections
|
||||
struct st_kisstnc kisstnc; // target for KISS TNC (via TCP, mainly for APRSdroid)
|
||||
} RDZConfig;
|
||||
|
||||
typedef struct st_sondeinfo {
|
||||
|
|
|
@ -137,6 +137,7 @@ static int mkaprscall(int32_t * p, char raw[],
|
|||
} /* end call() */
|
||||
|
||||
|
||||
|
||||
// returns raw len, 0 in case of error
|
||||
extern int aprsstr_mon2raw(const char *mon, char raw[], int raw_len)
|
||||
{
|
||||
|
@ -207,6 +208,28 @@ extern int aprsstr_mon2raw(const char *mon, char raw[], int raw_len)
|
|||
return p+2;
|
||||
} /* end mon2raw() */
|
||||
|
||||
extern int aprsstr_mon2kiss(const char *mon, char raw[], int raw_len)
|
||||
{
|
||||
char tmp[201];
|
||||
int len = aprsstr_mon2raw(mon, tmp, 201);
|
||||
if(len==0) return 0;
|
||||
int idx=0;
|
||||
raw[idx++] = '\xC0';
|
||||
for(int i=0; i<len-2; i++) { // -2: discard CRC, not used in KISS
|
||||
if(tmp[i]=='\xC0') {
|
||||
raw[idx++] = '\xDB';
|
||||
raw[idx++] = '\xDC';
|
||||
} else if (tmp[i]=='\xDB') {
|
||||
raw[idx++] = '\xDB';
|
||||
raw[idx++] = '\xDD';
|
||||
} else {
|
||||
raw[idx++] = tmp[i];
|
||||
}
|
||||
if(idx>=raw_len)
|
||||
return 0;
|
||||
}
|
||||
return idx;
|
||||
}
|
||||
|
||||
#define FEET (1.0/0.3048)
|
||||
#define KNOTS (1.851984)
|
||||
|
|
|
@ -16,10 +16,18 @@ struct st_feedinfo {
|
|||
int idformat; // 0: dxl 1: real 2: auto
|
||||
};
|
||||
|
||||
// maybe extend for external Bluetooth interface?
|
||||
// internal bluetooth consumes too much memory
|
||||
struct st_kisstnc {
|
||||
bool active;
|
||||
int idformat;
|
||||
};
|
||||
|
||||
|
||||
#define APRS_MAXLEN 201
|
||||
void aprs_gencrctab(void);
|
||||
int aprsstr_mon2raw(const char *mon, char raw[], int raw_len);
|
||||
int aprsstr_mon2kiss(const char *mon, char raw[], int raw_len);
|
||||
char * aprs_senddata(float lat, float lon, float alt, float speed, float dir, float climb, const char *type, const char *objname, const char *usercall, const char *sym);
|
||||
|
||||
|
||||
|
|
Ładowanie…
Reference in New Issue