Compare commits

...

21 Commits

Author SHA1 Message Date
richonguzman
ee25ec6873 checkItOut 2025-02-28 14:20:49 -03:00
richonguzman
60aef00b24 function name correction 2025-02-25 14:15:30 -03:00
richonguzman
72c2c144ae last corrections 2025-02-25 14:01:14 -03:00
richonguzman
a1c552f197 readme update 2025-02-25 13:56:27 -03:00
richonguzman
8ede848199 ready for testing 2025-02-25 13:54:36 -03:00
richonguzman
a4a82b75c5 more testing 2025-02-24 18:49:17 -03:00
richonguzman
64ac924f1f first proposal 2025-02-24 17:57:24 -03:00
richonguzman
bde4a7f042 trim mod 2025-02-24 17:08:53 -03:00
richonguzman
d54b63df22 telemetry conf packet start after first beacon 2025-02-24 16:36:52 -03:00
richonguzman
c3d94d673a height correction with gps 2025-02-24 16:17:01 -03:00
richonguzman
45edf2ffa3 gps satelites indicator 2025-02-24 16:10:02 -03:00
richonguzman
d628de9c9c code cleaned to lighter versions 2025-02-12 15:28:48 -03:00
richonguzman
f879182f62 new mods 2025-02-12 14:15:36 -03:00
richonguzman
c9ed618a8b t-deck readme update 2025-01-22 09:52:22 -03:00
richonguzman
6c7b8f9918 readme update 2025-01-22 09:40:42 -03:00
richonguzman
c2b4b3b92f readme update 2025-01-22 01:35:28 -03:00
richonguzman
f7319ce591 avoid msg TX-RF of telemetry declaration 2025-01-22 00:12:11 -03:00
richonguzman
858162eb9c version and readme update 2025-01-22 00:00:46 -03:00
richonguzman
100b002309 tdeck ready 2025-01-21 23:57:56 -03:00
richonguzman
3acf73bf5f Tdeck working 2025-01-21 23:00:49 -03:00
richonguzman
53675e8084 upload blackList 2025-01-14 15:15:28 -03:00
22 changed files with 428 additions and 211 deletions

View File

@@ -53,6 +53,10 @@ jobs:
chip: esp32
- name: ttgo-t-beam-v1_2_SX1262
chip: esp32
- name: ttgo_t_deck_plus
chip: esp32s3
- name: ttgo_t_deck_GPS
chip: esp32s3
- name: ESP32_DIY_LoRa_A7670
chip: esp32
- name: ESP32_DIY_LoRa_A7670_915

View File

@@ -36,6 +36,8 @@ ____________________________________________________
- TTGO T-Beam V1.0 , V1.1, V1.2 (also variations with SX1262 and SX1268 LoRa Modules).
- T-Deck Plus (and also regular T-Deck with/without GPS).
- HELTEC V2, V3 , Wireless Stick, Wireless Stick Lite, HT-CT62, Wireless Tracker, Wireless Paper.
- QRP Labs LightGateway 1.0.
@@ -52,6 +54,8 @@ ____________________________________________________
## Timeline (Versions):
- 2025.02.25 Objects Rules updated and GPS Boards: Satellites in Screen, Wx Height Correction from GPS Data.
- 2025.01.22 Added LILYGO T-DECK PLUS (and DIY+GPS version) board support.
- 2025.01.11 Added HELTEC V3.2 board support.
- 2025.01.07 TROY_LoRa_APRS board added. GMT in quarter hour fix and Beacon fix for TNC.
- 2025.01.02 Callsign Black List added.

View File

@@ -32,9 +32,9 @@ lib_deps =
arduino-libraries/NTPClient @ 3.2.1
ayushsharma82/ElegantOTA @ 3.1.5
bblanchon/ArduinoJson @ 6.21.3
ESP32Async/AsyncTCP @ 3.3.5
ESP32Async/ESPAsyncWebServer @ 3.7.0
jgromes/RadioLib @ 7.1.0
mathieucarbou/AsyncTCP @ 3.2.5
mathieucarbou/ESPAsyncWebServer @ 3.2.3
mikalhart/TinyGPSPlus @ 1.0.3
display_libs =
adafruit/Adafruit GFX Library @ 1.11.9

BIN
images/Web004-BlackList.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

View File

@@ -5,14 +5,9 @@
#define SCREEN_ADDRESS 0x3C ///< See datasheet for Address; 0x3D for 128x64, 0x3C for 128x32
void cleanTFT();
void displaySetup();
void displayToggle(bool toggle);
bool shouldCleanTFT(const String& header, const String& line1, const String& line2, const String& line3);
bool shouldCleanTFT(const String& header, const String& line1, const String& line2, const String& line3, const String& line4, const String& line5, const String& line6);
void displayShow(const String& header, const String& line1, const String& line2, const String& line3, int wait = 0);
void displayShow(const String& header, const String& line1, const String& line2, const String& line3, const String& line4, const String& line5, const String& line6, int wait = 0);

View File

