Compare commits

..

39 Commits

Author SHA1 Message Date
richonguzman
8b7e0fdcef minor correction to EM activation 2025-03-20 15:54:19 -03:00
richonguzman
ad996c8a49 encoded byte update 2025-03-18 19:10:15 -03:00
richonguzman
dedd7152d9 first update of timestamp 2025-03-18 18:50:08 -03:00
richonguzman
5f5d7d7868 ready for test 2025-03-18 14:02:09 -03:00
richonguzman
2e3cafd0f0 3 2025-03-10 03:02:48 -03:00
richonguzman
1c07c2fb2b 2 2025-03-09 10:48:18 -03:00
richonguzman
4c63dd8bb7 start1 2025-03-09 10:23:34 -03:00
richonguzman
b00fba9693 readme update 2025-03-03 13:53:29 -03:00
richonguzman
37162b9708 display font size correction 2025-03-03 12:22:22 -03:00
richonguzman
44d9732aa2 TbeamSupreme Added 2025-03-03 12:15:50 -03:00
richonguzman
312bdc9d9f refactor and blacklist2.0 2025-03-03 11:19:25 -03:00
richonguzman
ff0b96bfe4 readme update again 2025-02-28 16:56:54 -03:00
richonguzman
36a8ef0ffb readme update for epaper 2025-02-28 16:53:16 -03:00
richonguzman
5ce8059040 epaper updated 2025-02-28 16:48:26 -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
richonguzman
4349019f7b version and readme UPDATE 2025-01-11 10:44:40 -03:00
richonguzman
411753c0aa build.yml updated 2025-01-10 12:15:32 -03:00
richonguzman
ad6aed7f0d starting with Heltec V3_2 2025-01-10 11:53:52 -03:00
richonguzman
f325c54fc3 Heltec Wireless Stick display fix 2025-01-08 12:59:39 -03:00
richonguzman
1a3966eadc readme update 2025-01-07 16:10:35 -03:00
40 changed files with 1100 additions and 467 deletions

View File

@@ -21,6 +21,8 @@ jobs:
chip: esp32 chip: esp32
- name: heltec_wifi_lora_32_V3 - name: heltec_wifi_lora_32_V3
chip: esp32s3 chip: esp32s3
- name: heltec_wifi_lora_32_V3_2
chip: esp32s3
- name: heltec_wireless_stick - name: heltec_wireless_stick
chip: esp32s3 chip: esp32s3
- name: heltec_wireless_stick_lite_v3 - name: heltec_wireless_stick_lite_v3
@@ -51,6 +53,12 @@ jobs:
chip: esp32 chip: esp32
- name: ttgo-t-beam-v1_2_SX1262 - name: ttgo-t-beam-v1_2_SX1262
chip: esp32 chip: esp32
- name: ttgo_t_deck_plus
chip: esp32s3
- name: ttgo_t_deck_GPS
chip: esp32s3
- name: ttgo_t_beam_s3_SUPREME_v3
chip: esp32s3
- name: ESP32_DIY_LoRa_A7670 - name: ESP32_DIY_LoRa_A7670
chip: esp32 chip: esp32
- name: ESP32_DIY_LoRa_A7670_915 - 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). - 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. - HELTEC V2, V3 , Wireless Stick, Wireless Stick Lite, HT-CT62, Wireless Tracker, Wireless Paper.
- QRP Labs LightGateway 1.0. - QRP Labs LightGateway 1.0.
@@ -52,6 +54,12 @@ ____________________________________________________
## Timeline (Versions): ## Timeline (Versions):
- 2025.03.03 T-Beam Supreme board added and more BlackList rules added.
- 2025.02.28 Heltec Wireless Paper with Epaper working. Thanks SzymonPriv for pointing to the right library.
- 2025.02.25 Objects Rules update, GPS Boards: Satellites on 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. - 2025.01.02 Callsign Black List added.
- 2024.12.30 Fixed missing validation for correct Digipeater mode when not connected to APRS-IS. - 2024.12.30 Fixed missing validation for correct Digipeater mode when not connected to APRS-IS.
- 2024.12.06 APRS-IS connnection and passcode validation added. - 2024.12.06 APRS-IS connnection and passcode validation added.
@@ -60,7 +68,7 @@ ____________________________________________________
- 2024.10.25 Added QRP Labs LightGateway 1.0 support. - 2024.10.25 Added QRP Labs LightGateway 1.0 support.
- 2024.10.21 Boards with GPS can now send Real-GPS Beacon (also posible: GPS ambiguity of ~ 1 km). - 2024.10.21 Boards with GPS can now send Real-GPS Beacon (also posible: GPS ambiguity of ~ 1 km).
- 2024.10.14 Received Packets in WebUI show real Local Time (NTP with GMT offset). - 2024.10.14 Received Packets in WebUI show real Local Time (NTP with GMT offset).
- 2024.10.08 New EcoMode for Remote Digipeaters without WiFi/WiFiAP, Screen, Leds (Example: LILYGO LoRa32 uses only 24mA, with WifiAP and all was 150mA). APRS Message/Queries can start/stop this mode too. - 2024.10.08 New EcoMode for Remote Digipeaters without WiFi/WiFiAP, Screen, Leds (Example: LILYGO LoRa32 uses only 24mA, with WifiAP 150mA). APRS Message/Queries can start/stop this mode too.
- 2024.10.06 Cross Frequency Digipeater Rules added. - 2024.10.06 Cross Frequency Digipeater Rules added.
- 2024.09.23 Libraries Update for SDK3 - 2024.09.23 Libraries Update for SDK3
- 2024.09.23 Added Enconded Telemetry for Battery (+ External Voltage) in Station GPS Beacon Packet. - 2024.09.23 Added Enconded Telemetry for Battery (+ External Voltage) in Station GPS Beacon Packet.

View File

@@ -84,6 +84,10 @@
"ntp": { "ntp": {
"gmtCorrection": 0.0 "gmtCorrection": 0.0
}, },
"remoteManagement": {
"managers": "",
"rfOnly": true
},
"other": { "other": {
"rememberStationTime": 30, "rememberStationTime": 30,
"lowPowerMode": false, "lowPowerMode": false,
@@ -93,5 +97,5 @@
"rebootModeTime": 6 "rebootModeTime": 6
}, },
"personalNote": "", "personalNote": "",
"blackList": "" "blacklist": ""
} }

View File

@@ -590,20 +590,20 @@
</svg> </svg>
Black List Black List
</h5> </h5>
<small>Add Callsigns with space between them to Black List them (* wild card allowed)</small> <small>Add Callsigns with space between them to Blacklist them (* wild card allowed)</small>
</div> </div>
<div class="col-9 mt-2"> <div class="col-9 mt-2">
<div class="row"> <div class="row">
<div class="col-12"> <div class="col-12">
<label <label
for="blackList" for="blacklist"
class="form-label" class="form-label"
>Black List</label >Blacklist</label
> >
<input <input
type="text" type="text"
name="blackList" name="blacklist"
id="blackList" id="blacklist"
class="form-control" class="form-control"
placeholder="Station Callsign" placeholder="Station Callsign"
oninput="this.value = this.value.toUpperCase();" oninput="this.value = this.value.toUpperCase();"
@@ -1708,6 +1708,65 @@
</div> </div>
<hr /> <hr />
<div class="row my-5 d-flex align-items-top">
<div class="col-lg-3 col-sm-12">
<h5>
<svg
xmlns="http://www.w3.org/2000/svg"
width="20"
height="20"
fill="currentColor"
class="bi bi-cloud-upload-fill"
viewBox="0 0 16 16"
>
<path
fill-rule="evenodd"
d="M8 0a5.53 5.53 0 0 0-3.594 1.342c-.766.66-1.321 1.52-1.464 2.383C1.266 4.095 0 5.555 0 7.318 0 9.366 1.708 11 3.781 11H7.5V5.707L5.354 7.854a.5.5 0 1 1-.708-.708l3-3a.5.5 0 0 1 .708 0l3 3a.5.5 0 0 1-.708.708L8.5 5.707V11h4.188C14.502 11 16 9.57 16 7.773c0-1.636-1.242-2.969-2.834-3.194C12.923 1.999 10.69 0 8 0m-.5 14.5V11h1v3.5a.5.5 0 0 1-1 0"
/>
</svg>
Remote Management
</h5>
<small
>Manage Station via APRS Messages. Leave empty to disable!
</small>
</div>
<div class="col-lg-9 col-sm-12">
<div class="col-12">
<label
for="remoteManagement.managers"
class="form-label"
>Callsign-SSID of Managers, space separated, trailing * wildcard allowed</label
>
<div class="input-group">
<input
type="text"
name="remoteManagement.managers"
id="remoteManagement.managers"
class="form-control"
/>
</div>
</div>
<div class="row">
<div class="col-12">
<div class="form-check form-switch">
<input
type="checkbox"
name="remoteManagement.rfOnly"
id="remoteManagement.rfOnly"
class="form-check-input"
/>
<label
for="remoteManagement.rfOnly"
class="form-label"
>Managers commands only via RF (not APRS-IS)</label
>
</div>
</div>
</div>
</div>
</div>
<hr />
<div class="row my-5 d-flex align-items-top"> <div class="row my-5 d-flex align-items-top">
<div class="col-lg-3 col-sm-12"> <div class="col-lg-3 col-sm-12">
<h5> <h5>

View File

@@ -138,7 +138,7 @@ function loadSettings(settings) {
document.getElementById("beacon.gpsAmbiguity").checked = settings.beacon.gpsAmbiguity; document.getElementById("beacon.gpsAmbiguity").checked = settings.beacon.gpsAmbiguity;
// Black List // Black List
document.getElementById("blackList").value = settings.blackList; document.getElementById("blacklist").value = settings.blacklist;
// Digi // Digi
document.getElementById("digi.mode").value = settings.digi.mode; document.getElementById("digi.mode").value = settings.digi.mode;
@@ -223,6 +223,10 @@ function loadSettings(settings) {
document.getElementById("other.lowPowerMode").checked = settings.other.lowPowerMode; document.getElementById("other.lowPowerMode").checked = settings.other.lowPowerMode;
document.getElementById("other.lowVoltageCutOff").value = settings.other.lowVoltageCutOff || 0 document.getElementById("other.lowVoltageCutOff").value = settings.other.lowVoltageCutOff || 0
// Management over APRS
document.getElementById("remoteManagement.managers").value = settings.remoteManagement.managers;
document.getElementById("remoteManagement.rfOnly").checked = settings.remoteManagement.rfOnly;
updateImage(); updateImage();
refreshSpeedStandard(); refreshSpeedStandard();
toggleFields(); toggleFields();

BIN
images/Web004-BlackList.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

View File

@@ -122,6 +122,11 @@ public:
float gmtCorrection; float gmtCorrection;
}; };
class REMOTE_MANAGEMENT {
public:
String managers;
bool rfOnly;
};
class Configuration { class Configuration {
public: public:
@@ -133,7 +138,7 @@ public:
bool rebootMode; bool rebootMode;
int rebootModeTime; int rebootModeTime;
String personalNote; String personalNote;
String blackList; String blacklist;
std::vector<WiFi_AP> wifiAPs; std::vector<WiFi_AP> wifiAPs;
WiFi_Auto_AP wifiAutoAP; WiFi_Auto_AP wifiAutoAP;
BEACON beacon; BEACON beacon;
@@ -147,7 +152,8 @@ public:
TNC tnc; TNC tnc;
OTA ota; OTA ota;
WEBADMIN webadmin; WEBADMIN webadmin;
NTP ntp; NTP ntp;
REMOTE_MANAGEMENT remoteManagement;
void init(); void init();
void writeFile(); void writeFile();

View File

@@ -5,14 +5,9 @@
#define SCREEN_ADDRESS 0x3C ///< See datasheet for Address; 0x3D for 128x64, 0x3C for 128x32 #define SCREEN_ADDRESS 0x3C ///< See datasheet for Address; 0x3D for 128x64, 0x3C for 128x32
void cleanTFT();
void displaySetup(); void displaySetup();
void displayToggle(bool toggle); 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, 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); 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

@@ -18,8 +18,11 @@ struct LastHeardStation {
namespace STATION_Utils { namespace STATION_Utils {
void loadBlackList(); void loadBlacklist();
bool checkBlackList(const String& callsign); void loadManagers();
bool isBlacklisted(const String& callsign);
bool isManager(const String& callsign);
bool checkObjectTime(const String& packet);
void deleteNotHeard(); void deleteNotHeard();
void updateLastHeard(const String& station); void updateLastHeard(const String& station);
bool wasHeard(const String& station); bool wasHeard(const String& station);

View File

@@ -13,7 +13,7 @@ default_envs = ttgo-lora32-v21
extra_configs = extra_configs =
common_settings.ini common_settings.ini
variants/*/platformio.ini variants/*/platformio.ini
[env] [env]
platform = espressif32 @ 6.7.0 platform = espressif32 @ 6.7.0

View File

@@ -6,6 +6,7 @@
#include "display.h" #include "display.h"
#include "utils.h" #include "utils.h"
#ifdef HAS_A7670 #ifdef HAS_A7670
#define TINY_GSM_MODEM_SIM7600 //The AT instruction of A7670 is compatible with SIM7600 #define TINY_GSM_MODEM_SIM7600 //The AT instruction of A7670 is compatible with SIM7600
#define TINY_GSM_RX_BUFFER 1024 // Set RX buffer to 1Kb #define TINY_GSM_RX_BUFFER 1024 // Set RX buffer to 1Kb

View File

@@ -26,13 +26,11 @@ ___________________________________________________________________*/
#include <WiFi.h> #include <WiFi.h>
#include <vector> #include <vector>
#include "configuration.h" #include "configuration.h"
#include "battery_utils.h"
#include "aprs_is_utils.h" #include "aprs_is_utils.h"
#include "station_utils.h" #include "station_utils.h"
#include "battery_utils.h" #include "battery_utils.h"
#include "board_pinout.h" #include "board_pinout.h"
#include "syslog_utils.h" #include "syslog_utils.h"
#include "query_utils.h"
#include "power_utils.h" #include "power_utils.h"
#include "lora_utils.h" #include "lora_utils.h"
#include "wifi_utils.h" #include "wifi_utils.h"
@@ -48,12 +46,15 @@ ___________________________________________________________________*/
#include "A7670_utils.h" #include "A7670_utils.h"
#endif #endif
String versionDate = "2025.01.07";
String versionDate = "2025.03.20";
Configuration Config; Configuration Config;
WiFiClient espClient; WiFiClient espClient;
#ifdef HAS_GPS #ifdef HAS_GPS
HardwareSerial gpsSerial(1); HardwareSerial gpsSerial(1);
TinyGPSPlus gps; TinyGPSPlus gps;
uint32_t gpsSatelliteTime = 0;
bool gpsInfoToggle = false;
#endif #endif
uint8_t myWiFiAPIndex = 0; uint8_t myWiFiAPIndex = 0;
@@ -66,12 +67,17 @@ uint32_t lastBatteryCheck = 0;
bool backUpDigiMode = false; bool backUpDigiMode = false;
bool modemLoggedToAPRSIS = false; bool modemLoggedToAPRSIS = false;
#ifdef HAS_EPAPER
uint32_t lastEpaperTime = 0;
extern String lastEpaperText;
#endif
std::vector<ReceivedPacket> receivedPackets; std::vector<ReceivedPacket> receivedPackets;
String firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine; String firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine;
//#define STARTUP_DELAY 5 //min //#define STARTUP_DELAY 5 //min
void setup() { void setup() {
Serial.begin(115200); Serial.begin(115200);
POWER_Utils::setup(); POWER_Utils::setup();
@@ -79,7 +85,8 @@ void setup() {
LoRa_Utils::setup(); LoRa_Utils::setup();
Utils::validateFreqs(); Utils::validateFreqs();
GPS_Utils::setup(); GPS_Utils::setup();
STATION_Utils::loadBlackList(); STATION_Utils::loadBlacklist();
STATION_Utils::loadManagers();
#ifdef STARTUP_DELAY // (TEST) just to wait for WiFi init of Routers #ifdef STARTUP_DELAY // (TEST) just to wait for WiFi init of Routers
displayShow("", " STARTUP DELAY ...", "", "", 0); displayShow("", " STARTUP DELAY ...", "", "", 0);
@@ -152,7 +159,26 @@ void loop() {
BATTERY_Utils::checkIfShouldSleep(); 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 #ifdef HAS_A7670
if (Config.aprs_is.active && !modemLoggedToAPRSIS) A7670_Utils::APRS_IS_connect(); if (Config.aprs_is.active && !modemLoggedToAPRSIS) A7670_Utils::APRS_IS_connect();
@@ -198,7 +224,19 @@ void loop() {
STATION_Utils::processOutputPacketBuffer(); STATION_Utils::processOutputPacketBuffer();
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0); #ifdef HAS_EPAPER // Only consider updating every 10 seconds (when data to show is different from before)
if(lastEpaperTime == 0 || millis() - lastEpaperTime > 10000) {
String posibleEpaperText = firstLine + secondLine + thirdLine + fourthLine + fifthLine + sixthLine + seventhLine;
if (lastEpaperText != posibleEpaperText) {
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
lastEpaperText = posibleEpaperText;
lastEpaperTime = millis();
}
}
#else
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
#endif
Utils::checkRebootTime(); Utils::checkRebootTime();
Utils::checkSleepByLowBatteryVoltage(1); Utils::checkSleepByLowBatteryVoltage(1);
} }

View File

@@ -9,6 +9,7 @@
#include "display.h" #include "display.h"
#include "utils.h" #include "utils.h"
extern Configuration Config; extern Configuration Config;
extern WiFiClient espClient; extern WiFiClient espClient;
extern uint32_t lastScreenOn; extern uint32_t lastScreenOn;
@@ -58,7 +59,7 @@ namespace APRS_IS_Utils {
aprsAuth += Config.callsign; aprsAuth += Config.callsign;
aprsAuth += " pass "; aprsAuth += " pass ";
aprsAuth += Config.aprs_is.passcode; aprsAuth += Config.aprs_is.passcode;
aprsAuth += " vers CA2RXU_LoRa_iGate 2.0 filter "; aprsAuth += " vers CA2RXU_iGate 2.3 filter ";
aprsAuth += Config.aprs_is.filter; aprsAuth += Config.aprs_is.filter;
upload(aprsAuth); upload(aprsAuth);
} }
@@ -173,37 +174,35 @@ namespace APRS_IS_Utils {
void processLoRaPacket(const String& packet) { void processLoRaPacket(const String& packet) {
if (passcodeValid && (espClient.connected() || modemLoggedToAPRSIS)) { if (passcodeValid && (espClient.connected() || modemLoggedToAPRSIS)) {
if (packet != "") { if (packet.indexOf("NOGATE") == -1 && packet.indexOf("RFONLY") == -1) {
if ((packet.substring(0, 3) == "\x3c\xff\x01") && (packet.indexOf("NOGATE") == -1) && (packet.indexOf("RFONLY") == -1)) { int firstColonIndex = packet.indexOf(":");
int firstColonIndex = packet.indexOf(":"); if (firstColonIndex > 5 && firstColonIndex < (packet.length() - 1) && packet[firstColonIndex + 1] != '}' && packet.indexOf("TCPIP") == -1) {
if (firstColonIndex > 5 && firstColonIndex < (packet.length() - 1) && packet[firstColonIndex + 1] != '}' && packet.indexOf("TCPIP") == -1) { const String& Sender = packet.substring(3, packet.indexOf(">"));
const String& Sender = packet.substring(3, packet.indexOf(">")); if (Sender != Config.callsign && Utils::checkValidCallsign(Sender)) {
if (Sender != Config.callsign && Utils::checkValidCallsign(Sender) && !STATION_Utils::checkBlackList(Sender)) { STATION_Utils::updateLastHeard(Sender);
STATION_Utils::updateLastHeard(Sender); Utils::typeOfPacket(packet.substring(3), 0); // LoRa-APRS
Utils::typeOfPacket(packet.substring(3), 0); // LoRa-APRS const String& AddresseeAndMessage = packet.substring(packet.indexOf("::") + 2);
const String& AddresseeAndMessage = packet.substring(packet.indexOf("::") + 2); String Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":"));
String Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":")); Addressee.trim();
Addressee.trim(); bool queryMessage = false;
bool queryMessage = false; if (packet.indexOf("::") > 10 && Addressee == Config.callsign) { // its a message for me!
if (packet.indexOf("::") > 10 && Addressee == Config.callsign) { // its a message for me! queryMessage = processReceivedLoRaMessage(Sender, checkForStartingBytes(AddresseeAndMessage), false);
queryMessage = processReceivedLoRaMessage(Sender, checkForStartingBytes(AddresseeAndMessage), false); }
} if (!queryMessage) {
if (!queryMessage) { const String& aprsPacket = buildPacketToUpload(packet);
const String& aprsPacket = buildPacketToUpload(packet); if (!Config.display.alwaysOn && Config.display.timeout != 0) {
if (!Config.display.alwaysOn && Config.display.timeout != 0) { displayToggle(true);
displayToggle(true);
}
lastScreenOn = millis();
#ifdef HAS_A7670
stationBeacon = true;
A7670_Utils::uploadToAPRSIS(aprsPacket);
stationBeacon = false;
#else
upload(aprsPacket);
#endif
Utils::println("---> Uploaded to APRS-IS");
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
} }
lastScreenOn = millis();
#ifdef HAS_A7670
stationBeacon = true;
A7670_Utils::uploadToAPRSIS(aprsPacket);
stationBeacon = false;
#else
upload(aprsPacket);
#endif
Utils::println("---> Uploaded to APRS-IS");
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
} }
} }
} }
@@ -298,7 +297,8 @@ namespace APRS_IS_Utils {
receivedMessage = AddresseeAndMessage.substring(AddresseeAndMessage.indexOf(":") + 1); receivedMessage = AddresseeAndMessage.substring(AddresseeAndMessage.indexOf(":") + 1);
} }
if (receivedMessage.indexOf("?") == 0) { if (receivedMessage.indexOf("?") == 0) {
Utils::println("Received Query APRS-IS : " + packet); Utils::println("Rx Query (APRS-IS) : " + packet);
Sender.trim();
String queryAnswer = QUERY_Utils::process(receivedMessage, Sender, true, false); String queryAnswer = QUERY_Utils::process(receivedMessage, Sender, true, false);
//Serial.println("---> QUERY Answer : " + queryAnswer.substring(0,queryAnswer.indexOf("\n"))); //Serial.println("---> QUERY Answer : " + queryAnswer.substring(0,queryAnswer.indexOf("\n")));
if (!Config.display.alwaysOn && Config.display.timeout != 0) { if (!Config.display.alwaysOn && Config.display.timeout != 0) {
@@ -322,22 +322,28 @@ namespace APRS_IS_Utils {
seventhLine = "QUERY = "; seventhLine = "QUERY = ";
seventhLine += receivedMessage; seventhLine += receivedMessage;
} }
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
} else { } else {
Utils::print("Received Message from APRS-IS : " + packet); Utils::print("Rx Message (APRS-IS): " + packet);
if (STATION_Utils::wasHeard(Addressee)) { if (STATION_Utils::wasHeard(Addressee) && packet.indexOf("EQNS.") == -1 && packet.indexOf("UNIT.") == -1 && packet.indexOf("PARM.") == -1) {
STATION_Utils::addToOutputPacketBuffer(buildPacketToTx(packet, 1)); STATION_Utils::addToOutputPacketBuffer(buildPacketToTx(packet, 1));
displayToggle(true); displayToggle(true);
lastScreenOn = millis(); lastScreenOn = millis();
Utils::typeOfPacket(packet, 1); // APRS-LoRa Utils::typeOfPacket(packet, 1); // APRS-LoRa
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
} }
} }
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
} else if (Config.aprs_is.objectsToRF && packet.indexOf(":;") > 0) { } else if (Config.aprs_is.objectsToRF && packet.indexOf(":;") > 0) {
Utils::println("Received Object from APRS-IS : " + packet); Utils::print("Rx Object (APRS-IS) : " + packet);
STATION_Utils::addToOutputPacketBuffer(buildPacketToTx(packet, 5)); if (STATION_Utils::checkObjectTime(packet)) {
displayToggle(true); STATION_Utils::addToOutputPacketBuffer(buildPacketToTx(packet, 5));
lastScreenOn = millis(); displayToggle(true);
Utils::typeOfPacket(packet, 1); // APRS-LoRa lastScreenOn = millis();
Utils::typeOfPacket(packet, 1); // APRS-LoRa
Serial.println();
} else {
Serial.println(" ---> Rejected (Time): No Tx");
}
} }
} }
} }
@@ -349,7 +355,7 @@ namespace APRS_IS_Utils {
if (espClient.connected()) { if (espClient.connected()) {
if (espClient.available()) { if (espClient.available()) {
String aprsisPacket = espClient.readStringUntil('\r'); String aprsisPacket = espClient.readStringUntil('\r');
// Serial.println(aprsisPacket); aprsisPacket.trim(); // Serial.println(aprsisPacket);
processAPRSISPacket(aprsisPacket); processAPRSISPacket(aprsisPacket);
lastRxTime = millis(); lastRxTime = millis();
} }

View File

@@ -5,6 +5,7 @@
#include "power_utils.h" #include "power_utils.h"
#include "utils.h" #include "utils.h"
extern Configuration Config; extern Configuration Config;
extern uint32_t lastBatteryCheck; extern uint32_t lastBatteryCheck;
@@ -101,7 +102,7 @@ namespace BATTERY_Utils {
int sample; int sample;
int sampleSum = 0; int sampleSum = 0;
#ifdef ADC_CTRL #ifdef ADC_CTRL
#if defined(HELTEC_WIRELESS_TRACKER) #if defined(HELTEC_WIRELESS_TRACKER) || defined(HELTEC_V3_2)
digitalWrite(ADC_CTRL, HIGH); digitalWrite(ADC_CTRL, HIGH);
#endif #endif
#if defined(HELTEC_V3) || defined(HELTEC_V2) || defined(HELTEC_WSL_V3) || defined(HELTEC_WP) #if defined(HELTEC_V3) || defined(HELTEC_V2) || defined(HELTEC_WSL_V3) || defined(HELTEC_WP)
@@ -132,7 +133,7 @@ namespace BATTERY_Utils {
} }
#ifdef ADC_CTRL #ifdef ADC_CTRL
#if defined(HELTEC_WIRELESS_TRACKER) #if defined(HELTEC_WIRELESS_TRACKER) || defined(HELTEC_V3_2)
digitalWrite(ADC_CTRL, LOW); digitalWrite(ADC_CTRL, LOW);
#endif #endif
#if defined(HELTEC_V3) || defined(HELTEC_V2) || defined(HELTEC_WSL_V3) || defined(HELTEC_WP) #if defined(HELTEC_V3) || defined(HELTEC_V2) || defined(HELTEC_WSL_V3) || defined(HELTEC_WP)

View File

@@ -99,7 +99,7 @@ void Configuration::writeFile() {
data["personalNote"] = personalNote; data["personalNote"] = personalNote;
data["blackList"] = blackList; data["blacklist"] = blacklist;
data["webadmin"]["active"] = webadmin.active; data["webadmin"]["active"] = webadmin.active;
data["webadmin"]["username"] = webadmin.username; data["webadmin"]["username"] = webadmin.username;
@@ -107,6 +107,9 @@ void Configuration::writeFile() {
data["ntp"]["gmtCorrection"] = ntp.gmtCorrection; data["ntp"]["gmtCorrection"] = ntp.gmtCorrection;
data["remoteManagement"]["managers"] = remoteManagement.managers;
data["remoteManagement"]["rfOnly"] = remoteManagement.rfOnly;
serializeJson(data, configFile); serializeJson(data, configFile);
configFile.close(); configFile.close();
@@ -223,7 +226,10 @@ bool Configuration::readFile() {
personalNote = data["personalNote"] | "personal note here"; personalNote = data["personalNote"] | "personal note here";
blackList = data["blackList"] | "station callsign"; blacklist = data["blacklist"] | "station callsign";
remoteManagement.managers = data["remoteManagement"]["managers"] | "";
remoteManagement.rfOnly = data["remoteManagement"]["rfOnly"] | true;
if (wifiAPs.size() == 0) { // If we don't have any WiFi's from config we need to add "empty" SSID for AUTO AP if (wifiAPs.size() == 0) { // If we don't have any WiFi's from config we need to add "empty" SSID for AUTO AP
WiFi_AP wifiap; WiFi_AP wifiap;
@@ -331,7 +337,7 @@ void Configuration::init() {
personalNote = ""; personalNote = "";
blackList = ""; blacklist = "";
webadmin.active = false; webadmin.active = false;
webadmin.username = "admin"; webadmin.username = "admin";
@@ -339,6 +345,9 @@ void Configuration::init() {
ntp.gmtCorrection = 0.0; ntp.gmtCorrection = 0.0;
remoteManagement.managers = "";
remoteManagement.rfOnly = true;
Serial.println("All is Written!"); Serial.println("All is Written!");
} }

View File

@@ -2,7 +2,6 @@
#include "configuration.h" #include "configuration.h"
#include "station_utils.h" #include "station_utils.h"
#include "aprs_is_utils.h" #include "aprs_is_utils.h"
#include "query_utils.h"
#include "digi_utils.h" #include "digi_utils.h"
#include "wifi_utils.h" #include "wifi_utils.h"
#include "lora_utils.h" #include "lora_utils.h"
@@ -10,6 +9,7 @@
#include "display.h" #include "display.h"
#include "utils.h" #include "utils.h"
extern Configuration Config; extern Configuration Config;
extern uint32_t lastScreenOn; extern uint32_t lastScreenOn;
extern String iGateBeaconPacket; extern String iGateBeaconPacket;
@@ -117,46 +117,44 @@ namespace DIGI_Utils {
} }
void processLoRaPacket(const String& packet) { void processLoRaPacket(const String& packet) {
if (packet != "") { if (packet.indexOf("NOGATE") == -1) {
if ((packet.substring(0, 3) == "\x3c\xff\x01") && (packet.indexOf("NOGATE") == -1)) { bool thirdPartyPacket = false;
bool thirdPartyPacket = false; String temp, Sender;
String temp, Sender; int firstColonIndex = packet.indexOf(":");
int firstColonIndex = packet.indexOf(":"); if (firstColonIndex > 5 && firstColonIndex < (packet.length() - 1) && packet[firstColonIndex + 1] == '}' && packet.indexOf("TCPIP") > 0) { // 3rd Party
if (firstColonIndex > 5 && firstColonIndex < (packet.length() - 1) && packet[firstColonIndex + 1] == '}' && packet.indexOf("TCPIP") > 0) { // 3rd Party thirdPartyPacket = true;
thirdPartyPacket = true; temp = packet.substring(packet.indexOf(":}") + 2);
temp = packet.substring(packet.indexOf(":}") + 2); Sender = temp.substring(0, temp.indexOf(">"));
Sender = temp.substring(0, temp.indexOf(">")); } else {
} else { temp = packet.substring(3);
temp = packet.substring(3); Sender = packet.substring(3, packet.indexOf(">"));
Sender = packet.substring(3, packet.indexOf(">")); }
if (Sender != Config.callsign) { // Avoid listening to own packets
if (!thirdPartyPacket && !Utils::checkValidCallsign(Sender)) {
return;
} }
if (Sender != Config.callsign && !STATION_Utils::checkBlackList(Sender)) { // Avoid listening to own packets if (STATION_Utils::check25SegBuffer(Sender, temp.substring(temp.indexOf(":") + 2)) || Config.lowPowerMode) {
if (!thirdPartyPacket && !Utils::checkValidCallsign(Sender)) { STATION_Utils::updateLastHeard(Sender);
return; Utils::typeOfPacket(temp, 2); // Digi
} bool queryMessage = false;
if (STATION_Utils::check25SegBuffer(Sender, temp.substring(temp.indexOf(":") + 2)) || Config.lowPowerMode) { if (temp.indexOf("::") > 10) { // it's a message
STATION_Utils::updateLastHeard(Sender); String AddresseeAndMessage = temp.substring(temp.indexOf("::") + 2);
Utils::typeOfPacket(temp, 2); // Digi String Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":"));
bool queryMessage = false; Addressee.trim();
if (temp.indexOf("::") > 10) { // it's a message if (Addressee == Config.callsign) { // it's a message for me!
String AddresseeAndMessage = temp.substring(temp.indexOf("::") + 2); queryMessage = APRS_IS_Utils::processReceivedLoRaMessage(Sender, AddresseeAndMessage, thirdPartyPacket);
String Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":"));
Addressee.trim();
if (Addressee == Config.callsign) { // it's a message for me!
queryMessage = APRS_IS_Utils::processReceivedLoRaMessage(Sender, AddresseeAndMessage, thirdPartyPacket);
}
} }
if (!queryMessage) { }
String loraPacket = generateDigipeatedPacket(packet.substring(3), thirdPartyPacket); if (!queryMessage) {
if (loraPacket != "") { String loraPacket = generateDigipeatedPacket(packet.substring(3), thirdPartyPacket);
if (Config.lowPowerMode) { if (loraPacket != "") {
LoRa_Utils::sendNewPacket(loraPacket); if (Config.lowPowerMode) {
} else { LoRa_Utils::sendNewPacket(loraPacket);
STATION_Utils::addToOutputPacketBuffer(loraPacket); } else {
} STATION_Utils::addToOutputPacketBuffer(loraPacket);
displayToggle(true);
lastScreenOn = millis();
} }
displayToggle(true);
lastScreenOn = millis();
} }
} }
} }

View File

@@ -9,22 +9,37 @@
#include <TFT_eSPI.h> #include <TFT_eSPI.h>
TFT_eSPI tft = TFT_eSPI(); TFT_eSPI tft = TFT_eSPI();
TFT_eSprite sprite = TFT_eSprite(&tft);
#ifdef HELTEC_WIRELESS_TRACKER #ifdef HELTEC_WIRELESS_TRACKER
#define bigSizeFont 2 #define bigSizeFont 2
#define smallSizeFont 1 #define smallSizeFont 1
#define lineSpacing 10 #define lineSpacing 10
#endif #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 #else
#ifdef HAS_EPAPER #ifdef HAS_EPAPER
// #include <heltec-eink-modules.h>
#include "Fonts/FreeSansBold9pt7b.h"
EInkDisplay_WirelessPaperV1_1 display;
String lastEpaperText;
#else #else
#include <Adafruit_GFX.h> #include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h> #if defined(TTGO_T_Beam_S3_SUPREME_V3)
#ifdef HELTEC_WSL_V3_DISPLAY #include <Adafruit_SH110X.h>
Adafruit_SSD1306 display(128, 64, &Wire1, OLED_RST); Adafruit_SH1106G display(128, 64, &Wire, OLED_RST);
#else #else
Adafruit_SSD1306 display(128, 64, &Wire, OLED_RST); #include <Adafruit_SSD1306.h>
#ifdef HELTEC_WSL_V3_DISPLAY
Adafruit_SSD1306 display(128, 64, &Wire1, OLED_RST);
#else
Adafruit_SSD1306 display(128, 64, &Wire, OLED_RST);
#endif
#endif #endif
#endif #endif
#endif #endif
@@ -32,16 +47,8 @@
extern Configuration Config; extern Configuration Config;
String oldHeader, oldFirstLine, oldSecondLine, oldThirdLine, oldFourthLine, oldFifthLine, oldSixthLine;
bool displayFound = false; bool displayFound = false;
void cleanTFT() {
#ifdef HAS_TFT
tft.fillScreen(TFT_BLACK);
#endif
}
void displaySetup() { void displaySetup() {
#ifdef HAS_DISPLAY #ifdef HAS_DISPLAY
delay(500); delay(500);
@@ -53,11 +60,20 @@ void displaySetup() {
} else { } else {
tft.setRotation(1); tft.setRotation(1);
} }
pinMode(TFT_BL, OUTPUT);
digitalWrite(TFT_BL, HIGH);
tft.setTextFont(0); tft.setTextFont(0);
tft.fillScreen(TFT_BLACK); 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 #else
#ifdef HAS_EPAPER #ifdef HAS_EPAPER
// display.landscape();
display.printCenter("LoRa APRS iGate Initialising...");
display.update();
#else #else
#ifdef OLED_DISPLAY_HAS_RST_PIN #ifdef OLED_DISPLAY_HAS_RST_PIN
pinMode(OLED_RST, OUTPUT); pinMode(OLED_RST, OUTPUT);
@@ -66,17 +82,30 @@ void displaySetup() {
digitalWrite(OLED_RST, HIGH); digitalWrite(OLED_RST, HIGH);
#endif #endif
if(display.begin(SSD1306_SWITCHCAPVCC, SCREEN_ADDRESS)) { #if defined(TTGO_T_Beam_S3_SUPREME_V3)
displayFound = true; if (!display.begin(0x3c, false)) {
if (Config.display.turn180) display.setRotation(2); displayFound = true;
display.clearDisplay(); if (Config.display.turn180) display.setRotation(2);
display.setTextColor(WHITE); display.clearDisplay();
display.setTextSize(1); display.setTextColor(SH110X_WHITE);
display.setCursor(0, 0); display.setTextSize(1);
display.ssd1306_command(SSD1306_SETCONTRAST); display.setCursor(0, 0);
display.ssd1306_command(1); display.setContrast(1);
display.display(); display.display();
} }
#else
if(display.begin(SSD1306_SWITCHCAPVCC, SCREEN_ADDRESS)) {
displayFound = true;
if (Config.display.turn180) display.setRotation(2);
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(1);
display.setCursor(0, 0);
display.ssd1306_command(SSD1306_SETCONTRAST);
display.ssd1306_command(1);
display.display();
}
#endif
#endif #endif
#endif #endif
delay(1000); delay(1000);
@@ -90,9 +119,14 @@ void displayToggle(bool toggle) {
digitalWrite(TFT_BL, HIGH); digitalWrite(TFT_BL, HIGH);
#else #else
#ifdef HAS_EPAPER #ifdef HAS_EPAPER
// ... to be continued display.printCenter("EPAPER Display Disabled by toggle...");
display.update();
#else #else
if (displayFound) display.ssd1306_command(SSD1306_DISPLAYON); #if defined(TTGO_T_Beam_S3_SUPREME_V3)
if (displayFound) display.oled_command(SH110X_DISPLAYON);
#else
if (displayFound) display.ssd1306_command(SSD1306_DISPLAYON);
#endif
#endif #endif
#endif #endif
} else { } else {
@@ -100,65 +134,65 @@ void displayToggle(bool toggle) {
digitalWrite(TFT_BL, LOW); digitalWrite(TFT_BL, LOW);
#else #else
#ifdef HAS_EPAPER #ifdef HAS_EPAPER
// ... to be continued display.printCenter("Enabled EPAPER Display...");
display.update();
#else #else
if (displayFound) display.ssd1306_command(SSD1306_DISPLAYOFF); #if defined(TTGO_T_Beam_S3_SUPREME_V3)
if (displayFound) display.oled_command(SH110X_DISPLAYOFF);
#else
if (displayFound) display.ssd1306_command(SSD1306_DISPLAYOFF);
#endif
#endif #endif
#endif #endif
} }
#endif #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) { void displayShow(const String& header, const String& line1, const String& line2, const String& line3, int wait) {
#ifdef HAS_DISPLAY #ifdef HAS_DISPLAY
const String* const lines[] = {&line1, &line2, &line3}; const String* const lines[] = {&line1, &line2, &line3};
#ifdef HAS_TFT #ifdef HAS_TFT
if (shouldCleanTFT(header, line1, line2, line3)) { sprite.fillSprite(TFT_BLACK);
cleanTFT(); #if defined(HELTEC_WIRELESS_TRACKER)
} sprite.fillRect(0, 0, 160, 19, redColor);
tft.setTextColor(TFT_WHITE,TFT_BLACK); #endif
tft.setTextSize(bigSizeFont); #if defined(TTGO_T_DECK_GPS) || defined(TTGO_T_DECK_PLUS)
tft.setCursor(0, 0); sprite.fillRect(0, 0, 320, 43, redColor);
tft.print(header); #endif
tft.setTextSize(smallSizeFont); 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++) { for (int i = 0; i < 3; i++) {
tft.setCursor(0, ((lineSpacing * (2 + i)) - 2)); sprite.drawString(*lines[i], 3, (lineSpacing * (2 + i)) - 2);
tft.print(*lines[i]);
} }
sprite.pushSprite(0,0);
#else #else
#ifdef HAS_EPAPER #ifdef HAS_EPAPER
// ... to be continued display.clearMemory();
display.setCursor(5,10);
display.setFont(&FreeSansBold9pt7b);
display.println(header);
display.setFont(NULL);
for (int i = 0; i < 3; i++) {
display.setCursor(0, 25 + (14 * i));
display.println(*lines[i]);
}
display.update();
#else #else
if (displayFound) { if (displayFound) {
display.clearDisplay(); display.clearDisplay();
display.setTextColor(WHITE); #if defined(TTGO_T_Beam_S3_SUPREME_V3)
display.setTextColor(SH110X_WHITE);
#else
display.setTextColor(WHITE);
#endif
display.setTextSize(1); display.setTextSize(1);
display.setCursor(0, 0); display.setCursor(0, 0);
display.println(header); display.println(header);
@@ -166,8 +200,12 @@ void displayShow(const String& header, const String& line1, const String& line2,
display.setCursor(0, 8 + (8 * i)); display.setCursor(0, 8 + (8 * i));
display.println(*lines[i]); display.println(*lines[i]);
} }
display.ssd1306_command(SSD1306_SETCONTRAST); #if defined(TTGO_T_Beam_S3_SUPREME_V3)
display.ssd1306_command(1); display.setContrast(1);
#else
display.ssd1306_command(SSD1306_SETCONTRAST);
display.ssd1306_command(1);
#endif
display.display(); display.display();
} }
#endif #endif
@@ -180,25 +218,47 @@ void displayShow(const String& header, const String& line1, const String& line2,
#ifdef HAS_DISPLAY #ifdef HAS_DISPLAY
const String* const lines[] = {&line1, &line2, &line3, &line4, &line5, &line6}; const String* const lines[] = {&line1, &line2, &line3, &line4, &line5, &line6};
#ifdef HAS_TFT #ifdef HAS_TFT
if (shouldCleanTFT(header, line1, line2, line3, line4, line5, line6)) { sprite.fillSprite(TFT_BLACK);
cleanTFT(); #if defined(HELTEC_WIRELESS_TRACKER)
} sprite.fillRect(0, 0, 160, 19, redColor);
tft.setTextColor(TFT_WHITE,TFT_BLACK); #endif
tft.setTextSize(bigSizeFont); #if defined(TTGO_T_DECK_GPS) || defined(TTGO_T_DECK_PLUS)
tft.setCursor(0, 0); sprite.fillRect(0, 0, 320, 43, redColor);
tft.print(header); #endif
tft.setTextSize(smallSizeFont); 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++) { for (int i = 0; i < 6; i++) {
tft.setCursor(0, ((lineSpacing * (2 + i)) - 2)); sprite.drawString(*lines[i], 3, (lineSpacing * (2 + i)) - 2);
tft.print(*lines[i]);
} }
sprite.pushSprite(0,0);
#else #else
#ifdef HAS_EPAPER #ifdef HAS_EPAPER
// ... to be continued lastEpaperText = header + line1 + line2 + line3 + line4 + line5 + line6;
display.clearMemory();
display.setCursor(5,10);
display.setFont(&FreeSansBold9pt7b);
display.println(header);
display.setFont(NULL);
for (int i = 0; i < 6; i++) {
display.setCursor(0, 25 + (14 * i));
display.println(*lines[i]);
}
display.update();
#else #else
if (displayFound) { if (displayFound) {
display.clearDisplay(); display.clearDisplay();
display.setTextColor(WHITE); #if defined(TTGO_T_Beam_S3_SUPREME_V3)
display.setTextColor(SH110X_WHITE);
#else
display.setTextColor(WHITE);
#endif
display.setTextSize(2); display.setTextSize(2);
display.setCursor(0, 0); display.setCursor(0, 0);
display.println(header); display.println(header);
@@ -207,8 +267,12 @@ void displayShow(const String& header, const String& line1, const String& line2,
display.setCursor(0, 16 + (8 * i)); display.setCursor(0, 16 + (8 * i));
display.println(*lines[i]); display.println(*lines[i]);
} }
display.ssd1306_command(SSD1306_SETCONTRAST); #if defined(TTGO_T_Beam_S3_SUPREME_V3)
display.ssd1306_command(1); display.setContrast(1);
#else
display.ssd1306_command(SSD1306_SETCONTRAST);
display.ssd1306_command(1);
#endif
display.display(); display.display();
} }
#endif #endif

View File

@@ -110,22 +110,30 @@ namespace GPS_Utils {
} }
String decodeEncodedGPS(const String& packet) { String decodeEncodedGPS(const String& packet) {
const String& GPSPacket = packet.substring(packet.indexOf(":!")+3); int indexOfExclamation = packet.indexOf(":!");
const String& encodedLatitude = GPSPacket.substring(0,4); int indexOfEqual = packet.indexOf(":=");
const String& encodedLongtitude = GPSPacket.substring(4,8);
const String& comment = GPSPacket.substring(12);
int Y1 = int(encodedLatitude[0]); const uint8_t OFFSET = 3; // Offset for encoded data in the packet
int Y2 = int(encodedLatitude[1]); String GPSPacket;
int Y3 = int(encodedLatitude[2]); if (indexOfExclamation > 10) {
int Y4 = int(encodedLatitude[3]); GPSPacket = packet.substring(indexOfExclamation + OFFSET);
float decodedLatitude = 90.0 - ((((Y1-33) * pow(91,3)) + ((Y2-33) * pow(91,2)) + ((Y3-33) * 91) + Y4-33) / 380926.0); } else if (indexOfEqual > 10) {
GPSPacket = packet.substring(indexOfEqual + OFFSET);
int X1 = int(encodedLongtitude[0]); }
int X2 = int(encodedLongtitude[1]);
int X3 = int(encodedLongtitude[2]); String encodedLatitude = GPSPacket.substring(0,4);
int X4 = int(encodedLongtitude[3]); int Y1 = encodedLatitude[0] - 33;
float decodedLongitude = -180.0 + ((((X1-33) * pow(91,3)) + ((X2-33) * pow(91,2)) + ((X3-33) * 91) + X4-33) / 190463.0); int Y2 = encodedLatitude[1] - 33;
int Y3 = encodedLatitude[2] - 33;
int Y4 = encodedLatitude[3] - 33;
float decodedLatitude = 90.0 - (((Y1 * pow(91,3)) + (Y2 * pow(91,2)) + (Y3 * 91) + Y4) / 380926.0);
String encodedLongitude = GPSPacket.substring(4,8);
int X1 = encodedLongitude[0] - 33;
int X2 = encodedLongitude[1] - 33;
int X3 = encodedLongitude[2] - 33;
int X4 = encodedLongitude[3] - 33;
float decodedLongitude = -180.0 + (((X1 * pow(91,3)) + (X2 * pow(91,2)) + (X3 * 91) + X4) / 190463.0);
distance = String(calculateDistanceTo(decodedLatitude, decodedLongitude),1); distance = String(calculateDistanceTo(decodedLatitude, decodedLongitude),1);
@@ -136,6 +144,7 @@ namespace GPS_Utils {
decodedGPS += distance; decodedGPS += distance;
decodedGPS += "km"; decodedGPS += "km";
String comment = GPSPacket.substring(12);
if (comment != "") { if (comment != "") {
decodedGPS += " / "; decodedGPS += " / ";
decodedGPS += comment; decodedGPS += comment;
@@ -144,33 +153,30 @@ namespace GPS_Utils {
} }
String getReceivedGPS(const String& packet) { String getReceivedGPS(const String& packet) {
String infoGPS; int indexOfExclamation = packet.indexOf(":!");
if (packet.indexOf(":!") > 10) { int indexOfEqual = packet.indexOf(":=");
infoGPS = packet.substring(packet.indexOf(":!") + 2); int indexOfAt = packet.indexOf(":@");
} else if (packet.indexOf(":=") > 10) {
infoGPS = packet.substring(packet.indexOf(":=") + 2);
}
const String& Latitude = infoGPS.substring(0,8);
const String& Longitude = infoGPS.substring(9,18);
const String& comment = infoGPS.substring(19);
float convertedLatitude, convertedLongitude;
const String& firstLatPart = Latitude.substring(0,2);
const String& secondLatPart = Latitude.substring(2,4);
const String& thirdLatPart = Latitude.substring(Latitude.indexOf(".") + 1, Latitude.indexOf(".") + 3);
convertedLatitude = firstLatPart.toFloat() + (secondLatPart.toFloat()/60) + (thirdLatPart.toFloat()/(60*100));
const String& firstLngPart = Longitude.substring(0,3); String infoGPS;
const String& secondLngPart = Longitude.substring(3,5); if (indexOfExclamation > 10) {
const String& thirdLngPart = Longitude.substring(Longitude.indexOf(".") + 1, Longitude.indexOf(".") + 3); infoGPS = packet.substring(indexOfExclamation + 2);
convertedLongitude = firstLngPart.toFloat() + (secondLngPart.toFloat()/60) + (thirdLngPart.toFloat()/(60*100)); } else if (indexOfEqual > 10) {
infoGPS = packet.substring(indexOfEqual + 2);
if (String(Latitude[7]) == "S") { } else if (indexOfAt > 10) {
convertedLatitude = -convertedLatitude; infoGPS = packet.substring(indexOfAt + 9); // 9 = 2+7 (when 7 is timestamp characters)
}
if (String(Longitude[8]) == "W") {
convertedLongitude = -convertedLongitude;
} }
String Latitude = infoGPS.substring(0,8); // First 8 characters are Latitude
float convertedLatitude = Latitude.substring(0,2).toFloat(); // First 2 digits (Degrees)
convertedLatitude += Latitude.substring(2,4).toFloat() / 60; // Next 2 digits (Minutes)
convertedLatitude += Latitude.substring(Latitude.indexOf(".") + 1, Latitude.indexOf(".") + 3).toFloat() / (60*100);
if (Latitude.endsWith("S")) convertedLatitude = -convertedLatitude; // Handle Southern Hemisphere
String Longitude = infoGPS.substring(9,18); // Next 9 characters are Longitude
float convertedLongitude = Longitude.substring(0,3).toFloat(); // First 3 digits (Degrees)
convertedLongitude += Longitude.substring(3,5).toFloat() / 60; // Next 2 digits (Minutes)
convertedLongitude += Longitude.substring(Longitude.indexOf(".") + 1, Longitude.indexOf(".") + 3).toFloat() / (60*100);
if (Longitude.endsWith("W")) convertedLongitude = -convertedLongitude; // Handle Western Hemisphere
distance = String(calculateDistanceTo(convertedLatitude, convertedLongitude),1); distance = String(calculateDistanceTo(convertedLatitude, convertedLongitude),1);
@@ -181,6 +187,7 @@ namespace GPS_Utils {
decodedGPS += distance; decodedGPS += distance;
decodedGPS += "km"; decodedGPS += "km";
String comment = infoGPS.substring(19);
if (comment != "") { if (comment != "") {
decodedGPS += " / "; decodedGPS += " / ";
decodedGPS += comment; decodedGPS += comment;
@@ -189,22 +196,30 @@ namespace GPS_Utils {
} }
String getDistanceAndComment(const String& packet) { String getDistanceAndComment(const String& packet) {
uint8_t encodedBytePosition = 0; int indexOfAt = packet.indexOf(":@");
if (packet.indexOf(":!") > 10) { if (indexOfAt > 10) {
encodedBytePosition = packet.indexOf(":!") + 14; return getReceivedGPS(packet);
}
if (packet.indexOf(":=") > 10) {
encodedBytePosition = packet.indexOf(":=") + 14;
}
if (encodedBytePosition != 0) {
char currentChar = packet[encodedBytePosition];
if (currentChar == 'G' || currentChar == 'Q' || currentChar == '[' || currentChar == 'H' || currentChar == 'X') {
return decodeEncodedGPS(packet);
} else {
return getReceivedGPS(packet);
}
} else { } else {
return " _ / _ / _ "; const uint8_t ENCODED_BYTE_OFFSET = 14; // Offset for encoded data in the packet
int indexOfExclamation = packet.indexOf(":!");
int indexOfEqual = packet.indexOf(":=");
uint8_t encodedBytePosition = 0;
if (indexOfExclamation > 10) { // Determine the position where encoded data starts
encodedBytePosition = indexOfExclamation + ENCODED_BYTE_OFFSET;
} else if (indexOfEqual > 10) {
encodedBytePosition = indexOfEqual + ENCODED_BYTE_OFFSET;
}
if (encodedBytePosition != 0) {
char currentChar = packet[encodedBytePosition];
if (currentChar == 'G' || currentChar == 'Q' || currentChar == '[' || currentChar == 'H' || currentChar == 'X') {
return decodeEncodedGPS(packet); // If valid encoded data position is found, decode it
} else {
return getReceivedGPS(packet);
}
} else {
return " _ / _ / _ ";
}
} }
} }

View File

@@ -1,6 +1,7 @@
#include <Arduino.h> #include <Arduino.h>
#include "kiss_protocol.h" #include "kiss_protocol.h"
bool validateTNC2Frame(const String& tnc2FormattedFrame) { bool validateTNC2Frame(const String& tnc2FormattedFrame) {
return (tnc2FormattedFrame.indexOf(':') != -1) && (tnc2FormattedFrame.indexOf('>') != -1); return (tnc2FormattedFrame.indexOf(':') != -1) && (tnc2FormattedFrame.indexOf('>') != -1);
} }

View File

@@ -2,12 +2,14 @@
#include <WiFi.h> #include <WiFi.h>
#include "configuration.h" #include "configuration.h"
#include "aprs_is_utils.h" #include "aprs_is_utils.h"
#include "station_utils.h"
#include "board_pinout.h" #include "board_pinout.h"
#include "syslog_utils.h" #include "syslog_utils.h"
#include "ntp_utils.h" #include "ntp_utils.h"
#include "display.h" #include "display.h"
#include "utils.h" #include "utils.h"
extern Configuration Config; extern Configuration Config;
extern uint32_t lastRxTime; extern uint32_t lastRxTime;
@@ -139,7 +141,7 @@ namespace LoRa_Utils {
if (Config.syslog.active && WiFi.status() == WL_CONNECTED) { if (Config.syslog.active && WiFi.status() == WL_CONNECTED) {
SYSLOG_Utils::log(3, newPacket, 0, 0.0, 0); // TX SYSLOG_Utils::log(3, newPacket, 0, 0.0, 0); // TX
} }
Utils::print("---> LoRa Packet Tx : "); Utils::print("---> LoRa Packet Tx : ");
Utils::println(newPacket); Utils::println(newPacket);
} else { } else {
Utils::print(F("failed, code ")); Utils::print(F("failed, code "));
@@ -182,27 +184,33 @@ namespace LoRa_Utils {
int state = radio.readData(packet); int state = radio.readData(packet);
if (state == RADIOLIB_ERR_NONE) { if (state == RADIOLIB_ERR_NONE) {
if (packet != "") { if (packet != "") {
rssi = radio.getRSSI();
snr = radio.getSNR();
freqError = radio.getFrequencyError();
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) { String sender = packet.substring(3, packet.indexOf(">"));
if (receivedPackets.size() >= 10) { if (packet.substring(0,3) == "\x3c\xff\x01" && !STATION_Utils::isBlacklisted(sender)){ // avoid processing BlackListed stations
receivedPackets.erase(receivedPackets.begin()); rssi = radio.getRSSI();
snr = radio.getSNR();
freqError = radio.getFrequencyError();
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) {
if (receivedPackets.size() >= 10) {
receivedPackets.erase(receivedPackets.begin());
}
ReceivedPacket receivedPacket;
receivedPacket.rxTime = NTP_Utils::getFormatedTime();
receivedPacket.packet = packet.substring(3);
receivedPacket.RSSI = rssi;
receivedPacket.SNR = snr;
receivedPackets.push_back(receivedPacket);
} }
ReceivedPacket receivedPacket;
receivedPacket.rxTime = NTP_Utils::getFormatedTime();
receivedPacket.packet = packet.substring(3);
receivedPacket.RSSI = rssi;
receivedPacket.SNR = snr;
receivedPackets.push_back(receivedPacket);
}
if (Config.syslog.active && WiFi.status() == WL_CONNECTED) { if (Config.syslog.active && WiFi.status() == WL_CONNECTED) {
SYSLOG_Utils::log(1, packet, rssi, snr, freqError); // RX SYSLOG_Utils::log(1, packet, rssi, snr, freqError); // RX
} }
} else {
packet = "";
}
lastRxTime = millis(); lastRxTime = millis();
return packet; return packet;
} }

View File

@@ -5,6 +5,7 @@
#include "ota_utils.h" #include "ota_utils.h"
#include "display.h" #include "display.h"
extern Configuration Config; extern Configuration Config;
extern uint32_t lastScreenOn; extern uint32_t lastScreenOn;
extern bool isUpdatingOTA; extern bool isUpdatingOTA;
@@ -48,13 +49,13 @@ namespace OTA_Utils {
void onOTAEnd(bool success) { void onOTAEnd(bool success) {
displayToggle(true); displayToggle(true);
lastScreenOn = millis(); lastScreenOn = millis();
if (success) {
Serial.println("OTA update finished successfully!"); String statusMessage = success ? "OTA update success!" : "OTA update fail!";
displayShow("", "", " OTA update success!", "", " Rebooting ...", "", "", 4000); String rebootMessage = success ? "Rebooting ..." : "";
} else {
Serial.println("There was an error during OTA update!"); Serial.println(success ? "OTA update finished successfully!" : "There was an error during OTA update!");
displayShow("", "", " OTA update fail!", "", "", "", "", 4000); displayShow("", "", statusMessage, "", rebootMessage, "", "", 4000);
}
isUpdatingOTA = false; isUpdatingOTA = false;
} }

View File

@@ -4,9 +4,17 @@
#include "power_utils.h" #include "power_utils.h"
#if defined(HAS_AXP192) || defined(HAS_AXP2101) #if defined(HAS_AXP192) || defined(HAS_AXP2101)
#define I2C_SDA 21 #ifdef TTGO_T_Beam_S3_SUPREME_V3
#define I2C_SCL 22 #define I2C0_SDA 17
#define IRQ_PIN 35 #define I2C0_SCL 18
#define I2C1_SDA 42
#define I2C1_SCL 41
#define IRQ_PIN 40
#else
#define I2C_SDA 21
#define I2C_SCL 22
#define IRQ_PIN 35
#endif
#endif #endif
#ifdef HAS_AXP192 #ifdef HAS_AXP192
@@ -54,8 +62,13 @@ namespace POWER_Utils {
#endif #endif
#ifdef HAS_AXP2101 #ifdef HAS_AXP2101
#ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.setALDO4Voltage(3300);
PMU.enableALDO4();
#else
PMU.setALDO3Voltage(3300); PMU.setALDO3Voltage(3300);
PMU.enableALDO3(); PMU.enableALDO3();
#endif
#endif #endif
#ifdef HELTEC_WIRELESS_TRACKER #ifdef HELTEC_WIRELESS_TRACKER
digitalWrite(VEXT_CTRL, HIGH); digitalWrite(VEXT_CTRL, HIGH);
@@ -69,7 +82,11 @@ namespace POWER_Utils {
#endif #endif
#ifdef HAS_AXP2101 #ifdef HAS_AXP2101
PMU.disableALDO3(); #ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.disableALDO4();
#else
PMU.disableALDO3();
#endif
#endif #endif
#ifdef HELTEC_WIRELESS_TRACKER #ifdef HELTEC_WIRELESS_TRACKER
digitalWrite(VEXT_CTRL, LOW); digitalWrite(VEXT_CTRL, LOW);
@@ -83,8 +100,13 @@ namespace POWER_Utils {
PMU.enableLDO2(); PMU.enableLDO2();
#endif #endif
#ifdef HAS_AXP2101 #ifdef HAS_AXP2101
PMU.setALDO2Voltage(3300); #ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.enableALDO2(); PMU.setALDO3Voltage(3300);
PMU.enableALDO3();
#else
PMU.setALDO2Voltage(3300);
PMU.enableALDO2();
#endif
#endif #endif
} }
@@ -93,7 +115,11 @@ namespace POWER_Utils {
PMU.disableLDO2(); PMU.disableLDO2();
#endif #endif
#ifdef HAS_AXP2101 #ifdef HAS_AXP2101
PMU.disableALDO2(); #ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.disableALDO3();
#else
PMU.disableALDO2();
#endif
#endif #endif
} }
@@ -111,20 +137,29 @@ namespace POWER_Utils {
} }
return result; return result;
#elif defined(HAS_AXP2101) #elif defined(HAS_AXP2101)
bool result = PMU.begin(Wire, AXP2101_SLAVE_ADDRESS, I2C_SDA, I2C_SCL); #ifdef TTGO_T_Beam_S3_SUPREME_V3
bool result = PMU.begin(Wire1, AXP2101_SLAVE_ADDRESS, I2C1_SDA, I2C1_SCL);
#else
bool result = PMU.begin(Wire, AXP2101_SLAVE_ADDRESS, I2C_SDA, I2C_SCL);
#endif
if (result) { if (result) {
PMU.disableDC2(); PMU.disableDC2();
PMU.disableDC3(); PMU.disableDC3();
PMU.disableDC4(); PMU.disableDC4();
PMU.disableDC5(); PMU.disableDC5();
PMU.disableALDO1(); #ifndef TTGO_T_Beam_S3_SUPREME_V3
PMU.disableALDO4(); PMU.disableALDO1();
PMU.disableALDO4();
#endif
PMU.disableBLDO1(); PMU.disableBLDO1();
PMU.disableBLDO2(); PMU.disableBLDO2();
PMU.disableDLDO1(); PMU.disableDLDO1();
PMU.disableDLDO2(); PMU.disableDLDO2();
PMU.setDC1Voltage(3300); PMU.setDC1Voltage(3300);
PMU.enableDC1(); PMU.enableDC1();
#ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.setALDO1Voltage(3300);
#endif
PMU.setButtonBatteryChargeVoltage(3300); PMU.setButtonBatteryChargeVoltage(3300);
PMU.enableButtonBatteryCharge(); PMU.enableButtonBatteryCharge();
PMU.disableIRQ(XPOWERS_AXP2101_ALL_IRQ); PMU.disableIRQ(XPOWERS_AXP2101_ALL_IRQ);
@@ -152,8 +187,16 @@ namespace POWER_Utils {
#endif #endif
#ifdef HAS_AXP2101 #ifdef HAS_AXP2101
Wire.begin(SDA, SCL); bool beginStatus = false;
if (begin(Wire)) { #ifdef TTGO_T_Beam_S3_SUPREME_V3
Wire1.begin(I2C1_SDA, I2C1_SCL);
Wire.begin(I2C0_SDA, I2C0_SCL);
if (begin(Wire1)) beginStatus = true;
#else
Wire.begin(SDA, SCL);
if (begin(Wire)) beginStatus = true;
#endif
if (beginStatus) {
Serial.println("AXP2101 init done!"); Serial.println("AXP2101 init done!");
} else { } else {
Serial.println("AXP2101 init failed!"); Serial.println("AXP2101 init failed!");
@@ -181,10 +224,10 @@ namespace POWER_Utils {
#ifdef VEXT_CTRL #ifdef VEXT_CTRL
pinMode(VEXT_CTRL,OUTPUT); // GPS + TFT on HELTEC Wireless_Tracker and only for Oled in HELTEC V3 pinMode(VEXT_CTRL,OUTPUT); // GPS + TFT on HELTEC Wireless_Tracker and only for Oled in HELTEC V3
#ifndef HELTEC_WSL_V3 #if defined(HELTEC_WIRELESS_TRACKER) || defined(HELTEC_V3)
digitalWrite(VEXT_CTRL, HIGH); digitalWrite(VEXT_CTRL, HIGH);
#endif #endif
#ifdef HELTEC_WP #if defined(HELTEC_WP) || defined(HELTEC_WS) || defined(HELTEC_V3_2)
digitalWrite(VEXT_CTRL, LOW); digitalWrite(VEXT_CTRL, LOW);
#endif #endif
#endif #endif
@@ -201,13 +244,29 @@ namespace POWER_Utils {
Wire.begin(BOARD_I2C_SDA, BOARD_I2C_SCL); Wire.begin(BOARD_I2C_SDA, BOARD_I2C_SCL);
#endif #endif
#if defined(HELTEC_V3) || defined(HELTEC_WP) || defined(HELTEC_WSL_V3) || defined(HELTEC_WSL_V3_DISPLAY) #if defined(HELTEC_V3) || defined(HELTEC_V3_2) || defined(HELTEC_WS) || defined(LIGHTGATEWAY_1_0) || defined(TTGO_LORA32_T3S3_V1_2) || defined(HELTEC_V2)
Wire1.begin(BOARD_I2C_SDA, BOARD_I2C_SCL);
#endif
#if defined(HELTEC_V3) || defined(HELTEC_WS) || defined(LIGHTGATEWAY_1_0) || defined(TTGO_LORA32_T3S3_V1_2) || defined(HELTEC_V2)
Wire.begin(OLED_SDA, OLED_SCL); Wire.begin(OLED_SDA, OLED_SCL);
#endif #endif
#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
#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); delay(1000);
BATTERY_Utils::setup(); BATTERY_Utils::setup();

View File

@@ -22,9 +22,9 @@ namespace QUERY_Utils {
String queryQuestion = query; String queryQuestion = query;
queryQuestion.toUpperCase(); queryQuestion.toUpperCase();
if (queryQuestion == "?APRS?" || queryQuestion == "H" || queryQuestion == "HELP" || queryQuestion=="?") { if (queryQuestion == "?APRS?" || queryQuestion == "H" || queryQuestion == "HELP" || queryQuestion=="?") {
answer.concat("?APRSV ?APRSP ?APRSL ?APRSH ?WHERE callsign"); answer.concat("?APRSV ?APRSP ?APRSL ?APRSSSR ?EM=? ?TX=? "); // ?APRSH ?WHERE callsign
} else if (queryQuestion == "?APRSV") { } else if (queryQuestion == "?APRSV") {
answer.concat("CA2RXU_LoRa_iGate 2.0 v"); answer.concat("CA2RXU_LoRa_iGate 2.3 v");
answer.concat(versionDate); answer.concat(versionDate);
} else if (queryQuestion == "?APRSP") { } else if (queryQuestion == "?APRSP") {
answer.concat("iGate QTH: "); answer.concat("iGate QTH: ");
@@ -46,29 +46,69 @@ namespace QUERY_Utils {
char signalData[35]; char signalData[35];
snprintf(signalData, sizeof(signalData), " %ddBm / %.2fdB / %dHz", rssi, snr, freqError); snprintf(signalData, sizeof(signalData), " %ddBm / %.2fdB / %dHz", rssi, snr, freqError);
answer.concat(signalData); answer.concat(signalData);
} else if (queryQuestion.indexOf("?APRSH") == 0) { } /*else if (queryQuestion.indexOf("?APRSH") == 0) {
// sacar callsign despues de ?APRSH // sacar callsign despues de ?APRSH
Serial.println("escuchaste a X estacion? en las ultimas 24 o 8 horas?"); Serial.println("escuchaste a X estacion? en las ultimas 24 o 8 horas?");
answer.concat("?APRSH on development 73!"); answer.concat("?APRSH on development 73!");
} else if (queryQuestion.indexOf("?WHERE") == 0) { } *//*else if (queryQuestion.indexOf("?WHERE") == 0) {
// agregar callsign para completar donde esta X callsign --> posicion // agregar callsign para completar donde esta X callsign --> posicion
Serial.println("estaciones escuchadas directo (ultimos 30 min)"); Serial.println("estaciones escuchadas directo (ultimos 30 min)");
answer.concat("?WHERE on development 73!"); answer.concat("?WHERE on development 73!");
} else if (queryQuestion.indexOf("?APRSEEM") == 0 && Config.digi.ecoMode == true) { // Exit Digipeater EcoMode } */
answer = "DigiEcoMode:Stop"; else if (STATION_Utils::isManager(station) && (!queryFromAPRSIS || !Config.remoteManagement.rfOnly)) {
Config.digi.ecoMode = false; if (queryQuestion.indexOf("?EM=OFF") == 0) {
Config.display.alwaysOn = true; if ((Config.digi.mode == 2 || Config.digi.mode == 3) && Config.loramodule.txActive && Config.loramodule.rxActive && !Config.aprs_is.active) {
Config.display.timeout = 10; if (Config.digi.ecoMode) { // Exit Digipeater EcoMode
shouldSleepLowVoltage = true; // to make sure all packets in outputPacketBuffer are sended before restart. answer = "DigiEcoMode:OFF";
saveNewDigiEcoModeConfig = true; Config.digi.ecoMode = false;
} else if (queryQuestion.indexOf("?APRSSEM") == 0 && Config.digi.ecoMode == false) { // Start Digipeater EcoMode Config.display.alwaysOn = true;
answer = "DigiEcoMode:Start"; Config.display.timeout = 10;
Config.digi.ecoMode = true; shouldSleepLowVoltage = true; // to make sure all packets in outputPacketBuffer are sended before restart.
shouldSleepLowVoltage = true; // to make sure all packets in outputPacketBuffer are sended before restart. saveNewDigiEcoModeConfig = true;
saveNewDigiEcoModeConfig = true; } else {
} else if (queryQuestion.indexOf("?APRSEMS") == 0) { // Digipeater EcoMode Status answer = "DigiEcoMode was OFF";
answer = (Config.digi.ecoMode) ? "DigiEcoMode:ON" : "DigiEcoMode:OFF"; }
} else {
answer = "DigiEcoMode control not possible";
}
} else if (queryQuestion.indexOf("?EM=ON") == 0) {
if ((Config.digi.mode == 2 || Config.digi.mode == 3) && Config.loramodule.txActive && Config.loramodule.rxActive && !Config.aprs_is.active) {
if (!Config.digi.ecoMode) { // Start Digipeater EcoMode
answer = "DigiEcoMode:ON";
Config.digi.ecoMode = true;
shouldSleepLowVoltage = true; // to make sure all packets in outputPacketBuffer are sended before restart.
saveNewDigiEcoModeConfig = true;
} else {
answer = "DigiEcoMode was ON";
}
} else {
answer = "DigiEcoMode control not possible";
}
} else if (queryQuestion.indexOf("?EM=?") == 0) { // Digipeater EcoMode Status
answer = (Config.digi.ecoMode) ? "DigiEcoMode:ON" : "DigiEcoMode:OFF";
} else if (queryQuestion.indexOf("?TX=ON") == 0) {
if (Config.loramodule.txActive) {
answer = "TX was ON";
} else {
Config.loramodule.txActive = true;
answer = "TX=ON";
}
} else if (queryQuestion.indexOf("?TX=OFF") == 0) {
if (!Config.loramodule.txActive) {
answer = "TX was OFF";
} else {
Config.loramodule.txActive = false;
answer = "TX=OFF";
}
} else if (queryQuestion.indexOf("?TX=?") == 0) {
answer = (Config.loramodule.txActive) ? "TX=ON" : "TX=OFF";
} else if (queryQuestion.indexOf("?COMMIT") == 0) { // saving for next reboot
answer = "New Config Saved";
Config.writeFile();
}
} }
if (answer == "") return "";
String queryAnswer = Config.callsign; String queryAnswer = Config.callsign;
queryAnswer += ">APLRG1"; queryAnswer += ">APLRG1";
@@ -90,6 +130,11 @@ namespace QUERY_Utils {
queryAnswer += processedStation; queryAnswer += processedStation;
queryAnswer += ":"; queryAnswer += ":";
queryAnswer += answer; queryAnswer += answer;
queryAnswer += " *";
queryAnswer += char(random(97, 123));
queryAnswer += char(random(97, 123));
queryAnswer += "*";
return queryAnswer; return queryAnswer;
} }

View File

@@ -7,6 +7,7 @@
#include "utils.h" #include "utils.h"
#include <vector> #include <vector>
extern Configuration Config; extern Configuration Config;
extern uint32_t lastRxTime; extern uint32_t lastRxTime;
extern String fourthLine; extern String fourthLine;
@@ -16,41 +17,87 @@ uint32_t lastTxTime = millis();
std::vector<LastHeardStation> lastHeardStations; std::vector<LastHeardStation> lastHeardStations;
std::vector<String> outputPacketBuffer; std::vector<String> outputPacketBuffer;
std::vector<Packet25SegBuffer> packet25SegBuffer; std::vector<Packet25SegBuffer> packet25SegBuffer;
std::vector<String> blackList; std::vector<String> blacklist;
std::vector<String> managers;
std::vector<LastHeardStation> lastHeardObjects;
bool saveNewDigiEcoModeConfig = false; bool saveNewDigiEcoModeConfig = false;
namespace STATION_Utils { namespace STATION_Utils {
void loadBlackList() { std::vector<String> loadCallSignList(const String& list) {
if (Config.blackList != "") { std::vector<String> loadedList;
String callsigns = Config.blackList;
int spaceIndex = callsigns.indexOf(" ");
while (spaceIndex >= 0) { String callsigns = list;
blackList.push_back(callsigns.substring(0, spaceIndex)); callsigns.trim();
callsigns = callsigns.substring(spaceIndex + 1);
spaceIndex = callsigns.indexOf(" "); while (callsigns.length() > 0) { // != ""
int spaceIndex = callsigns.indexOf(" ");
if (spaceIndex == -1) { // No more spaces, add the last part
loadedList.push_back(callsigns);
break;
} }
callsigns.trim(); loadedList.push_back(callsigns.substring(0, spaceIndex));
if (callsigns.length() > 0) blackList.push_back(callsigns); // Add the last word if available callsigns = callsigns.substring(spaceIndex + 1);
callsigns.trim(); // Trim in case of multiple spaces
} }
return loadedList;
} }
bool checkBlackList(const String& callsign) { void loadBlacklist() {
for (int i = 0; i < blackList.size(); i++) { blacklist = loadCallSignList(Config.blacklist);
if (blackList[i].indexOf("*") >= 0) { // use wild card }
String wildCard = blackList[i].substring(0, blackList[i].indexOf("*"));
if (callsign.startsWith(wildCard))return true; void loadManagers() {
managers = loadCallSignList(Config.remoteManagement.managers);
}
bool checkCallsignList(const std::vector<String>& list, const String& callsign) {
for (int i = 0; i < list.size(); i++) {
int wildcardIndex = list[i].indexOf("*");
if (wildcardIndex >= 0) {
String wildcard = list[i].substring(0, wildcardIndex);
if (callsign.startsWith(wildcard)) return true;
} else { } else {
if (blackList[i] == callsign) return true; if (list[i] == callsign) return true;
} }
} }
return false; return false;
}
bool isBlacklisted(const String& callsign) {
return checkCallsignList(blacklist, callsign);
} }
bool isManager(const String& callsign) {
return checkCallsignList(managers, callsign);
}
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() { void deleteNotHeard() {
std::vector<LastHeardStation> lastHeardStation_temp; std::vector<LastHeardStation> lastHeardStation_temp;
for (int i = 0; i < lastHeardStations.size(); i++) { for (int i = 0; i < lastHeardStations.size(); i++) {
@@ -72,22 +119,11 @@ namespace STATION_Utils {
if (lastHeardStations[i].station == station) { if (lastHeardStations[i].station == station) {
lastHeardStations[i].lastHeardTime = millis(); lastHeardStations[i].lastHeardTime = millis();
stationHeard = true; stationHeard = true;
break;
} }
} }
if (!stationHeard) { if (!stationHeard) lastHeardStations.emplace_back(LastHeardStation{millis(), station});
LastHeardStation lastStation; Utils::activeStations();
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());
} }
bool wasHeard(const String& station) { bool wasHeard(const String& station) {
@@ -98,7 +134,7 @@ namespace STATION_Utils {
return true; 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; return false;
} }
@@ -112,11 +148,7 @@ namespace STATION_Utils {
if (packet25SegBuffer[i].station == station && packet25SegBuffer[i].payload == textMessage) return false; if (packet25SegBuffer[i].station == station && packet25SegBuffer[i].payload == textMessage) return false;
} }
} }
Packet25SegBuffer packet; packet25SegBuffer.emplace_back(Packet25SegBuffer{millis(), station, textMessage});
packet.receivedTime = millis();
packet.station = station;
packet.payload = textMessage;
packet25SegBuffer.push_back(packet);
return true; return true;
} }

View File

@@ -4,6 +4,7 @@
#include "syslog_utils.h" #include "syslog_utils.h"
#include "gps_utils.h" #include "gps_utils.h"
extern Configuration Config; extern Configuration Config;
WiFiUDP udpClient; WiFiUDP udpClient;
@@ -20,6 +21,10 @@ namespace SYSLOG_Utils {
char signalData[35]; char signalData[35];
snprintf(signalData, sizeof(signalData), " / %ddBm / %.2fdB / %dHz", rssi, snr, freqError); 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) { switch (type) {
case 0: // CRC case 0: // CRC
syslogPacket.concat("CRC / CRC-ERROR / "); syslogPacket.concat("CRC / CRC-ERROR / ");
@@ -28,59 +33,57 @@ namespace SYSLOG_Utils {
break; break;
case 1: // RX case 1: // RX
syslogPacket.concat("RX / "); syslogPacket.concat("RX / ");
if (packet.indexOf("::") > 10) { if (nextChar == ':') {
syslogPacket.concat("MESSAGE / "); syslogPacket.concat("MESSAGE / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">"))); syslogPacket.concat(sender);
syslogPacket.concat(" ---> "); syslogPacket.concat(packet.substring(packet.indexOf("::") + 2)); syslogPacket.concat(" ---> ");
syslogPacket.concat(signalData); syslogPacket.concat(packet.substring(colonIndex + 2));
} else if (packet.indexOf(":!") > 10 || packet.indexOf(":=") > 10) { } else if (nextChar == '!' || nextChar == '=' || nextChar == '@') {
syslogPacket.concat("GPS / "); syslogPacket.concat("GPS / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">"))); syslogPacket.concat(sender);
syslogPacket.concat(" / "); syslogPacket.concat(" / ");
int greaterThanIndex = packet.indexOf(">");
if (packet.indexOf("WIDE1-1") > 10) { if (packet.indexOf("WIDE1-1") > 10) {
syslogPacket.concat(packet.substring(packet.indexOf(">") + 1, packet.indexOf(","))); syslogPacket.concat(packet.substring(greaterThanIndex + 1, packet.indexOf(",")));
syslogPacket.concat(" / WIDE1-1"); syslogPacket.concat(" / WIDE1-1");
} else { } else {
syslogPacket.concat(packet.substring(packet.indexOf(">") + 1, packet.indexOf(":"))); syslogPacket.concat(packet.substring(greaterThanIndex + 1, colonIndex));
syslogPacket.concat(" / -"); syslogPacket.concat(" / -");
} }
syslogPacket.concat(signalData); } else if (nextChar == '>') {
syslogPacket.concat(" / ");
syslogPacket.concat(GPS_Utils::getDistanceAndComment(packet));
} else if (packet.indexOf(":>") > 10) {
syslogPacket.concat("STATUS / "); syslogPacket.concat("STATUS / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">"))); syslogPacket.concat(sender);
syslogPacket.concat(" ---> "); syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf(":>") + 2)); syslogPacket.concat(packet.substring(colonIndex + 2));
syslogPacket.concat(signalData); } else if (nextChar == '`') {
} else if (packet.indexOf(":`") > 10) {
syslogPacket.concat("MIC-E / "); syslogPacket.concat("MIC-E / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">"))); syslogPacket.concat(sender);
syslogPacket.concat(" ---> "); syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf(":`") + 2)); syslogPacket.concat(packet.substring(colonIndex + 2));
syslogPacket.concat(signalData); } 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) { } else if (packet.indexOf(":T#") >= 10 && packet.indexOf(":=/") == -1) {
syslogPacket.concat("TELEMETRY / "); syslogPacket.concat("TELEMETRY / ");
syslogPacket.concat(packet.substring(3, packet.indexOf(">"))); syslogPacket.concat(sender);
syslogPacket.concat(" ---> "); syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf(":T#") + 3)); 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 { } else {
syslogPacket.concat(packet); syslogPacket.concat(packet);
syslogPacket.concat(signalData); }
syslogPacket.concat(signalData);
if (nextChar == '!' || nextChar == '=' || nextChar == '@') {
syslogPacket.concat(" / ");
syslogPacket.concat(GPS_Utils::getDistanceAndComment(packet));
} }
break; break;
case 2: // APRSIS TX case 2: // APRSIS TX
syslogPacket.concat("APRSIS TX / "); syslogPacket.concat("APRSIS TX / ");
if (packet.indexOf(":>") > 10) { if (nextChar == '>') {
syslogPacket.concat("StartUp_Status / "); syslogPacket.concat("StartUp_Status / ");
syslogPacket.concat(packet.substring(packet.indexOf(":>") + 2)); syslogPacket.concat(packet.substring(colonIndex + 2));
} else { } else {
syslogPacket.concat("QUERY / "); syslogPacket.concat("QUERY / ");
syslogPacket.concat(packet); syslogPacket.concat(packet);
@@ -91,11 +94,11 @@ namespace SYSLOG_Utils {
if (packet.indexOf("RFONLY") > 10) { if (packet.indexOf("RFONLY") > 10) {
syslogPacket.concat("RFONLY / "); syslogPacket.concat("RFONLY / ");
syslogPacket.concat(packet); syslogPacket.concat(packet);
} else if (packet.indexOf("::") > 10) { } else if (nextChar == ':') {
syslogPacket.concat("MESSAGE / "); syslogPacket.concat("MESSAGE / ");
syslogPacket.concat(packet.substring(0,packet.indexOf(">"))); syslogPacket.concat(sender);
syslogPacket.concat(" ---> "); syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(packet.indexOf("::") + 2)); syslogPacket.concat(packet.substring(colonIndex + 2));
} else { } else {
syslogPacket.concat(packet); syslogPacket.concat(packet);
} }

View File

@@ -5,6 +5,7 @@
#include "station_utils.h" #include "station_utils.h"
#include "utils.h" #include "utils.h"
extern Configuration Config; extern Configuration Config;
#define MAX_CLIENTS 4 #define MAX_CLIENTS 4
@@ -44,16 +45,9 @@ namespace TNC_Utils {
} }
void handleInputData(char character, int bufferIndex) { void handleInputData(char character, int bufferIndex) {
String* data; String* data = (bufferIndex == -1) ? &inputSerialBuffer : &inputServerBuffer[bufferIndex];
if (bufferIndex == -1) { if (data->length() == 0 && character != (char)FEND) return;
data = &inputSerialBuffer;
} else {
data = &inputServerBuffer[bufferIndex];
}
if (data->length() == 0 && character != (char)FEND) {
return;
}
data->concat(character); data->concat(character);
if (character == (char)FEND && data->length() > 3) { if (character == (char)FEND && data->length() > 3) {

View File

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

@@ -5,6 +5,7 @@
#include "display.h" #include "display.h"
#include "utils.h" #include "utils.h"
extern Configuration Config; extern Configuration Config;
extern uint32_t lastBeaconTx; extern uint32_t lastBeaconTx;
extern std::vector<ReceivedPacket> receivedPackets; extern std::vector<ReceivedPacket> receivedPackets;
@@ -206,7 +207,7 @@ namespace WEB_Utils {
Config.personalNote = request->getParam("personalNote", true)->value(); Config.personalNote = request->getParam("personalNote", true)->value();
Config.blackList = request->getParam("blackList", true)->value(); Config.blacklist = request->getParam("blacklist", true)->value();
Config.webadmin.active = request->hasParam("webadmin.active", true); Config.webadmin.active = request->hasParam("webadmin.active", true);
if (Config.webadmin.active) { if (Config.webadmin.active) {
@@ -216,6 +217,9 @@ namespace WEB_Utils {
Config.ntp.gmtCorrection = request->getParam("ntp.gmtCorrection", true)->value().toFloat(); Config.ntp.gmtCorrection = request->getParam("ntp.gmtCorrection", true)->value().toFloat();
Config.remoteManagement.managers = request->getParam("remoteManagement.managers", true)->value();
Config.remoteManagement.rfOnly = request->getParam("remoteManagement.rfOnly", true);
Config.writeFile(); Config.writeFile();
AsyncWebServerResponse *response = request->beginResponse(302, "text/html", ""); AsyncWebServerResponse *response = request->beginResponse(302, "text/html", "");

View File

@@ -5,6 +5,7 @@
#include "display.h" #include "display.h"
#include "utils.h" #include "utils.h"
extern Configuration Config; extern Configuration Config;
extern uint8_t myWiFiAPIndex; extern uint8_t myWiFiAPIndex;

View File

@@ -1,4 +1,6 @@
#include <TinyGPS++.h>
#include "configuration.h" #include "configuration.h"
#include "board_pinout.h"
#include "wx_utils.h" #include "wx_utils.h"
#include "display.h" #include "display.h"
@@ -8,6 +10,9 @@
extern Configuration Config; extern Configuration Config;
extern String fifthLine; extern String fifthLine;
#ifdef HAS_GPS
extern TinyGPSPlus gps;
#endif
int wxModuleType = 0; int wxModuleType = 0;
uint8_t wxModuleAddress = 0x00; uint8_t wxModuleAddress = 0x00;
@@ -16,7 +21,7 @@ float newHum, newTemp, newPress, newGas;
Adafruit_BME280 bme280; Adafruit_BME280 bme280;
#ifdef HELTEC_V3 #if defined(HELTEC_V3) || defined(HELTEC_V3_2)
Adafruit_BMP280 bmp280(&Wire1); Adafruit_BMP280 bmp280(&Wire1);
Adafruit_Si7021 sensor = Adafruit_Si7021(); Adafruit_Si7021 sensor = Adafruit_Si7021();
#else #else
@@ -26,13 +31,12 @@ Adafruit_Si7021 sensor = Adafruit_Si7021();
#endif #endif
namespace WX_Utils { namespace WX_Utils {
void getWxModuleAddres() { void getWxModuleAddres() {
uint8_t err, addr; uint8_t err, addr;
for(addr = 1; addr < 0x7F; addr++) { for(addr = 1; addr < 0x7F; addr++) {
#if defined(HELTEC_V3) || defined(HELTEC_WSL_V3) || defined(HELTEC_WSL_V3_DISPLAY) #if defined(HELTEC_V3) || defined(HELTEC_V3_2) || defined(HELTEC_WSL_V3) || defined(HELTEC_WSL_V3_DISPLAY)
Wire1.beginTransmission(addr); Wire1.beginTransmission(addr);
err = Wire1.endTransmission(); err = Wire1.endTransmission();
#else #else
@@ -58,7 +62,7 @@ namespace WX_Utils {
if (wxModuleAddress != 0x00) { if (wxModuleAddress != 0x00) {
bool wxModuleFound = false; bool wxModuleFound = false;
if (wxModuleAddress == 0x76 || wxModuleAddress == 0x77) { if (wxModuleAddress == 0x76 || wxModuleAddress == 0x77) {
#if defined(HELTEC_V3) || defined(HELTEC_WSL_V3) || defined(HELTEC_WSL_V3_DISPLAY) #if defined(HELTEC_V3) || defined(HELTEC_V3_2) || defined(HELTEC_WSL_V3) || defined(HELTEC_WSL_V3_DISPLAY)
if (bme280.begin(wxModuleAddress, &Wire1)) { if (bme280.begin(wxModuleAddress, &Wire1)) {
Serial.println("BME280 sensor found"); Serial.println("BME280 sensor found");
wxModuleType = 1; wxModuleType = 1;
@@ -115,7 +119,7 @@ namespace WX_Utils {
Serial.println("BMP280 Module init done!"); Serial.println("BMP280 Module init done!");
break; break;
case 3: case 3:
#ifndef HELTEC_V3 #if !defined(HELTEC_V3) && !defined(HELTEC_V3_2)
bme680.setTemperatureOversampling(BME680_OS_1X); bme680.setTemperatureOversampling(BME680_OS_1X);
bme680.setHumidityOversampling(BME680_OS_1X); bme680.setHumidityOversampling(BME680_OS_1X);
bme680.setPressureOversampling(BME680_OS_1X); bme680.setPressureOversampling(BME680_OS_1X);
@@ -195,7 +199,7 @@ namespace WX_Utils {
newHum = 0; newHum = 0;
break; break;
case 3: // BME680 case 3: // BME680
#ifndef HELTEC_V3 #if !defined(HELTEC_V3) && !defined(HELTEC_V3_2)
bme680.performReading(); bme680.performReading();
delay(50); delay(50);
if (bme680.endReading()) { if (bme680.endReading()) {
@@ -227,13 +231,14 @@ namespace WX_Utils {
humStr = ".."; humStr = "..";
} }
String presStr; String presStr = (wxModuleAddress == 4)
if (wxModuleAddress == 4) { ? "....."
presStr = "....."; #ifdef HAS_GPS
} else { : generatePresString(newPress + (gps.altitude.meters() / CORRECTION_FACTOR));
presStr = generatePresString(newPress + (Config.wxsensor.heightCorrection/CORRECTION_FACTOR)); #else
} : generatePresString(newPress + (Config.wxsensor.heightCorrection / CORRECTION_FACTOR));
#endif
fifthLine = "BME-> "; fifthLine = "BME-> ";
fifthLine += String(int(newTemp + Config.wxsensor.temperatureCorrection)); fifthLine += String(int(newTemp + Config.wxsensor.temperatureCorrection));
fifthLine += "C "; fifthLine += "C ";

View File

@@ -0,0 +1,34 @@
#ifndef BOARD_PINOUT_H_
#define BOARD_PINOUT_H_
// LoRa Radio
#define HAS_SX1262
#define RADIO_SCLK_PIN 9
#define RADIO_MISO_PIN 11
#define RADIO_MOSI_PIN 10
#define RADIO_CS_PIN 8
#define RADIO_RST_PIN 12
#define RADIO_DIO1_PIN 14
#define RADIO_BUSY_PIN 13
// Display
#define HAS_DISPLAY
#undef OLED_SDA
#undef OLED_SCL
#undef OLED_RST
#define OLED_SDA 17
#define OLED_SCL 18
#define OLED_RST 21
#define OLED_DISPLAY_HAS_RST_PIN
// Aditional Config
#define INTERNAL_LED_PIN 35
#define BATTERY_PIN 1
#define VEXT_CTRL 36
#define ADC_CTRL 37
#define BOARD_I2C_SDA 41
#define BOARD_I2C_SCL 42
#endif

View File

@@ -0,0 +1,9 @@
[env:heltec_wifi_lora_32_V3_2]
board = heltec_wifi_lora_32_V3
board_build.mcu = esp32s3
build_flags =
${common.build_flags}
-D HELTEC_V3_2
lib_deps =
${common.lib_deps}
${common.display_libs}

View File

@@ -4,5 +4,7 @@ board_build.mcu = esp32s3
build_flags = build_flags =
${common.build_flags} ${common.build_flags}
-D HELTEC_WP -D HELTEC_WP
-D WIRELESS_PAPER
lib_deps = lib_deps =
${common.lib_deps} ${common.lib_deps}
todd-herbert/heltec-eink-modules@^4.4.0

View File

@@ -18,9 +18,9 @@
#undef OLED_SCL #undef OLED_SCL
#undef OLED_RST #undef OLED_RST
#define OLED_SDA 4 #define OLED_SDA 17
#define OLED_SCL 15 #define OLED_SCL 18
#define OLED_RST 16 #define OLED_RST 21
#define OLED_DISPLAY_HAS_RST_PIN #define OLED_DISPLAY_HAS_RST_PIN
// Aditional Config // Aditional Config

View File

@@ -0,0 +1,37 @@
#ifndef BOARD_PINOUT_H_
#define BOARD_PINOUT_H_
// LoRa Radio
#define HAS_SX1262
#define RADIO_SCLK_PIN 12
#define RADIO_MISO_PIN 13
#define RADIO_MOSI_PIN 11
#define RADIO_CS_PIN 10
#define RADIO_DIO0_PIN -1
#define RADIO_RST_PIN 5
#define RADIO_DIO1_PIN 1
#define RADIO_BUSY_PIN 4
// Display
#define HAS_DISPLAY
#undef OLED_SDA
#undef OLED_SCL
#undef OLED_RST
#define OLED_SDA 17
#define OLED_SCL 18
#define OLED_RST 16
#define OLED_DISPLAY_HAS_RST_PIN
// Aditional Config
#define HAS_AXP2101
// GPS
#define HAS_GPS
#define GPS_RX 8
#define GPS_TX 9
#define BOARD_HAS_PSRAM
#endif

View File

@@ -0,0 +1,12 @@
[env:ttgo_t_beam_s3_SUPREME_v3]
board = esp32-s3-devkitc-1
board_build.mcu = esp32s3
build_flags =
${common.build_flags}
${common.usb_flags}
-D TTGO_T_Beam_S3_SUPREME_V3
lib_deps =
${common.lib_deps}
${common.display_libs}
lewisxhe/XPowersLib @ 0.2.4
adafruit/Adafruit SH110X @ 2.1.10

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