@@ -20,6 +20,7 @@ namespace STATION_Utils {
void loadBlackList();
bool checkBlackList(const String& callsign);
bool checkObjectTime(const String& packet);
void deleteNotHeard();
void updateLastHeard(const String& station);
bool wasHeard(const String& station);

View File

@@ -16,7 +16,7 @@ extra_configs =
variants/*/platformio.ini
[env]
platform = espressif32 @ 6.7.0
platform = espressif32 @ 6.10.0
board_build.partitions = min_spiffs.csv
framework = arduino
monitor_speed = 115200

View File

@@ -48,12 +48,14 @@ ___________________________________________________________________*/
#include "A7670_utils.h"
#endif
String versionDate = "2025.01.11";
String versionDate = "2025.02.28";
Configuration Config;
WiFiClient espClient;
#ifdef HAS_GPS
HardwareSerial gpsSerial(1);
TinyGPSPlus gps;
uint32_t gpsSatelliteTime = 0;
bool gpsInfoToggle = false;
#endif
uint8_t myWiFiAPIndex = 0;
@@ -152,7 +154,26 @@ void loop() {
BATTERY_Utils::checkIfShouldSleep();
}
thirdLine = Utils::getLocalIP();
#ifdef HAS_GPS
if (Config.beacon.gpsActive) {
if (millis() - gpsSatelliteTime > 5000) {
gpsInfoToggle = !gpsInfoToggle;
gpsSatelliteTime = millis();
}
if (gpsInfoToggle) {
thirdLine = "Satellite(s): ";
String gpsData = String(gps.satellites.value());
if (gpsData.length() < 2) gpsData = "0" + gpsData; // Ensure two-digit formatting
thirdLine += gpsData;
} else {
thirdLine = Utils::getLocalIP();
}
} else {
thirdLine = Utils::getLocalIP();
}
#else
thirdLine = Utils::getLocalIP();
#endif
#ifdef HAS_A7670
if (Config.aprs_is.active && !modemLoggedToAPRSIS) A7670_Utils::APRS_IS_connect();

View File

@@ -298,7 +298,7 @@ namespace APRS_IS_Utils {
receivedMessage = AddresseeAndMessage.substring(AddresseeAndMessage.indexOf(":") + 1);
}
if (receivedMessage.indexOf("?") == 0) {
Utils::println("Received Query APRS-IS : " + packet);
Utils::println("Rx Query (APRS-IS) : " + packet);
String queryAnswer = QUERY_Utils::process(receivedMessage, Sender, true, false);
//Serial.println("---> QUERY Answer : " + queryAnswer.substring(0,queryAnswer.indexOf("\n")));
if (!Config.display.alwaysOn && Config.display.timeout != 0) {
@@ -323,8 +323,8 @@ namespace APRS_IS_Utils {
seventhLine += receivedMessage;
}
} else {
Utils::print("Received Message from APRS-IS : " + packet);
if (STATION_Utils::wasHeard(Addressee)) {
Utils::print("Rx Message (APRS-IS): " + packet);
if (STATION_Utils::wasHeard(Addressee) && packet.indexOf("EQNS.") == -1 && packet.indexOf("UNIT.") == -1 && packet.indexOf("PARM.") == -1) {
STATION_Utils::addToOutputPacketBuffer(buildPacketToTx(packet, 1));
displayToggle(true);
lastScreenOn = millis();
@@ -333,11 +333,16 @@ namespace APRS_IS_Utils {
}
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
} else if (Config.aprs_is.objectsToRF && packet.indexOf(":;") > 0) {
Utils::println("Received Object from APRS-IS : " + packet);
STATION_Utils::addToOutputPacketBuffer(buildPacketToTx(packet, 5));
displayToggle(true);
lastScreenOn = millis();
Utils::typeOfPacket(packet, 1); // APRS-LoRa
Utils::print("Rx Object (APRS-IS) : " + packet);
if (STATION_Utils::checkObjectTime(packet)) {
STATION_Utils::addToOutputPacketBuffer(buildPacketToTx(packet, 5));
displayToggle(true);
lastScreenOn = millis();
Utils::typeOfPacket(packet, 1); // APRS-LoRa
Serial.println();
} else {
Serial.println(" ---> Rejected (Time): No Tx");
}
}
}
}
@@ -349,7 +354,7 @@ namespace APRS_IS_Utils {
if (espClient.connected()) {
if (espClient.available()) {
String aprsisPacket = espClient.readStringUntil('\r');
// Serial.println(aprsisPacket);
aprsisPacket.trim(); // Serial.println(aprsisPacket);
processAPRSISPacket(aprsisPacket);
lastRxTime = millis();
}

View File

@@ -9,12 +9,19 @@
#include <TFT_eSPI.h>
TFT_eSPI tft = TFT_eSPI();
TFT_eSprite sprite = TFT_eSprite(&tft);
#ifdef HELTEC_WIRELESS_TRACKER
#define bigSizeFont 2
#define smallSizeFont 1
#define lineSpacing 10
#endif
#if defined(TTGO_T_DECK_GPS) || defined(TTGO_T_DECK_PLUS)
#define bigSizeFont 5
#define smallSizeFont 2
#define lineSpacing 25
#endif
uint16_t redColor = 0xc8a2;
#else
#ifdef HAS_EPAPER
//
@@ -32,16 +39,8 @@
extern Configuration Config;
String oldHeader, oldFirstLine, oldSecondLine, oldThirdLine, oldFourthLine, oldFifthLine, oldSixthLine;
bool displayFound = false;
void cleanTFT() {
#ifdef HAS_TFT
tft.fillScreen(TFT_BLACK);
#endif
}
void displaySetup() {
#ifdef HAS_DISPLAY
delay(500);
@@ -53,8 +52,15 @@ void displaySetup() {
} else {
tft.setRotation(1);
}
pinMode(TFT_BL, OUTPUT);
digitalWrite(TFT_BL, HIGH);
tft.setTextFont(0);
tft.fillScreen(TFT_BLACK);
#if defined(TTGO_T_DECK_GPS) || defined(TTGO_T_DECK_PLUS)
sprite.createSprite(320,240);
#else
sprite.createSprite(160,80);
#endif
#else
#ifdef HAS_EPAPER
//
@@ -109,49 +115,30 @@ void displayToggle(bool toggle) {
#endif
}
bool shouldCleanTFT(const String& header, const String& line1, const String& line2, const String& line3) {
if (oldHeader != header || oldFirstLine != line1 || oldSecondLine != line2 || oldThirdLine != line3) {
oldHeader = header;
oldFirstLine = line1;
oldSecondLine = line2;
oldThirdLine = line3;
return true;
} else {
return false;
}
}
bool shouldCleanTFT(const String& header, const String& line1, const String& line2, const String& line3, const String& line4, const String& line5, const String& line6) {
if (oldHeader != header || oldFirstLine != line1 || oldSecondLine != line2 || oldThirdLine != line3 || oldFourthLine != line4 || oldFifthLine != line5 || oldSixthLine != line6) {
oldHeader = header;
oldFirstLine = line1;
oldSecondLine = line2;
oldThirdLine = line3;
oldFourthLine = line4;
oldFifthLine = line5;
oldSixthLine = line6;
return true;
} else {
return false;
}
}
void displayShow(const String& header, const String& line1, const String& line2, const String& line3, int wait) {
#ifdef HAS_DISPLAY
const String* const lines[] = {&line1, &line2, &line3};
#ifdef HAS_TFT
if (shouldCleanTFT(header, line1, line2, line3)) {
cleanTFT();
}
tft.setTextColor(TFT_WHITE,TFT_BLACK);
tft.setTextSize(bigSizeFont);
tft.setCursor(0, 0);
tft.print(header);
tft.setTextSize(smallSizeFont);
sprite.fillSprite(TFT_BLACK);
#if defined(HELTEC_WIRELESS_TRACKER)
sprite.fillRect(0, 0, 160, 19, redColor);
#endif
#if defined(TTGO_T_DECK_GPS) || defined(TTGO_T_DECK_PLUS)
sprite.fillRect(0, 0, 320, 43, redColor);
#endif
sprite.setTextFont(0);
sprite.setTextSize(bigSizeFont);
sprite.setTextColor(TFT_WHITE, redColor);
sprite.drawString(header, 3, 3);
sprite.setTextSize(smallSizeFont);
sprite.setTextColor(TFT_WHITE, TFT_BLACK);
for (int i = 0; i < 3; i++) {
tft.setCursor(0, ((lineSpacing * (2 + i)) - 2));
tft.print(*lines[i]);
sprite.drawString(*lines[i], 3, (lineSpacing * (2 + i)) - 2);
}
sprite.pushSprite(0,0);
#else
#ifdef HAS_EPAPER
// ... to be continued
@@ -180,18 +167,26 @@ void displayShow(const String& header, const String& line1, const String& line2,
#ifdef HAS_DISPLAY
const String* const lines[] = {&line1, &line2, &line3, &line4, &line5, &line6};
#ifdef HAS_TFT
if (shouldCleanTFT(header, line1, line2, line3, line4, line5, line6)) {
cleanTFT();
}
tft.setTextColor(TFT_WHITE,TFT_BLACK);
tft.setTextSize(bigSizeFont);
tft.setCursor(0, 0);
tft.print(header);
tft.setTextSize(smallSizeFont);
sprite.fillSprite(TFT_BLACK);
#if defined(HELTEC_WIRELESS_TRACKER)
sprite.fillRect(0, 0, 160, 19, redColor);
#endif
#if defined(TTGO_T_DECK_GPS) || defined(TTGO_T_DECK_PLUS)
sprite.fillRect(0, 0, 320, 43, redColor);
#endif
sprite.setTextFont(0);
sprite.setTextSize(bigSizeFont);
sprite.setTextColor(TFT_WHITE, redColor);
sprite.drawString(header, 3, 3);
sprite.setTextSize(smallSizeFont);
sprite.setTextColor(TFT_WHITE, TFT_BLACK);
for (int i = 0; i < 6; i++) {
tft.setCursor(0, ((lineSpacing * (2 + i)) - 2));
tft.print(*lines[i]);
sprite.drawString(*lines[i], 3, (lineSpacing * (2 + i)) - 2);
}
sprite.pushSprite(0,0);
#else
#ifdef HAS_EPAPER
// ... to be continued

View File

@@ -139,7 +139,7 @@ namespace LoRa_Utils {
if (Config.syslog.active && WiFi.status() == WL_CONNECTED) {
SYSLOG_Utils::log(3, newPacket, 0, 0.0, 0); // TX
}
Utils::print("---> LoRa Packet Tx : ");
Utils::print("---> LoRa Packet Tx : ");
Utils::println(newPacket);
} else {
Utils::print(F("failed, code "));
@@ -185,7 +185,7 @@ namespace LoRa_Utils {
rssi = radio.getRSSI();
snr = radio.getSNR();
freqError = radio.getFrequencyError();
Utils::println("<--- LoRa Packet Rx : " + packet.substring(3));
Utils::println("<--- LoRa Packet Rx : " + packet.substring(3));
Utils::println("(RSSI:" + String(rssi) + " / SNR:" + String(snr) + " / FreqErr:" + String(freqError) + ")");
if (!Config.lowPowerMode && !Config.digi.ecoMode) {

View File

@@ -48,13 +48,13 @@ namespace OTA_Utils {
void onOTAEnd(bool success) {
displayToggle(true);
lastScreenOn = millis();
if (success) {
Serial.println("OTA update finished successfully!");
displayShow("", "", " OTA update success!", "", " Rebooting ...", "", "", 4000);
} else {
Serial.println("There was an error during OTA update!");
displayShow("", "", " OTA update fail!", "", "", "", "", 4000);
}
String statusMessage = success ? "OTA update success!" : "OTA update fail!";
String rebootMessage = success ? "Rebooting ..." : "";
Serial.println(success ? "OTA update finished successfully!" : "There was an error during OTA update!");
displayShow("", "", statusMessage, "", rebootMessage, "", "", 4000);
isUpdatingOTA = false;
}

View File

@@ -207,7 +207,23 @@ namespace POWER_Utils {
#if defined(HELTEC_V3) || defined(HELTEC_V3_2) || defined(HELTEC_WP) || defined(HELTEC_WSL_V3) || defined(HELTEC_WSL_V3_DISPLAY)
Wire1.begin(BOARD_I2C_SDA, BOARD_I2C_SCL);
#endif
#endif
#if defined(TTGO_T_DECK_GPS) || defined(TTGO_T_DECK_PLUS)
pinMode(BOARD_POWERON, OUTPUT);
digitalWrite(BOARD_POWERON, HIGH);
pinMode(BOARD_SDCARD_CS, OUTPUT);
pinMode(RADIO_CS_PIN, OUTPUT);
pinMode(TFT_CS, OUTPUT);
digitalWrite(BOARD_SDCARD_CS, HIGH);
digitalWrite(RADIO_CS_PIN, HIGH);
digitalWrite(TFT_CS, HIGH);
delay(500);
Wire.begin(BOARD_I2C_SDA, BOARD_I2C_SCL);
#endif
delay(1000);
BATTERY_Utils::setup();

View File

@@ -17,6 +17,7 @@ std::vector<LastHeardStation> lastHeardStations;
std::vector<String> outputPacketBuffer;
std::vector<Packet25SegBuffer> packet25SegBuffer;
std::vector<String> blackList;
std::vector<LastHeardStation> lastHeardObjects;
bool saveNewDigiEcoModeConfig = false;
@@ -50,7 +51,30 @@ namespace STATION_Utils {
return false;
}
void cleanObjectsHeard() {
for (auto it = lastHeardObjects.begin(); it != lastHeardObjects.end(); ) {
if (millis() - it->lastHeardTime >= 9.75 * 60 * 1000) { // 9.75 = 9min 45secs
it = lastHeardObjects.erase(it); // erase() returns the next valid iterator
} else {
++it; // Only increment if not erasing
}
}
}
bool checkObjectTime(const String& packet) {
cleanObjectsHeard();
int objectIDIndex = packet.indexOf(":;");
String object = packet.substring(objectIDIndex + 2, objectIDIndex + 11);
object.trim();
for (int i = 0; i < lastHeardObjects.size(); i++) { // Check if i should Tx object
if (lastHeardObjects[i].station == object) return false;
}
lastHeardObjects.emplace_back(LastHeardStation{millis(), object}); // Add new object and Tx
return true;
}
void deleteNotHeard() {
std::vector<LastHeardStation> lastHeardStation_temp;
for (int i = 0; i < lastHeardStations.size(); i++) {
@@ -72,22 +96,11 @@ namespace STATION_Utils {
if (lastHeardStations[i].station == station) {
lastHeardStations[i].lastHeardTime = millis();
stationHeard = true;
break;
}
}
if (!stationHeard) {
LastHeardStation lastStation;
lastStation.lastHeardTime = millis();
lastStation.station = station;
lastHeardStations.push_back(lastStation);
}
fourthLine = "Stations (";
fourthLine += String(Config.rememberStationTime);
fourthLine += "min) = ";
if (lastHeardStations.size() < 10) {
fourthLine += " ";
}
fourthLine += String(lastHeardStations.size());
if (!stationHeard) lastHeardStations.emplace_back(LastHeardStation{millis(), station});
Utils::activeStations();
}
bool wasHeard(const String& station) {
@@ -98,7 +111,7 @@ namespace STATION_Utils {
return true;
}
}
Utils::println(" ---> Station not Heard for last 30 min (Not Tx)\n");
Utils::println(" ---> Station not Heard in " + String(Config.rememberStationTime) + " min: No Tx");
return false;
}
@@ -112,11 +125,7 @@ namespace STATION_Utils {
if (packet25SegBuffer[i].station == station && packet25SegBuffer[i].payload == textMessage) return false;
}
}
Packet25SegBuffer packet;
packet.receivedTime = millis();
packet.station = station;
packet.payload = textMessage;
packet25SegBuffer.push_back(packet);
packet25SegBuffer.emplace_back(Packet25SegBuffer{millis(), station, textMessage});
return true;
}

View File

@@ -20,6 +20,10 @@ namespace SYSLOG_Utils {
char signalData[35];
snprintf(signalData, sizeof(signalData), " / %ddBm / %.2fdB / %dHz", rssi, snr, freqError);
int colonIndex = packet.indexOf(":");
char nextChar = packet[colonIndex + 1];
String sender = packet.substring(3, packet.indexOf(">"));
switch (type) {
case 0: // CRC
syslogPacket.concat("CRC / CRC-ERROR / ");
@@ -28,59 +32,56 @@ namespace SYSLOG_Utils {
break;
case 1: // RX
syslogPacket.concat("RX / ");
if (packet.indexOf("::") > 10) {
if (nextChar == ':') {
syslogPacket.concat("MESSAGE / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">")));
syslogPacket.concat(" ---> "); syslogPacket.concat(packet.substring(packet.indexOf("::") + 2));
syslogPacket.concat(signalData);
} else if (packet.indexOf(":!") > 10 || packet.indexOf(":=") > 10) {
syslogPacket.concat(sender);
syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(colonIndex + 2));
} else if (nextChar == '!' || nextChar == '=') {
syslogPacket.concat("GPS / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">")));
syslogPacket.concat(sender);
syslogPacket.concat(" / ");
if (packet.indexOf("WIDE1-1") > 10) {
syslogPacket.concat(packet.substring(packet.indexOf(">") + 1, packet.indexOf(",")));
syslogPacket.concat(" / WIDE1-1");
} else {
syslogPacket.concat(packet.substring(packet.indexOf(">") + 1, packet.indexOf(":")));
syslogPacket.concat(packet.substring(packet.indexOf(">") + 1, colonIndex));
syslogPacket.concat(" / -");
}
syslogPacket.concat(signalData);
syslogPacket.concat(" / ");
syslogPacket.concat(GPS_Utils::getDistanceAndComment(packet));
} else if (packet.indexOf(":>") > 10) {
} else if (nextChar == '>') {
syslogPacket.concat("STATUS / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">")));
syslogPacket.concat(sender);
syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf(":>") + 2));
syslogPacket.concat(signalData);
} else if (packet.indexOf(":`") > 10) {
syslogPacket.concat(packet.substring(colonIndex + 2));
} else if (nextChar == '`') {
syslogPacket.concat("MIC-E / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">")));
syslogPacket.concat(sender);
syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf(":`") + 2));
syslogPacket.concat(signalData);
syslogPacket.concat(packet.substring(colonIndex + 2));
} else if (nextChar == ';') {
syslogPacket.concat("OBJECT / ");
syslogPacket.concat(sender);
syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(colonIndex + 2));
} else if (packet.indexOf(":T#") >= 10 && packet.indexOf(":=/") == -1) {
syslogPacket.concat("TELEMETRY / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">")));
syslogPacket.concat(sender);
syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf(":T#") + 3));
syslogPacket.concat(signalData);
} else if (packet.indexOf(":;") > 10) {
syslogPacket.concat("OBJECT / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">")));
syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf(":;") + 2));
syslogPacket.concat(signalData);
} else {
syslogPacket.concat(packet);
syslogPacket.concat(signalData);
}
syslogPacket.concat(signalData);
if (nextChar == '!' || nextChar == '=') {
syslogPacket.concat(" / ");
syslogPacket.concat(GPS_Utils::getDistanceAndComment(packet));
}
break;
case 2: // APRSIS TX
syslogPacket.concat("APRSIS TX / ");
if (packet.indexOf(":>") > 10) {
if (nextChar == '>') {
syslogPacket.concat("StartUp_Status / ");
syslogPacket.concat(packet.substring(packet.indexOf(":>") + 2));
syslogPacket.concat(packet.substring(colonIndex + 2));
} else {
syslogPacket.concat("QUERY / ");
syslogPacket.concat(packet);
@@ -91,11 +92,11 @@ namespace SYSLOG_Utils {
if (packet.indexOf("RFONLY") > 10) {
syslogPacket.concat("RFONLY / ");
syslogPacket.concat(packet);
} else if (packet.indexOf("::") > 10) {
} else if (nextChar == ':') {
syslogPacket.concat("MESSAGE / ");
syslogPacket.concat(packet.substring(0,packet.indexOf(">")));
syslogPacket.concat(sender);
syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf("::") + 2));
syslogPacket.concat(packet.substring(colonIndex + 2));
} else {
syslogPacket.concat(packet);
}

View File

@@ -44,16 +44,9 @@ namespace TNC_Utils {
}
void handleInputData(char character, int bufferIndex) {
String* data;
if (bufferIndex == -1) {
data = &inputSerialBuffer;
} else {
data = &inputServerBuffer[bufferIndex];
}
if (data->length() == 0 && character != (char)FEND) {
return;
}
String* data = (bufferIndex == -1) ? &inputSerialBuffer : &inputServerBuffer[bufferIndex];
if (data->length() == 0 && character != (char)FEND) return;
data->concat(character);
if (character == (char)FEND && data->length() > 3) {

View File

@@ -103,20 +103,15 @@ namespace Utils {
}
void activeStations() {
fourthLine = "Stations (";
fourthLine.concat(String(Config.rememberStationTime));
fourthLine.concat("min) = ");
if (lastHeardStations.size() < 10) {
fourthLine += " ";
}
fourthLine.concat(String(lastHeardStations.size()));
char buffer[30]; // Adjust size as needed
sprintf(buffer, "Stations (%dmin) = %2d", Config.rememberStationTime, lastHeardStations.size());
fourthLine = buffer;
}
void sendInitialTelemetryPackets() {
String sender = Config.callsign;
for (int i = sender.length(); i < 9; i++) {
sender += ' ';
}
char sender[10]; // 9 characters + null terminator
snprintf(sender, sizeof(sender), "%-9s", Config.callsign.c_str()); // Left-align with spaces
String baseAPRSISTelemetryPacket = Config.callsign;
baseAPRSISTelemetryPacket += ">APLRG1,TCPIP,qAC::";
baseAPRSISTelemetryPacket += sender;
@@ -137,7 +132,7 @@ namespace Utils {
telemetryPacket1 += "0,0.01,0";
}
if (Config.battery.sendExternalVoltage) {
telemetryPacket1 += String(Config.battery.sendInternalVoltage ? "," : "") + "0,0.02,0";
telemetryPacket1 += String(Config.battery.sendInternalVoltage ? ",0,0.02,0" : "0,0.02,0");
}
String telemetryPacket2 = "UNIT.";
@@ -145,7 +140,7 @@ namespace Utils {
telemetryPacket2 += "VDC";
}
if (Config.battery.sendExternalVoltage) {
telemetryPacket2 += String(Config.battery.sendInternalVoltage ? "," : "") + "VDC";
telemetryPacket2 += String(Config.battery.sendInternalVoltage ? ",VDC" : "VDC");
}
String telemetryPacket3 = "PARM.";
@@ -153,7 +148,7 @@ namespace Utils {
telemetryPacket3 += "V_Batt";
}
if (Config.battery.sendExternalVoltage) {
telemetryPacket3 += String(Config.battery.sendInternalVoltage ? "," : "") + "V_Ext";
telemetryPacket3 += String(Config.battery.sendInternalVoltage ? ",V_Ext" : "V_Ext");
}
if (Config.beacon.sendViaAPRSIS) {
@@ -200,7 +195,12 @@ namespace Utils {
if (beaconUpdate) {
if (!Config.display.alwaysOn && Config.display.timeout != 0) displayToggle(true);
if (sendStartTelemetry && Config.battery.sendVoltageAsTelemetry && !Config.wxsensor.active && (Config.battery.sendInternalVoltage || Config.battery.sendExternalVoltage)) {
if (sendStartTelemetry &&
Config.battery.sendVoltageAsTelemetry &&
!Config.wxsensor.active &&
(Config.battery.sendInternalVoltage || Config.battery.sendExternalVoltage) &&
(lastBeaconTx > 0)) {
//(!Config.digi.ecoMode || lastBeaconTx > 0)) {
sendInitialTelemetryPackets();
}
@@ -222,13 +222,10 @@ namespace Utils {
}
#endif
if (Config.wxsensor.active && wxModuleType != 0) {
String sensorData = WX_Utils::readDataSensor();
beaconPacket += sensorData;
secondaryBeaconPacket += sensorData;
} else if (Config.wxsensor.active && wxModuleType == 0) {
beaconPacket += ".../...g...t...";
secondaryBeaconPacket += ".../...g...t...";
if (Config.wxsensor.active) {
const char* sensorData = (wxModuleType == 0) ? ".../...g...t..." : WX_Utils::readDataSensor().c_str();
beaconPacket += sensorData;
secondaryBeaconPacket += sensorData;
}
beaconPacket += Config.beacon.comment;
secondaryBeaconPacket += Config.beacon.comment;
@@ -242,11 +239,14 @@ namespace Utils {
shouldSleepLowVoltage = true;
}
String internalVoltageInfo = String(internalVoltage,2) + "V";
if (Config.battery.sendInternalVoltage) {
sixthLine = " (Batt=";
sixthLine += internalVoltageInfo;
sixthLine += ")";
char internalVoltageInfo[10]; // Enough to hold "xx.xxV\0"
snprintf(internalVoltageInfo, sizeof(internalVoltageInfo), "%.2fV", internalVoltage);
char sixthLineBuffer[25]; // Enough to hold " (Batt=xx.xxV)"
snprintf(sixthLineBuffer, sizeof(sixthLineBuffer), " (Batt=%s)", internalVoltageInfo);
sixthLine = sixthLineBuffer;
if (!Config.battery.sendVoltageAsTelemetry) {
beaconPacket += " Batt=";
beaconPacket += internalVoltageInfo;
@@ -266,11 +266,14 @@ namespace Utils {
shouldSleepLowVoltage = true;
}
String externalVoltageInfo = String(externalVoltage,2) + "V";
if (Config.battery.sendExternalVoltage) {
sixthLine = " (Ext V=";
sixthLine += externalVoltageInfo;
sixthLine += ")";
char externalVoltageInfo[10]; // "xx.xxV\0" (max 7 chars)
snprintf(externalVoltageInfo, sizeof(externalVoltageInfo), "%.2fV", externalVoltage);
char sixthLineBuffer[25]; // Ensure enough space
snprintf(sixthLineBuffer, sizeof(sixthLineBuffer), " (Ext V=%s)", externalVoltageInfo);
sixthLine = sixthLineBuffer;
if (!Config.battery.sendVoltageAsTelemetry) {
beaconPacket += " Ext=";
beaconPacket += externalVoltageInfo;
@@ -345,54 +348,45 @@ namespace Utils {
fifthLine = "LoRa Rx ----> LoRa Tx";
break;
}
int firstColonIndex = packet.indexOf(":");
char nextChar = packet[firstColonIndex + 1];
for (int i = sender.length(); i < 9; i++) {
sender += " ";
}
sixthLine = sender;
String seventhLineHelper = "RSSI:";
seventhLineHelper += String(rssi);
seventhLineHelper += "dBm SNR: ";
seventhLineHelper += String(snr);
seventhLineHelper += "dBm";
int firstColonIndex = packet.indexOf(":");
if (packet[firstColonIndex + 1] == ':') {
if (nextChar == ':') {
sixthLine += "> MESSAGE";
seventhLine = seventhLineHelper;
} else if (packet[firstColonIndex + 1] == '>') {
} else if (nextChar == '>') {
sixthLine += "> NEW STATUS";
seventhLine = seventhLineHelper;
} else if (packet[firstColonIndex + 1] == '!' || packet[firstColonIndex + 1] == '=' || packet[firstColonIndex + 1] == '@') {
} else if (nextChar == '!' || nextChar == '=' || nextChar == '@') {
sixthLine += "> GPS BEACON";
if (!Config.syslog.active) {
GPS_Utils::getDistanceAndComment(packet); // to be checked!!!
}
if (!Config.syslog.active) GPS_Utils::getDistanceAndComment(packet); // to be checked!!!
seventhLine = "RSSI:";
seventhLine += String(rssi);
seventhLine += "dBm";
if (rssi <= -100) {
seventhLine += " ";
} else {
seventhLine += " ";
}
if (distance.indexOf(".") == 1) {
seventhLine += " ";
}
seventhLine += (rssi <= -100) ? " " : " ";
if (distance.indexOf(".") == 1) seventhLine += " ";
seventhLine += "D:";
seventhLine += distance;
seventhLine += "km";
} else if (packet[firstColonIndex + 1] == '`' || packet[firstColonIndex + 1] == '\'') {
} else if (nextChar == '`' || nextChar == '\'') {
sixthLine += "> MIC-E";
seventhLine = seventhLineHelper;
} else if (packet[firstColonIndex + 1] == ';') {
} else if (nextChar == ';') {
sixthLine += "> OBJECT";
seventhLine = seventhLineHelper;
} else if (packet.indexOf(":T#") >= 10 && packet.indexOf(":=/") == -1) {
sixthLine += "> TELEMETRY";
seventhLine = seventhLineHelper;
} else {
sixthLine += "> ??????????";
seventhLine = seventhLineHelper;
}
if (nextChar != '!' && nextChar != '=' && nextChar != '@') { // Common assignment for non-GPS cases
seventhLine = "RSSI:";
seventhLine += String(rssi);
seventhLine += "dBm SNR: ";
seventhLine += String(snr);
seventhLine += "dBm";
}
}

View File

@@ -1,4 +1,6 @@
#include <TinyGPS++.h>
#include "configuration.h"
#include "board_pinout.h"
#include "wx_utils.h"
#include "display.h"
@@ -8,6 +10,9 @@
extern Configuration Config;
extern String fifthLine;
#ifdef HAS_GPS
extern TinyGPSPlus gps;
#endif
int wxModuleType = 0;
uint8_t wxModuleAddress = 0x00;
@@ -227,13 +232,14 @@ namespace WX_Utils {
humStr = "..";
}
String presStr;
if (wxModuleAddress == 4) {
presStr = ".....";
} else {
presStr = generatePresString(newPress + (Config.wxsensor.heightCorrection/CORRECTION_FACTOR));
}
String presStr = (wxModuleAddress == 4)
? "....."
#ifdef HAS_GPS
: generatePresString(newPress + (gps.altitude.meters() / CORRECTION_FACTOR));
#else
: generatePresString(newPress + (Config.wxsensor.heightCorrection / CORRECTION_FACTOR));
#endif
fifthLine = "BME-> ";
fifthLine += String(int(newTemp + Config.wxsensor.temperatureCorrection));
fifthLine += "C ";

View File

@@ -0,0 +1,36 @@
#ifndef BOARD_PINOUT_H_
#define BOARD_PINOUT_H_
// LoRa Radio
#define HAS_SX1262
#define RADIO_SCLK_PIN 40
#define RADIO_MISO_PIN 38
#define RADIO_MOSI_PIN 41
#define RADIO_CS_PIN 9
#define RADIO_RST_PIN 17
#define RADIO_DIO1_PIN 45
#define RADIO_BUSY_PIN 13
// Display
#define HAS_DISPLAY
#define HAS_TFT
#undef OLED_SDA
#undef OLED_SCL
#undef OLED_RST
// GPS
#define GPS_RX 43
#define GPS_TX 44
// Aditional Config
#define BATTERY_PIN 4
#define BOARD_POWERON 10
#define BOARD_SDCARD_CS 39
#define BOARD_BL_PIN 42
#define BOARD_I2C_SDA 18
#define BOARD_I2C_SCL 8
#endif

View File

@@ -0,0 +1,50 @@
[env:ttgo_t_deck_GPS]
framework = arduino
monitor_speed = 115200
platform = espressif32 @ 6.3.1
board_build.partitions = min_spiffs.csv
board = esp32-s3-devkitc-1
board_build.mcu = esp32s3
board_build.embed_files =
data_embed/index.html.gz
data_embed/style.css.gz
data_embed/script.js.gz
data_embed/bootstrap.css.gz
data_embed/bootstrap.js.gz
data_embed/favicon.png.gz
extra_scripts =
pre:tools/compress.py
debug_tool = esp-prog
build_flags =
${common.build_flags}
${common.usb_flags}
-D TTGO_T_DECK_PLUS
-D BOARD_HAS_PSRAM
-D USER_SETUP_LOADED
-D ST7789_DRIVER
-D TFT_WIDTH=240
-D TFT_HEIGHT=320
-D TFT_RGB_ORDER=TFT_BGR
-D TFT_INVERSION_ON
-D TFT_MISO=38
-D TFT_MOSI=41
-D TFT_SCLK=40
-D TFT_CS=12
-D TFT_DC=11
-D TFT_RST=-1
-D TFT_BUSY=-1
-D TFT_BL=42
-D TFT_BACKLIGHT_ON=1
-D TOUCH_CS=-1
-D LOAD_GLCD
-D LOAD_FONT2
-D LOAD_FONT4
-D LOAD_FONT6
-D LOAD_FONT7
-D LOAD_FONT8
-D SPI_FREQUENCY=40000000
-D SPI_READ_FREQUENCY=16000000
lib_deps =
${common.lib_deps}
bodmer/TFT_eSPI @ 2.5.43
https://github.com/mmMicky/TouchLib.git

View File

@@ -0,0 +1,37 @@
#ifndef BOARD_PINOUT_H_
#define BOARD_PINOUT_H_
// LoRa Radio
#define HAS_SX1262
#define RADIO_SCLK_PIN 40
#define RADIO_MISO_PIN 38
#define RADIO_MOSI_PIN 41
#define RADIO_CS_PIN 9
#define RADIO_RST_PIN 17
#define RADIO_DIO1_PIN 45
#define RADIO_BUSY_PIN 13
// Display
#define HAS_DISPLAY
#define HAS_TFT
#undef OLED_SDA
#undef OLED_SCL
#undef OLED_RST
// GPS
#define GPS_RX 43
#define GPS_TX 44
#define GPS_BAUDRATE 38400
// Aditional Config
#define BATTERY_PIN 4
#define BOARD_POWERON 10
#define BOARD_SDCARD_CS 39
#define BOARD_BL_PIN 42
#define BOARD_I2C_SDA 18
#define BOARD_I2C_SCL 8
#endif

View File

@@ -0,0 +1,50 @@
[env:ttgo_t_deck_plus]
framework = arduino
monitor_speed = 115200
platform = espressif32 @ 6.3.1
board_build.partitions = min_spiffs.csv
board = esp32-s3-devkitc-1
board_build.mcu = esp32s3
board_build.embed_files =
data_embed/index.html.gz
data_embed/style.css.gz
data_embed/script.js.gz
data_embed/bootstrap.css.gz
data_embed/bootstrap.js.gz
data_embed/favicon.png.gz
extra_scripts =
pre:tools/compress.py
debug_tool = esp-prog
build_flags =
${common.build_flags}
${common.usb_flags}
-D TTGO_T_DECK_PLUS
-D BOARD_HAS_PSRAM
-D USER_SETUP_LOADED
-D ST7789_DRIVER
-D TFT_WIDTH=240
-D TFT_HEIGHT=320
-D TFT_RGB_ORDER=TFT_BGR
-D TFT_INVERSION_ON
-D TFT_MISO=38
-D TFT_MOSI=41
-D TFT_SCLK=40
-D TFT_CS=12
-D TFT_DC=11
-D TFT_RST=-1
-D TFT_BUSY=-1
-D TFT_BL=42
-D TFT_BACKLIGHT_ON=1
-D TOUCH_CS=-1
-D LOAD_GLCD
-D LOAD_FONT2
-D LOAD_FONT4
-D LOAD_FONT6
-D LOAD_FONT7
-D LOAD_FONT8
-D SPI_FREQUENCY=40000000
-D SPI_READ_FREQUENCY=16000000
lib_deps =
${common.lib_deps}
bodmer/TFT_eSPI @ 2.5.43
https://github.com/mmMicky/TouchLib.git