Compare commits

..

1 Commits

Author SHA1 Message Date
richonguzman
ee25ec6873 checkItOut 2025-02-28 14:20:49 -03:00
82 changed files with 614 additions and 1135 deletions

View File

@@ -57,8 +57,6 @@ jobs:
chip: esp32s3
- name: ttgo_t_deck_GPS
chip: esp32s3
- name: ttgo_t_beam_s3_SUPREME_v3
chip: esp32s3
- name: ESP32_DIY_LoRa_A7670
chip: esp32
- name: ESP32_DIY_LoRa_A7670_915

21
LICENSE Normal file
View File

@@ -0,0 +1,21 @@
MIT License
Copyright (c) 2023 Ricardo Guzman (Richonguzman)
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.

View File

@@ -54,11 +54,7 @@ ____________________________________________________
## Timeline (Versions):
- 2025-04-20000000
- 2025.03.20 Manager List added to enable/disable DigiEcoMode and Tx Control. Thanks LB5JJ.
- 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.02.25 Objects Rules updated and GPS Boards: Satellites in Screen, Wx Height Correction from GPS Data.
- 2025.01.22 Added LILYGO T-DECK PLUS (and DIY+GPS version) board support.
- 2025.01.11 Added HELTEC V3.2 board support.
- 2025.01.07 TROY_LoRa_APRS board added. GMT in quarter hour fix and Beacon fix for TNC.
@@ -70,7 +66,7 @@ ____________________________________________________
- 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.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 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 and all was 150mA). APRS Message/Queries can start/stop this mode too.
- 2024.10.06 Cross Frequency Digipeater Rules added.
- 2024.09.23 Libraries Update for SDK3
- 2024.09.23 Added Enconded Telemetry for Battery (+ External Voltage) in Station GPS Beacon Packet.

View File

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

View File

@@ -29,7 +29,7 @@
},
"digi": {
"mode": 0,
"ecoMode": 0
"ecoMode": false
},
"lora": {
"txFreq": 433775000,
@@ -84,16 +84,14 @@
"ntp": {
"gmtCorrection": 0.0
},
"remoteManagement": {
"managers": "",
"rfOnly": true
},
"other": {
"rememberStationTime": 30,
"lowPowerMode": false,
"lowVoltageCutOff": 0,
"backupDigiMode": false,
"rebootMode": false,
"rebootModeTime": 6
},
"personalNote": "",
"blacklist": ""
"blackList": ""
}

View File

@@ -590,20 +590,20 @@
</svg>
Black List
</h5>
<small>Add Callsigns with space between them to Blacklist them (* wild card allowed)</small>
<small>Add Callsigns with space between them to Black List them (* wild card allowed)</small>
</div>
<div class="col-9 mt-2">
<div class="row">
<div class="col-12">
<label
for="blacklist"
for="blackList"
class="form-label"
>Blacklist</label
>Black List</label
>
<input
type="text"
name="blacklist"
id="blacklist"
name="blackList"
id="blackList"
class="form-control"
placeholder="Station Callsign"
oninput="this.value = this.value.toUpperCase();"
@@ -646,9 +646,7 @@
name="digi.mode"
id="digi.mode"
>
<option value="0">
OFF
</option>
<option value="0">off</option>
<option value="2">
WIDE1 (fill-in) Digi
</option>
@@ -657,27 +655,20 @@
</option>
</select>
</div>
<div class="col-12 mt-3">
<label
for="digi.ecoMode"
class="form-label"
>Eco Mode</label
>
<select
class="form-select form-select"
name="digi.ecoMode"
id="digi.ecoMode"
>
<option value="0">
OFF (Normal Mode - WiFiAP enabled)
</option>
<option value="1">
Ultra Eco Mode (Sleep till Packet Rx (WiFiAP/WebUI & Display disabled))
</option>
<option value="2">
OFF (Normal Mode - WiFiAP disabled)
</option>
</select>
<div class="col-12 mt-5">
<div class="form-check form-switch">
<input
type="checkbox"
name="digi.ecoMode"
id="digi.ecoMode"
class="form-check-input"
/>
<label
for="digi.ecoMode"
class="form-label"
>Eco Mode<small> This will disable WiFi, Display, Leds and lower CPU Speed for Low Power Digipeater. (<strong>Caution:</strong> Active means No WebUI Configuration, so <strong>ONLY</strong> activate this for Remote Digipeater)</small></label
>
</div>
</div>
</div>
</div>
@@ -1717,65 +1708,6 @@
</div>
<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 (ex: AB1CDE-9, AB1CDE*)</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="col-lg-3 col-sm-12">
<h5>
@@ -1867,6 +1799,46 @@
>
</div>
</div>
<div class="col-12">
<div class="form-check form-switch">
<div class="form-text">
WiFi disabled. Sleep mode. Best for solar Digi with SX126X.
</div>
<input
type="checkbox"
name="other.lowPowerMode"
id="other.lowPowerMode"
class="form-check-input"
/>
<label
for="other.lowPowerMode"
class="form-label"
>Low power mode (only for HT-CT62)</label
>
</div>
</div>
<div class="col-12 mt-3">
<label
for="other.lowVoltageCutOff"
class="form-label"
>Low voltage cut off <small>(Deep sleep below specific voltage)</small></label
>
<input
type="text"
name="other.lowVoltageCutOff"
id="other.lowVoltageCutOff"
placeholder="0"
min="0"
step="0.01"
class="form-control"
/>
<span class="input-group-text"
>Volts</span
>
<div class="form-text">
MCU will deep sleep when below provided battery voltage to save power. Set to <strong>0</strong> if you don't want this option. <u>Please calibrate your voltage reading first!</u>
</div>
</div>
</div>
</div>
</div>

View File

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

Binary file not shown.

Before

Width:  |  Height:  |  Size: 98 KiB

View File

@@ -8,10 +8,10 @@ namespace APRS_IS_Utils {
void upload(const String& line);
void connect();
void checkStatus();
String checkForStartingBytes(const String& packet);
String buildPacketToUpload(const String& packet);
bool processReceivedLoRaMessage(const String& sender, const String& packet, bool thirdParty);
void processLoRaPacket(const String& packet);

View File

@@ -8,10 +8,10 @@ namespace BATTERY_Utils {
void adcCalibration();
void adcCalibrationCheck();
void setup();
float checkInternalVoltage();
float checkExternalVoltage();
void checkIfShouldSleep(); // ????
void startupBatteryHealth();
String generateEncodedTelemetryBytes(float value, bool firstBytes, byte voltageType);

View File

@@ -47,7 +47,7 @@ public:
class DIGI {
public:
int mode;
int ecoMode; // 0 = Not Active | 1 = Ultra EcoMode | 2 = Not Active (WiFi OFF, Serial ON)
bool ecoMode;
};
class LoraModule {
@@ -122,21 +122,18 @@ public:
float gmtCorrection;
};
class REMOTE_MANAGEMENT {
public:
String managers;
bool rfOnly;
};
class Configuration {
public:
String callsign;
int rememberStationTime;
bool lowPowerMode;
double lowVoltageCutOff;
bool backupDigiMode;
bool rebootMode;
int rebootModeTime;
String personalNote;
String blacklist;
String blackList;
std::vector<WiFi_AP> wifiAPs;
WiFi_Auto_AP wifiAutoAP;
BEACON beacon;
@@ -150,9 +147,8 @@ public:
TNC tnc;
OTA ota;
WEBADMIN webadmin;
NTP ntp;
REMOTE_MANAGEMENT remoteManagement;
NTP ntp;
void init();
void writeFile();
Configuration();

View File

@@ -8,11 +8,11 @@ namespace LoRa_Utils {
void setup();
void sendNewPacket(const String& newPacket);
String receivePacketFromSleep();
//String packetSanitization(const String& packet);
String receivePacket();
void changeFreqTx();
void changeFreqRx();
void wakeRadio();
void startReceive();
void sleepRadio();
}

View File

@@ -1,15 +0,0 @@
#ifndef SLEEP_UTILS_H_
#define SLEEP_UTILS_H_
#include <Arduino.h>
namespace SLEEP_Utils {
void setup();
void checkWakeUpFlag();
void startSleeping();
void checkSerial();
}
#endif

View File

@@ -18,16 +18,14 @@ struct LastHeardStation {
namespace STATION_Utils {
void loadBlacklistAndManagers();
bool isBlacklisted(const String& callsign);
bool isManager(const String& callsign);
void loadBlackList();
bool checkBlackList(const String& callsign);
bool checkObjectTime(const String& packet);
void deleteNotHeard();
void updateLastHeard(const String& station);
bool wasHeard(const String& station);
void clean25SegBuffer();
bool check25SegBuffer(const String& station, const String& textMessage);
void processOutputPacketBufferUltraEcoMode();
void processOutputPacketBuffer();
void addToOutputPacketBuffer(const String& packet);

View File

@@ -8,7 +8,7 @@ namespace TNC_Utils {
void setup();
void loop();
void sendToClients(const String& packet);
void sendToSerial(const String& packet);

View File

@@ -11,7 +11,7 @@ namespace WIFI_Utils {
void startWiFi();
void checkAutoAPTimeout();
void setup();
}
#endif

View File

@@ -13,10 +13,10 @@ default_envs = ttgo-lora32-v21
extra_configs =
common_settings.ini
variants/*/platformio.ini
variants/*/platformio.ini
[env]
platform = espressif32 @ 6.7.0
platform = espressif32 @ 6.10.0
board_build.partitions = min_spiffs.csv
framework = arduino
monitor_speed = 115200

View File

@@ -6,7 +6,6 @@
#include "display.h"
#include "utils.h"
#ifdef HAS_A7670
#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
@@ -129,7 +128,7 @@
delayATMessage = 0;
} else if (ATMessage.indexOf(Config.callsign) >= 3 && !modemLoggedToAPRSIS && response.indexOf("OK") >= 0 && !stationBeacon) { // login info
validAT = true;
delayATMessage = 0;
delayATMessage = 0;
} else if (ATMessage.indexOf(Config.callsign) == 0 && !beaconSended && response.indexOf("OK") >= 0 && !stationBeacon) { // self beacon or querys
validAT = true;
i = 1;
@@ -203,5 +202,4 @@
delay(1);
}
}
#endif

View File

@@ -26,13 +26,14 @@ ___________________________________________________________________*/
#include <WiFi.h>
#include <vector>
#include "configuration.h"
#include "battery_utils.h"
#include "aprs_is_utils.h"
#include "station_utils.h"
#include "battery_utils.h"
#include "board_pinout.h"
#include "syslog_utils.h"
#include "query_utils.h"
#include "power_utils.h"
#include "sleep_utils.h"
#include "lora_utils.h"
#include "wifi_utils.h"
#include "digi_utils.h"
@@ -47,8 +48,7 @@ ___________________________________________________________________*/
#include "A7670_utils.h"
#endif
String versionDate = "2025-06-20";
String versionDate = "2025.02.28";
Configuration Config;
WiFiClient espClient;
#ifdef HAS_GPS
@@ -68,16 +68,11 @@ uint32_t lastBatteryCheck = 0;
bool backUpDigiMode = false;
bool modemLoggedToAPRSIS = false;
#ifdef HAS_EPAPER
uint32_t lastEpaperTime = 0;
extern String lastEpaperText;
#endif
std::vector<ReceivedPacket> receivedPackets;
String firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine;
//#define STARTUP_DELAY 5 //min
//#define STARTUP_DELAY 5 //min
void setup() {
Serial.begin(115200);
@@ -86,14 +81,54 @@ void setup() {
LoRa_Utils::setup();
Utils::validateFreqs();
GPS_Utils::setup();
STATION_Utils::loadBlacklistAndManagers();
STATION_Utils::loadBlackList();
#ifdef STARTUP_DELAY // (TEST) just to wait for WiFi init of Routers
displayShow("", " STARTUP DELAY ...", "", "", 0);
delay(STARTUP_DELAY * 60 * 1000);
#endif
SLEEP_Utils::setup();
#ifdef HELTEC_HTCT62
if (Config.lowPowerMode) {
gpio_wakeup_enable(GPIO_NUM_3, GPIO_INTR_HIGH_LEVEL);
esp_deep_sleep_enable_gpio_wakeup(GPIO_NUM_3, ESP_GPIO_WAKEUP_GPIO_HIGH);
long lastBeacon = 0;
LoRa_Utils::startReceive();
while (true) {
auto wakeup_reason = esp_sleep_get_wakeup_cause();
if (wakeup_reason == 7) { // packet received
Serial.println("Received packet");
String packet = LoRa_Utils::receivePacket();
Serial.println(packet);
if (Config.digi.mode == 2) DIGI_Utils::processLoRaPacket(packet);
if (packet.indexOf(Config.callsign + ":?APRSELP{") != -1) { // Send `?APRSELP` to exit low power
Serial.println("Got ?APRSELP message, exiting from low power mode");
break;
};
}
long time = esp_timer_get_time() / 1000000;
if (lastBeacon == 0 || time - lastBeacon >= Config.beacon.interval * 60) {
Serial.println("Sending beacon");
String comment = Config.beacon.comment;
if (Config.battery.sendInternalVoltage) comment += " Batt=" + String(BATTERY_Utils::checkInternalVoltage(),2) + "V";
if (Config.battery.sendExternalVoltage) comment += " Ext=" + String(BATTERY_Utils::checkExternalVoltage(),2) + "V";
LoRa_Utils::sendNewPacket(GPS_Utils::getiGateLoRaBeaconPacket() + comment);
lastBeacon = time;
}
LoRa_Utils::startReceive();
Serial.println("Sleeping");
long sleep = (Config.beacon.interval * 60) - (time - lastBeacon);
Serial.flush();
esp_sleep_enable_timer_wakeup(sleep * 1000000);
esp_light_sleep_start();
Serial.println("Waked up");
}
Config.loramodule.rxActive = false;
}
#endif
DIGI_Utils::checkEcoMode();
WIFI_Utils::setup();
NTP_Utils::setup();
SYSLOG_Utils::setup();
@@ -105,109 +140,86 @@ void setup() {
#endif
Utils::checkRebootMode();
APRS_IS_Utils::firstConnection();
SLEEP_Utils::checkSerial();
}
void loop() {
if (Config.digi.ecoMode == 1) {
SLEEP_Utils::checkWakeUpFlag();
Utils::checkBeaconInterval();
STATION_Utils::processOutputPacketBufferUltraEcoMode();
Utils::checkSleepByLowBatteryVoltage(1);
SLEEP_Utils::startSleeping();
} else {
WIFI_Utils::checkAutoAPTimeout();
WIFI_Utils::checkAutoAPTimeout();
if (isUpdatingOTA) {
ElegantOTA.loop();
return; // Don't process IGate and Digi during OTA update
}
#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();
}
if (isUpdatingOTA) {
ElegantOTA.loop();
return; // Don't process IGate and Digi during OTA update
}
if (Config.lowVoltageCutOff > 0) {
BATTERY_Utils::checkIfShouldSleep();
}
#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
} else {
thirdLine = Utils::getLocalIP();
#endif
#ifdef HAS_A7670
if (Config.aprs_is.active && !modemLoggedToAPRSIS) A7670_Utils::APRS_IS_connect();
#else
WIFI_Utils::checkWiFi();
if (Config.aprs_is.active && (WiFi.status() == WL_CONNECTED) && !espClient.connected()) APRS_IS_Utils::connect();
#endif
NTP_Utils::update();
TNC_Utils::loop();
Utils::checkDisplayInterval();
Utils::checkBeaconInterval();
APRS_IS_Utils::checkStatus(); // Need that to update display, maybe split this and send APRSIS status to display func?
String packet = "";
if (Config.loramodule.rxActive) {
packet = LoRa_Utils::receivePacket(); // We need to fetch LoRa packet above APRSIS and Digi
}
#else
thirdLine = Utils::getLocalIP();
#endif
if (packet != "") {
if (Config.aprs_is.active) { // If APRSIS enabled
APRS_IS_Utils::processLoRaPacket(packet); // Send received packet to APRSIS
}
#ifdef HAS_A7670
if (Config.aprs_is.active && !modemLoggedToAPRSIS) A7670_Utils::APRS_IS_connect();
#else
WIFI_Utils::checkWiFi();
if (Config.aprs_is.active && (WiFi.status() == WL_CONNECTED) && !espClient.connected()) APRS_IS_Utils::connect();
#endif
if (Config.loramodule.txActive && (Config.digi.mode == 2 || Config.digi.mode == 3 || backUpDigiMode)) { // If Digi enabled
STATION_Utils::clean25SegBuffer();
DIGI_Utils::processLoRaPacket(packet); // Send received packet to Digi
}
NTP_Utils::update();
TNC_Utils::loop();
if (Config.tnc.enableServer) { // If TNC server enabled
TNC_Utils::sendToClients(packet); // Send received packet to TNC KISS
}
if (Config.tnc.enableSerial) { // If Serial KISS enabled
TNC_Utils::sendToSerial(packet); // Send received packet to Serial KISS
}
}
Utils::checkDisplayInterval();
Utils::checkBeaconInterval();
APRS_IS_Utils::checkStatus(); // Need that to update display, maybe split this and send APRSIS status to display func?
if (Config.aprs_is.active) {
APRS_IS_Utils::listenAPRSIS(); // listen received packet from APRSIS
}
STATION_Utils::processOutputPacketBuffer();
#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::checkSleepByLowBatteryVoltage(1);
String packet = "";
if (Config.loramodule.rxActive) {
packet = LoRa_Utils::receivePacket(); // We need to fetch LoRa packet above APRSIS and Digi
}
}
// ESP32 (and ESPS3) work?
if (packet != "") {
if (Config.aprs_is.active) { // If APRSIS enabled
APRS_IS_Utils::processLoRaPacket(packet); // Send received packet to APRSIS
}
// ESP32C3 :
// - HT-CT62 sleeps??
// - and others?
if (Config.loramodule.txActive && (Config.digi.mode == 2 || Config.digi.mode == 3 || backUpDigiMode)) { // If Digi enabled
STATION_Utils::clean25SegBuffer();
DIGI_Utils::processLoRaPacket(packet); // Send received packet to Digi
}
if (Config.tnc.enableServer) { // If TNC server enabled
TNC_Utils::sendToClients(packet); // Send received packet to TNC KISS
}
if (Config.tnc.enableSerial) { // If Serial KISS enabled
TNC_Utils::sendToSerial(packet); // Send received packet to Serial KISS
}
}
if (Config.aprs_is.active) {
APRS_IS_Utils::listenAPRSIS(); // listen received packet from APRSIS
}
STATION_Utils::processOutputPacketBuffer();
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
Utils::checkRebootTime();
Utils::checkSleepByLowBatteryVoltage(1);
}

View File

@@ -2,7 +2,6 @@
#include "configuration.h"
#include "aprs_is_utils.h"
#include "station_utils.h"
#include "board_pinout.h"
#include "syslog_utils.h"
#include "query_utils.h"
#include "A7670_utils.h"
@@ -10,7 +9,6 @@
#include "display.h"
#include "utils.h"
extern Configuration Config;
extern WiFiClient espClient;
extern uint32_t lastScreenOn;
@@ -28,7 +26,7 @@ uint32_t lastRxTime = millis();
bool passcodeValid = false;
#ifdef HAS_A7670
extern bool stationBeacon;
extern bool stationBeacon;
#endif
@@ -60,7 +58,7 @@ namespace APRS_IS_Utils {
aprsAuth += Config.callsign;
aprsAuth += " pass ";
aprsAuth += Config.aprs_is.passcode;
aprsAuth += " vers CA2RXU_iGate 3.0 filter ";
aprsAuth += " vers CA2RXU_LoRa_iGate 2.0 filter ";
aprsAuth += Config.aprs_is.filter;
upload(aprsAuth);
}
@@ -71,11 +69,11 @@ namespace APRS_IS_Utils {
if (WiFi.status() == WL_CONNECTED) {
wifiState = "OK";
} else {
if (backUpDigiMode || Config.digi.ecoMode == 1 || Config.digi.ecoMode == 2) {
if (backUpDigiMode || Config.digi.ecoMode) {
wifiState = "--";
} else {
wifiState = "AP";
}
}
if (!Config.display.alwaysOn && Config.display.timeout != 0) {
displayToggle(true);
}
@@ -136,7 +134,7 @@ namespace APRS_IS_Utils {
ackMessage.concat(packet.substring(packet.indexOf("{") + 1));
ackMessage.trim();
//Serial.println(ackMessage);
String addToBuffer = Config.callsign;
addToBuffer += ">APLRG1";
if (!thirdParty) addToBuffer += ",RFONLY";
@@ -175,35 +173,37 @@ namespace APRS_IS_Utils {
void processLoRaPacket(const String& packet) {
if (passcodeValid && (espClient.connected() || modemLoggedToAPRSIS)) {
if (packet.indexOf("NOGATE") == -1 && packet.indexOf("RFONLY") == -1) {
int firstColonIndex = packet.indexOf(":");
if (firstColonIndex > 5 && firstColonIndex < (packet.length() - 1) && packet[firstColonIndex + 1] != '}' && packet.indexOf("TCPIP") == -1) {
const String& Sender = packet.substring(3, packet.indexOf(">"));
if (Sender != Config.callsign && Utils::checkValidCallsign(Sender)) {
STATION_Utils::updateLastHeard(Sender);
Utils::typeOfPacket(packet.substring(3), 0); // LoRa-APRS
const String& AddresseeAndMessage = packet.substring(packet.indexOf("::") + 2);
String Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":"));
Addressee.trim();
bool queryMessage = false;
if (packet.indexOf("::") > 10 && Addressee == Config.callsign) { // its a message for me!
queryMessage = processReceivedLoRaMessage(Sender, checkForStartingBytes(AddresseeAndMessage), false);
}
if (!queryMessage) {
const String& aprsPacket = buildPacketToUpload(packet);
if (!Config.display.alwaysOn && Config.display.timeout != 0) {
displayToggle(true);
if (packet != "") {
if ((packet.substring(0, 3) == "\x3c\xff\x01") && (packet.indexOf("NOGATE") == -1) && (packet.indexOf("RFONLY") == -1)) {
int firstColonIndex = packet.indexOf(":");
if (firstColonIndex > 5 && firstColonIndex < (packet.length() - 1) && packet[firstColonIndex + 1] != '}' && packet.indexOf("TCPIP") == -1) {
const String& Sender = packet.substring(3, packet.indexOf(">"));
if (Sender != Config.callsign && Utils::checkValidCallsign(Sender) && !STATION_Utils::checkBlackList(Sender)) {
STATION_Utils::updateLastHeard(Sender);
Utils::typeOfPacket(packet.substring(3), 0); // LoRa-APRS
const String& AddresseeAndMessage = packet.substring(packet.indexOf("::") + 2);
String Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":"));
Addressee.trim();
bool queryMessage = false;
if (packet.indexOf("::") > 10 && Addressee == Config.callsign) { // its a message for me!
queryMessage = processReceivedLoRaMessage(Sender, checkForStartingBytes(AddresseeAndMessage), false);
}
if (!queryMessage) {
const String& aprsPacket = buildPacketToUpload(packet);
if (!Config.display.alwaysOn && Config.display.timeout != 0) {
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);
}
}
}
@@ -299,7 +299,6 @@ namespace APRS_IS_Utils {
}
if (receivedMessage.indexOf("?") == 0) {
Utils::println("Rx Query (APRS-IS) : " + packet);
Sender.trim();
String queryAnswer = QUERY_Utils::process(receivedMessage, Sender, true, false);
//Serial.println("---> QUERY Answer : " + queryAnswer.substring(0,queryAnswer.indexOf("\n")));
if (!Config.display.alwaysOn && Config.display.timeout != 0) {
@@ -323,7 +322,6 @@ namespace APRS_IS_Utils {
seventhLine = "QUERY = ";
seventhLine += receivedMessage;
}
displayShow(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
} else {
Utils::print("Rx Message (APRS-IS): " + packet);
if (STATION_Utils::wasHeard(Addressee) && packet.indexOf("EQNS.") == -1 && packet.indexOf("UNIT.") == -1 && packet.indexOf("PARM.") == -1) {
@@ -331,9 +329,9 @@ namespace APRS_IS_Utils {
displayToggle(true);
lastScreenOn = millis();
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) {
Utils::print("Rx Object (APRS-IS) : " + packet);
if (STATION_Utils::checkObjectTime(packet)) {

View File

@@ -5,7 +5,6 @@
#include "power_utils.h"
#include "utils.h"
extern Configuration Config;
extern uint32_t lastBatteryCheck;
@@ -157,12 +156,7 @@ namespace BATTERY_Utils {
return (2 * (sampleSum/100) * adcReadingTransformation) + voltageDividerCorrection; // raw voltage without mapping
}
#else
#ifdef LIGHTGATEWAY_PLUS_1_0
double inputDivider = (1.0 / (560.0 + 100.0)) * 100.0; // The voltage divider is a 560k + 100k resistor in series, 100k on the low side.
return (((sampleSum/100) * adcReadingTransformation) / inputDivider) + 0.41;
#else
return (2 * (sampleSum/100) * adcReadingTransformation) + voltageDividerCorrection; // raw voltage without mapping
#endif
return (2 * (sampleSum/100) * adcReadingTransformation) + voltageDividerCorrection; // raw voltage without mapping
#endif
#endif
// return mapVoltage(voltage, 3.34, 4.71, 3.0, 4.2); // mapped voltage
@@ -203,6 +197,15 @@ namespace BATTERY_Utils {
// return mapVoltage(voltage, 5.05, 6.32, 4.5, 5.5); // mapped voltage
}
void checkIfShouldSleep() {
if (lastBatteryCheck == 0 || millis() - lastBatteryCheck >= 15 * 60 * 1000) {
lastBatteryCheck = millis();
if (checkInternalVoltage() < Config.lowVoltageCutOff) {
ESP.deepSleep(1800000000); // 30 min sleep (60s = 60e6)
}
}
}
void startupBatteryHealth() {
#ifdef BATTERY_PIN
if (Config.battery.monitorInternalVoltage && checkInternalVoltage() < Config.battery.internalSleepVoltage + 0.1) {
@@ -251,7 +254,9 @@ namespace BATTERY_Utils {
String telemetry = "|";
telemetry += generateEncodedTelemetryBytes(telemetryCounter, true, 0);
telemetryCounter++;
if (telemetryCounter == 1000) telemetryCounter = 0;
if (telemetryCounter == 1000) {
telemetryCounter = 0;
}
if (Config.battery.sendInternalVoltage) telemetry += generateEncodedTelemetryBytes(checkInternalVoltage(), false, 0);
if (Config.battery.sendExternalVoltage) telemetry += generateEncodedTelemetryBytes(checkExternalVoltage(), false, 1);
telemetry += "|";

View File

@@ -4,11 +4,8 @@
#include "display.h"
bool shouldSleepStop = true;
void Configuration::writeFile() {
Serial.println("Saving config...");
Serial.println("Saving config..");
StaticJsonDocument<2560> data;
File configFile = SPIFFS.open("/igate_conf.json", "w");
@@ -97,9 +94,12 @@ void Configuration::writeFile() {
data["other"]["backupDigiMode"] = backupDigiMode;
data["other"]["lowPowerMode"] = lowPowerMode;
data["other"]["lowVoltageCutOff"] = lowVoltageCutOff;
data["personalNote"] = personalNote;
data["blacklist"] = blacklist;
data["blackList"] = blackList;
data["webadmin"]["active"] = webadmin.active;
data["webadmin"]["username"] = webadmin.username;
@@ -107,15 +107,11 @@ void Configuration::writeFile() {
data["ntp"]["gmtCorrection"] = ntp.gmtCorrection;
data["remoteManagement"]["managers"] = remoteManagement.managers;
data["remoteManagement"]["rfOnly"] = remoteManagement.rfOnly;
serializeJson(data, configFile);
configFile.close();
Serial.println("Config saved");
delay(200);
}
bool Configuration::readFile() {
@@ -168,8 +164,7 @@ bool Configuration::readFile() {
aprs_is.objectsToRF = data["aprs_is"]["objectsToRF"] | false;
digi.mode = data["digi"]["mode"] | 0;
digi.ecoMode = data["digi"]["ecoMode"] | 0;
if (digi.ecoMode == 1) shouldSleepStop = false;
digi.ecoMode = data["digi"]["ecoMode"] | false;
loramodule.txFreq = data["lora"]["txFreq"] | 433775000;
loramodule.rxFreq = data["lora"]["rxFreq"] | 433775000;
@@ -218,6 +213,9 @@ bool Configuration::readFile() {
ntp.gmtCorrection = data["ntp"]["gmtCorrection"] | 0.0;
lowPowerMode = data["other"]["lowPowerMode"] | false;
lowVoltageCutOff = data["other"]["lowVoltageCutOff"] | 0;
backupDigiMode = data["other"]["backupDigiMode"] | false;
rebootMode = data["other"]["rebootMode"] | false;
@@ -225,10 +223,7 @@ bool Configuration::readFile() {
personalNote = data["personalNote"] | "personal note here";
blacklist = data["blacklist"] | "station callsign";
remoteManagement.managers = data["remoteManagement"]["managers"] | "";
remoteManagement.rfOnly = data["remoteManagement"]["rfOnly"] | true;
blackList = data["blackList"] | "station callsign";
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;
@@ -273,7 +268,7 @@ void Configuration::init() {
beacon.gpsAmbiguity = false;
digi.mode = 0;
digi.ecoMode = 0;
digi.ecoMode = false;
tnc.enableServer = false;
tnc.enableSerial = false;
@@ -326,6 +321,9 @@ void Configuration::init() {
battery.sendVoltageAsTelemetry = false;
lowPowerMode = false;
lowVoltageCutOff = 0;
backupDigiMode = false;
rebootMode = false;
@@ -333,7 +331,7 @@ void Configuration::init() {
personalNote = "";
blacklist = "";
blackList = "";
webadmin.active = false;
webadmin.username = "admin";
@@ -341,9 +339,6 @@ void Configuration::init() {
ntp.gmtCorrection = 0.0;
remoteManagement.managers = "";
remoteManagement.rfOnly = true;
Serial.println("All is Written!");
}

View File

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

View File

@@ -24,27 +24,19 @@
uint16_t redColor = 0xc8a2;
#else
#ifdef HAS_EPAPER
#include <heltec-eink-modules.h>
#include "Fonts/FreeSansBold9pt7b.h"
EInkDisplay_WirelessPaperV1_1 display;
String lastEpaperText;
//
#else
#include <Adafruit_GFX.h>
#if defined(TTGO_T_Beam_S3_SUPREME_V3)
#include <Adafruit_SH110X.h>
Adafruit_SH1106G display(128, 64, &Wire, OLED_RST);
#include <Adafruit_SSD1306.h>
#ifdef HELTEC_WSL_V3_DISPLAY
Adafruit_SSD1306 display(128, 64, &Wire1, OLED_RST);
#else
#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
Adafruit_SSD1306 display(128, 64, &Wire, OLED_RST);
#endif
#endif
#endif
#endif
extern Configuration Config;
bool displayFound = false;
@@ -71,9 +63,7 @@ void displaySetup() {
#endif
#else
#ifdef HAS_EPAPER
display.landscape();
display.printCenter("LoRa APRS iGate Initialising...");
display.update();
//
#else
#ifdef OLED_DISPLAY_HAS_RST_PIN
pinMode(OLED_RST, OUTPUT);
@@ -82,30 +72,17 @@ void displaySetup() {
digitalWrite(OLED_RST, HIGH);
#endif
#if defined(TTGO_T_Beam_S3_SUPREME_V3)
if (!display.begin(0x3c, false)) {
displayFound = true;
if (Config.display.turn180) display.setRotation(2);
display.clearDisplay();
display.setTextColor(SH110X_WHITE);
display.setTextSize(1);
display.setCursor(0, 0);
display.setContrast(1);
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
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
delay(1000);
@@ -119,14 +96,9 @@ void displayToggle(bool toggle) {
digitalWrite(TFT_BL, HIGH);
#else
#ifdef HAS_EPAPER
display.printCenter("EPAPER Display Disabled by toggle...");
display.update();
// ... to be continued
#else
#if defined(TTGO_T_Beam_S3_SUPREME_V3)
if (displayFound) display.oled_command(SH110X_DISPLAYON);
#else
if (displayFound) display.ssd1306_command(SSD1306_DISPLAYON);
#endif
if (displayFound) display.ssd1306_command(SSD1306_DISPLAYON);
#endif
#endif
} else {
@@ -134,15 +106,9 @@ void displayToggle(bool toggle) {
digitalWrite(TFT_BL, LOW);
#else
#ifdef HAS_EPAPER
display.printCenter("Enabled EPAPER Display...");
display.update();
// ... to be continued
#else
#if defined(TTGO_T_Beam_S3_SUPREME_V3)
if (displayFound) display.oled_command(SH110X_DISPLAYOFF);
#else
if (displayFound) display.ssd1306_command(SSD1306_DISPLAYOFF);
#endif
if (displayFound) display.ssd1306_command(SSD1306_DISPLAYOFF);
#endif
#endif
}
@@ -175,24 +141,11 @@ void displayShow(const String& header, const String& line1, const String& line2,
sprite.pushSprite(0,0);
#else
#ifdef HAS_EPAPER
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();
// ... to be continued
#else
if (displayFound) {
display.clearDisplay();
#if defined(TTGO_T_Beam_S3_SUPREME_V3)
display.setTextColor(SH110X_WHITE);
#else
display.setTextColor(WHITE);
#endif
display.setTextColor(WHITE);
display.setTextSize(1);
display.setCursor(0, 0);
display.println(header);
@@ -200,12 +153,8 @@ void displayShow(const String& header, const String& line1, const String& line2,
display.setCursor(0, 8 + (8 * i));
display.println(*lines[i]);
}
#if defined(TTGO_T_Beam_S3_SUPREME_V3)
display.setContrast(1);
#else
display.ssd1306_command(SSD1306_SETCONTRAST);
display.ssd1306_command(1);
#endif
display.ssd1306_command(SSD1306_SETCONTRAST);
display.ssd1306_command(1);
display.display();
}
#endif
@@ -240,25 +189,11 @@ void displayShow(const String& header, const String& line1, const String& line2,
sprite.pushSprite(0,0);
#else
#ifdef HAS_EPAPER
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();
// ... to be continued
#else
if (displayFound) {
display.clearDisplay();
#if defined(TTGO_T_Beam_S3_SUPREME_V3)
display.setTextColor(SH110X_WHITE);
#else
display.setTextColor(WHITE);
#endif
display.setTextColor(WHITE);
display.setTextSize(2);
display.setCursor(0, 0);
display.println(header);
@@ -267,12 +202,8 @@ void displayShow(const String& header, const String& line1, const String& line2,
display.setCursor(0, 16 + (8 * i));
display.println(*lines[i]);
}
#if defined(TTGO_T_Beam_S3_SUPREME_V3)
display.setContrast(1);
#else
display.ssd1306_command(SSD1306_SETCONTRAST);
display.ssd1306_command(1);
#endif
display.ssd1306_command(SSD1306_SETCONTRAST);
display.ssd1306_command(1);
display.display();
}
#endif

View File

@@ -101,7 +101,7 @@ namespace GPS_Utils {
}
generateBeaconFirstPart();
String encodedGPS = encodeGPS(Config.beacon.latitude, Config.beacon.longitude, Config.beacon.overlay, Config.beacon.symbol);
iGateBeaconPacket += encodedGPS;
iGateBeaconPacket += encodedGPS;
iGateLoRaBeaconPacket += encodedGPS;
}
@@ -110,30 +110,22 @@ namespace GPS_Utils {
}
String decodeEncodedGPS(const String& packet) {
int indexOfExclamation = packet.indexOf(":!");
int indexOfEqual = packet.indexOf(":=");
const String& GPSPacket = packet.substring(packet.indexOf(":!")+3);
const String& encodedLatitude = GPSPacket.substring(0,4);
const String& encodedLongtitude = GPSPacket.substring(4,8);
const String& comment = GPSPacket.substring(12);
const uint8_t OFFSET = 3; // Offset for encoded data in the packet
String GPSPacket;
if (indexOfExclamation > 10) {
GPSPacket = packet.substring(indexOfExclamation + OFFSET);
} else if (indexOfEqual > 10) {
GPSPacket = packet.substring(indexOfEqual + OFFSET);
}
String encodedLatitude = GPSPacket.substring(0,4);
int Y1 = encodedLatitude[0] - 33;
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);
int Y1 = int(encodedLatitude[0]);
int Y2 = int(encodedLatitude[1]);
int Y3 = int(encodedLatitude[2]);
int Y4 = int(encodedLatitude[3]);
float decodedLatitude = 90.0 - ((((Y1-33) * pow(91,3)) + ((Y2-33) * pow(91,2)) + ((Y3-33) * 91) + Y4-33) / 380926.0);
int X1 = int(encodedLongtitude[0]);
int X2 = int(encodedLongtitude[1]);
int X3 = int(encodedLongtitude[2]);
int X4 = int(encodedLongtitude[3]);
float decodedLongitude = -180.0 + ((((X1-33) * pow(91,3)) + ((X2-33) * pow(91,2)) + ((X3-33) * 91) + X4-33) / 190463.0);
distance = String(calculateDistanceTo(decodedLatitude, decodedLongitude),1);
@@ -144,7 +136,6 @@ namespace GPS_Utils {
decodedGPS += distance;
decodedGPS += "km";
String comment = GPSPacket.substring(12);
if (comment != "") {
decodedGPS += " / ";
decodedGPS += comment;
@@ -153,30 +144,33 @@ namespace GPS_Utils {
}
String getReceivedGPS(const String& packet) {
int indexOfExclamation = packet.indexOf(":!");
int indexOfEqual = packet.indexOf(":=");
int indexOfAt = packet.indexOf(":@");
String infoGPS;
if (indexOfExclamation > 10) {
infoGPS = packet.substring(indexOfExclamation + 2);
} else if (indexOfEqual > 10) {
infoGPS = packet.substring(indexOfEqual + 2);
} else if (indexOfAt > 10) {
infoGPS = packet.substring(indexOfAt + 9); // 9 = 2+7 (when 7 is timestamp characters)
if (packet.indexOf(":!") > 10) {
infoGPS = packet.substring(packet.indexOf(":!") + 2);
} 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));
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
const String& firstLngPart = Longitude.substring(0,3);
const String& secondLngPart = Longitude.substring(3,5);
const String& thirdLngPart = Longitude.substring(Longitude.indexOf(".") + 1, Longitude.indexOf(".") + 3);
convertedLongitude = firstLngPart.toFloat() + (secondLngPart.toFloat()/60) + (thirdLngPart.toFloat()/(60*100));
if (String(Latitude[7]) == "S") {
convertedLatitude = -convertedLatitude;
}
if (String(Longitude[8]) == "W") {
convertedLongitude = -convertedLongitude;
}
distance = String(calculateDistanceTo(convertedLatitude, convertedLongitude),1);
@@ -187,7 +181,6 @@ namespace GPS_Utils {
decodedGPS += distance;
decodedGPS += "km";
String comment = infoGPS.substring(19);
if (comment != "") {
decodedGPS += " / ";
decodedGPS += comment;
@@ -196,36 +189,28 @@ namespace GPS_Utils {
}
String getDistanceAndComment(const String& packet) {
int indexOfAt = packet.indexOf(":@");
if (indexOfAt > 10) {
return getReceivedGPS(packet);
} else {
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);
}
uint8_t encodedBytePosition = 0;
if (packet.indexOf(":!") > 10) {
encodedBytePosition = packet.indexOf(":!") + 14;
}
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 " _ / _ / _ ";
return getReceivedGPS(packet);
}
} else {
return " _ / _ / _ ";
}
}
void setup() {
#ifdef HAS_GPS
if (Config.beacon.gpsActive && Config.digi.ecoMode != 1) {
if (Config.beacon.gpsActive) {
gpsSerial.begin(GPS_BAUD, SERIAL_8N1, GPS_TX, GPS_RX);
}
#endif

View File

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

View File

@@ -2,14 +2,12 @@
#include <WiFi.h>
#include "configuration.h"
#include "aprs_is_utils.h"
#include "station_utils.h"
#include "board_pinout.h"
#include "syslog_utils.h"
#include "ntp_utils.h"
#include "display.h"
#include "utils.h"
extern Configuration Config;
extern uint32_t lastRxTime;
@@ -22,7 +20,7 @@ bool transmitFlag = true;
SX1262 radio = new Module(RADIO_CS_PIN, RADIO_DIO1_PIN, RADIO_RST_PIN, RADIO_BUSY_PIN);
#endif
#ifdef HAS_SX1268
#if defined(LIGHTGATEWAY_1_0) || defined(LIGHTGATEWAY_PLUS_1_0)
#if defined(LIGHTGATEWAY_1_0)
SPIClass loraSPI(FSPI);
SX1268 radio = new Module(RADIO_CS_PIN, RADIO_DIO1_PIN, RADIO_RST_PIN, RADIO_BUSY_PIN, loraSPI);
#else
@@ -50,7 +48,7 @@ namespace LoRa_Utils {
}
void setup() {
#if defined (LIGHTGATEWAY_1_0) || defined(LIGHTGATEWAY_PLUS_1_0)
#ifdef LIGHTGATEWAY_1_0
pinMode(RADIO_VCC_PIN,OUTPUT);
digitalWrite(RADIO_VCC_PIN,HIGH);
loraSPI.begin(RADIO_SCLK_PIN, RADIO_MISO_PIN, RADIO_MOSI_PIN, RADIO_CS_PIN);
@@ -69,7 +67,11 @@ namespace LoRa_Utils {
while (true);
}
#if defined(HAS_SX1262) || defined(HAS_SX1268) || defined(HAS_LLCC68)
radio.setDio1Action(setFlag);
if (!Config.lowPowerMode) {
radio.setDio1Action(setFlag);
} else {
radio.setDIOMapping(1, RADIOLIB_SX126X_IRQ_RX_DONE);
}
#endif
#if defined(HAS_SX1278) || defined(HAS_SX1276)
radio.setDio0Action(setFlag, RISING);
@@ -80,7 +82,7 @@ namespace LoRa_Utils {
radio.setCodingRate(Config.loramodule.codingRate4);
radio.setCRC(true);
#if (defined(RADIO_RXEN) && defined(RADIO_TXEN)) // QRP Labs LightGateway has 400M22S (SX1268)
#if (defined(RADIO_RXEN) && defined(RADIO_TXEN)) || defined(LIGHTGATEWAY_1_0) // QRP Labs LightGateway has 400M22S (SX1268)
radio.setRfSwitchPins(RADIO_RXEN, RADIO_TXEN);
#endif
@@ -129,7 +131,7 @@ namespace LoRa_Utils {
}
#ifdef INTERNAL_LED_PIN
if (Config.digi.ecoMode != 1) digitalWrite(INTERNAL_LED_PIN, HIGH); // disabled in Ultra Eco Mode
if (!Config.digi.ecoMode) digitalWrite(INTERNAL_LED_PIN, HIGH);
#endif
int state = radio.transmit("\x3c\xff\x01" + newPacket);
transmitFlag = true;
@@ -144,61 +146,62 @@ namespace LoRa_Utils {
Utils::println(String(state));
}
#ifdef INTERNAL_LED_PIN
if (Config.digi.ecoMode != 1) digitalWrite(INTERNAL_LED_PIN, LOW); // disabled in Ultra Eco Mode
if (!Config.digi.ecoMode) digitalWrite(INTERNAL_LED_PIN, LOW);
#endif
if (Config.loramodule.txFreq != Config.loramodule.rxFreq) {
changeFreqRx();
}
}
String receivePacketFromSleep() {
String packet = "";
int state = radio.readData(packet);
if (state == RADIOLIB_ERR_NONE) {
Utils::println("<--- LoRa Packet Rx : " + packet.substring(3));
} else {
packet = "";
/*String packetSanitization(const String& packet) {
String sanitizedPacket = packet;
if (packet.indexOf("\0") > 0) {
sanitizedPacket.replace("\0", "");
}
return packet;
if (packet.indexOf("\r") > 0) {
sanitizedPacket.replace("\r", "");
}
if (packet.indexOf("\n") > 0) {
sanitizedPacket.replace("\n", "");
}
return sanitizedPacket;
}*/
void startReceive() {
radio.startReceive();
}
String receivePacket() {
String packet = "";
if (operationDone) {
if (operationDone || Config.lowPowerMode) {
operationDone = false;
if (transmitFlag) {
if (transmitFlag && !Config.lowPowerMode) {
radio.startReceive();
transmitFlag = false;
} else {
int state = radio.readData(packet);
if (state == RADIOLIB_ERR_NONE) {
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) + ")");
String sender = packet.substring(3, packet.indexOf(">"));
if (packet.substring(0,3) == "\x3c\xff\x01" && !STATION_Utils::isBlacklisted(sender)){ // avoid processing BlackListed stations
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.digi.ecoMode == 0) {
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);
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);
}
if (Config.syslog.active && WiFi.status() == WL_CONNECTED) {
SYSLOG_Utils::log(1, packet, rssi, snr, freqError); // RX
}
} else {
packet = "";
if (Config.syslog.active && WiFi.status() == WL_CONNECTED) {
SYSLOG_Utils::log(1, packet, rssi, snr, freqError); // RX
}
lastRxTime = millis();
return packet;
@@ -222,10 +225,6 @@ namespace LoRa_Utils {
return packet;
}
void wakeRadio() {
radio.startReceive();
}
void sleepRadio() {
radio.sleep();
}

View File

@@ -15,7 +15,7 @@ NTPClient timeClient(ntpUDP, "pool.ntp.org", 0, 15 * 60 * 1000); // Update in
namespace NTP_Utils {
void setup() {
if (WiFi.status() == WL_CONNECTED && Config.digi.ecoMode == 0 && Config.callsign != "NOCALL-10") {
if (WiFi.status() == WL_CONNECTED && !Config.digi.ecoMode && Config.callsign != "NOCALL-10") {
int gmt = Config.ntp.gmtCorrection * 3600;
timeClient.setTimeOffset(gmt);
timeClient.begin();
@@ -23,11 +23,11 @@ namespace NTP_Utils {
}
void update() {
if (WiFi.status() == WL_CONNECTED && Config.digi.ecoMode == 0 && Config.callsign != "NOCALL-10") timeClient.update();
if (WiFi.status() == WL_CONNECTED && !Config.digi.ecoMode && Config.callsign != "NOCALL-10") timeClient.update();
}
String getFormatedTime() {
if (Config.digi.ecoMode == 0) return timeClient.getFormattedTime();
if (!Config.digi.ecoMode) return timeClient.getFormattedTime();
return "DigiEcoMode Active";
}

View File

@@ -5,7 +5,6 @@
#include "ota_utils.h"
#include "display.h"
extern Configuration Config;
extern uint32_t lastScreenOn;
extern bool isUpdatingOTA;
@@ -14,14 +13,14 @@ unsigned long ota_progress_millis = 0;
namespace OTA_Utils {
void setup(AsyncWebServer *server) {
if (Config.ota.username != "" && Config.ota.password != "") {
ElegantOTA.begin(server, Config.ota.username.c_str(), Config.ota.password.c_str());
} else {
ElegantOTA.begin(server);
}
ElegantOTA.setAutoReboot(true);
ElegantOTA.onStart(onOTAStart);
ElegantOTA.onProgress(onOTAProgress);
@@ -55,8 +54,8 @@ namespace OTA_Utils {
Serial.println(success ? "OTA update finished successfully!" : "There was an error during OTA update!");
displayShow("", "", statusMessage, "", rebootMessage, "", "", 4000);
isUpdatingOTA = false;
}
}

View File

@@ -4,17 +4,9 @@
#include "power_utils.h"
#if defined(HAS_AXP192) || defined(HAS_AXP2101)
#ifdef TTGO_T_Beam_S3_SUPREME_V3
#define I2C0_SDA 17
#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
#define I2C_SDA 21
#define I2C_SCL 22
#define IRQ_PIN 35
#endif
#ifdef HAS_AXP192
@@ -62,13 +54,8 @@ namespace POWER_Utils {
#endif
#ifdef HAS_AXP2101
#ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.setALDO4Voltage(3300);
PMU.enableALDO4();
#else
PMU.setALDO3Voltage(3300);
PMU.enableALDO3();
#endif
#endif
#ifdef HELTEC_WIRELESS_TRACKER
digitalWrite(VEXT_CTRL, HIGH);
@@ -82,11 +69,7 @@ namespace POWER_Utils {
#endif
#ifdef HAS_AXP2101
#ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.disableALDO4();
#else
PMU.disableALDO3();
#endif
PMU.disableALDO3();
#endif
#ifdef HELTEC_WIRELESS_TRACKER
digitalWrite(VEXT_CTRL, LOW);
@@ -100,13 +83,8 @@ namespace POWER_Utils {
PMU.enableLDO2();
#endif
#ifdef HAS_AXP2101
#ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.setALDO3Voltage(3300);
PMU.enableALDO3();
#else
PMU.setALDO2Voltage(3300);
PMU.enableALDO2();
#endif
PMU.setALDO2Voltage(3300);
PMU.enableALDO2();
#endif
}
@@ -115,11 +93,7 @@ namespace POWER_Utils {
PMU.disableLDO2();
#endif
#ifdef HAS_AXP2101
#ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.disableALDO3();
#else
PMU.disableALDO2();
#endif
PMU.disableALDO2();
#endif
}
@@ -137,29 +111,20 @@ namespace POWER_Utils {
}
return result;
#elif defined(HAS_AXP2101)
#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
bool result = PMU.begin(Wire, AXP2101_SLAVE_ADDRESS, I2C_SDA, I2C_SCL);
if (result) {
PMU.disableDC2();
PMU.disableDC3();
PMU.disableDC4();
PMU.disableDC5();
#ifndef TTGO_T_Beam_S3_SUPREME_V3
PMU.disableALDO1();
PMU.disableALDO4();
#endif
PMU.disableALDO1();
PMU.disableALDO4();
PMU.disableBLDO1();
PMU.disableBLDO2();
PMU.disableDLDO1();
PMU.disableDLDO2();
PMU.setDC1Voltage(3300);
PMU.enableDC1();
#ifdef TTGO_T_Beam_S3_SUPREME_V3
PMU.setALDO1Voltage(3300);
#endif
PMU.setButtonBatteryChargeVoltage(3300);
PMU.enableButtonBatteryCharge();
PMU.disableIRQ(XPOWERS_AXP2101_ALL_IRQ);
@@ -187,16 +152,8 @@ namespace POWER_Utils {
#endif
#ifdef HAS_AXP2101
bool beginStatus = false;
#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) {
Wire.begin(SDA, SCL);
if (begin(Wire)) {
Serial.println("AXP2101 init done!");
} else {
Serial.println("AXP2101 init failed!");
@@ -216,7 +173,6 @@ namespace POWER_Utils {
#ifdef INTERNAL_LED_PIN
pinMode(INTERNAL_LED_PIN, OUTPUT);
digitalWrite(INTERNAL_LED_PIN, LOW);
#endif
if (Config.battery.sendExternalVoltage || Config.battery.monitorExternalVoltage) {
@@ -225,39 +181,33 @@ namespace POWER_Utils {
#ifdef VEXT_CTRL
pinMode(VEXT_CTRL,OUTPUT); // GPS + TFT on HELTEC Wireless_Tracker and only for Oled in HELTEC V3
#if defined(HELTEC_WIRELESS_TRACKER) || defined(HELTEC_V3)
digitalWrite(VEXT_CTRL, Config.digi.ecoMode == 1 ? LOW : HIGH);
#if defined(HELTEC_WIRELESS_TRACKER) || defined(HELTEC_V3)
digitalWrite(VEXT_CTRL, HIGH);
#endif
#if defined(HELTEC_WP) || defined(HELTEC_WS) || defined(HELTEC_V3_2) || defined(HELTEC_WSL_V3)
digitalWrite(VEXT_CTRL, Config.digi.ecoMode == 1 ? HIGH : LOW);
#if defined(HELTEC_WP) || defined(HELTEC_WS) || defined(HELTEC_V3_2)
digitalWrite(VEXT_CTRL, LOW);
#endif
#endif
#ifdef HAS_GPS
if (Config.beacon.gpsActive && Config.digi.ecoMode != 1) activateGPS();
if (Config.beacon.gpsActive) activateGPS();
#endif
#ifdef ADC_CTRL
pinMode(ADC_CTRL, OUTPUT);
#if defined(HELTEC_WIRELESS_TRACKER) || defined(HELTEC_V3_2)
digitalWrite(ADC_CTRL, LOW);
#endif
#if defined(HELTEC_V3) || defined(HELTEC_V2) || defined(HELTEC_WSL_V3) || defined(HELTEC_WP)
digitalWrite(ADC_CTRL, HIGH);
#endif
#endif
#if defined(HELTEC_WIRELESS_TRACKER)
Wire.begin(BOARD_I2C_SDA, BOARD_I2C_SCL);
#endif
#if defined(HELTEC_V3) || defined(HELTEC_V3_2) || defined(HELTEC_WS) || defined(LIGHTGATEWAY_1_0) || defined(LIGHTGATEWAY_PLUS_1_0) || defined(TTGO_LORA32_T3S3_V1_2) || defined(HELTEC_V2)
#if defined(HELTEC_V3) || defined(HELTEC_V3_2) || defined(HELTEC_WS) || defined(LIGHTGATEWAY_1_0) || defined(TTGO_LORA32_T3S3_V1_2) || defined(HELTEC_V2)
Wire.begin(OLED_SDA, OLED_SCL);
#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
#endif
#if defined(TTGO_T_DECK_GPS) || defined(TTGO_T_DECK_PLUS)
pinMode(BOARD_POWERON, OUTPUT);
@@ -273,12 +223,11 @@ namespace POWER_Utils {
delay(500);
Wire.begin(BOARD_I2C_SDA, BOARD_I2C_SCL);
#endif
#endif
delay(1000);
BATTERY_Utils::setup();
BATTERY_Utils::startupBatteryHealth();
setCpuFrequencyMhz(80);
}
}

View File

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

View File

@@ -1,65 +0,0 @@
#include "configuration.h"
#include "board_pinout.h"
#include "sleep_utils.h"
#include "digi_utils.h"
#include "lora_utils.h"
extern Configuration Config;
extern bool shouldSleepStop;
extern uint32_t lastBeaconTx;
bool wakeUpFlag = false;
namespace SLEEP_Utils {
void wakeUpLoRaPacketReceived() {
wakeUpFlag = true;
}
void checkWakeUpFlag() {
if (wakeUpFlag) {
String packet = LoRa_Utils::receivePacketFromSleep();
if (packet != "") {
DIGI_Utils::processLoRaPacket(packet);
}
wakeUpFlag = false;
}
}
void setup() {
if (Config.digi.ecoMode == 1) {
pinMode(RADIO_WAKEUP_PIN, INPUT);
attachInterrupt(digitalPinToInterrupt(RADIO_WAKEUP_PIN), wakeUpLoRaPacketReceived, RISING);
#if defined(TTGO_LORA32_V2_1) || defined(TTGO_LORA32_V2_1_915) || defined(TTGO_LORA32_T3S3_V1_2) || defined(TTGO_T_BEAM_V1_0) || defined(TTGO_T_BEAM_V1_0_915) || defined(TTGO_T_BEAM_V1_0_SX1268) || defined(TTGO_T_BEAM_V1_2) || defined(TTGO_T_BEAM_V1_2_915) || defined(TTGO_T_BEAM_V1_2_SX1262) || defined(TTGO_T_DECK_PLUS) || defined(TTGO_T_DECK_GPS) || defined(TTGO_T_Beam_S3_SUPREME_V3) || defined(HELTEC_V3) || defined(HELTEC_V3_2) || defined(HELTEC_WP) || defined(HELTEC_WS) || defined(HELTEC_WSL_V3) || defined(HELTEC_WSL_V3_DISPLAY) || defined(HELTEC_WIRELESS_TRACKER) || defined(HELTEC_V2) || defined(XIAO_ESP32S3_LORA) || defined(LIGHTGATEWAY_1_0) || defined(LIGHTGATEWAY_PLUS_1_0) || defined(TROY_LoRa_APRS) || defined(OE5HWN_MeshCom) || defined(ESP32_DIY_LoRa) || defined(ESP32_DIY_LoRa_915) || defined(ESP32_DIY_1W_LoRa) || defined(ESP32_DIY_1W_LoRa_915) || defined(ESP32_DIY_1W_LoRa_LLCC68) || defined(ESP32_DIY_1W_LoRa_Mesh_V1_2) || defined(WEMOS_S2_MINI_DIY_LoRa) || defined(WEMOS_D1_R32_RA02) || defined(WEMOS_LOLIN32_OLED_DIY_LoRa)
esp_sleep_enable_ext1_wakeup(GPIO_WAKEUP_PIN, ESP_EXT1_WAKEUP_ANY_HIGH);
#endif
#if defined(HELTEC_HTCT62) || defined(ESP32C3_DIY_1W_LoRa) || defined(ESP32C3_DIY_1W_LoRa_915) || defined(ESP32_C3_OctopusLab_LoRa)
esp_deep_sleep_enable_gpio_wakeup(1ULL << GPIO_WAKEUP_PIN, ESP_GPIO_WAKEUP_GPIO_HIGH);
#endif
}
}
uint32_t getSecondsToSleep() {
uint32_t elapsedTime = (millis() - lastBeaconTx) / 1000; // in secs
uint32_t intervalTime = Config.beacon.interval * 60; // in secs
return (elapsedTime < intervalTime) ? (intervalTime - elapsedTime) : 0;
}
void startSleeping() {
if (!shouldSleepStop) {
uint32_t timeToSleep = getSecondsToSleep();
esp_sleep_enable_timer_wakeup(timeToSleep * 1000000); // 1 min = 60sec
Serial.print("(Sleeping : "); Serial.print(timeToSleep); Serial.println("seconds)");
delay(100);
LoRa_Utils::wakeRadio();
esp_light_sleep_start();
}
}
void checkSerial() {
if (Config.digi.ecoMode == 1) Serial.end();
}
}

View File

@@ -7,7 +7,6 @@
#include "utils.h"
#include <vector>
extern Configuration Config;
extern uint32_t lastRxTime;
extern String fourthLine;
@@ -17,8 +16,7 @@ uint32_t lastTxTime = millis();
std::vector<LastHeardStation> lastHeardStations;
std::vector<String> outputPacketBuffer;
std::vector<Packet25SegBuffer> packet25SegBuffer;
std::vector<String> blacklist;
std::vector<String> managers;
std::vector<String> blackList;
std::vector<LastHeardStation> lastHeardObjects;
bool saveNewDigiEcoModeConfig = false;
@@ -26,51 +24,33 @@ bool saveNewDigiEcoModeConfig = false;
namespace STATION_Utils {
std::vector<String> loadCallSignList(const String& list) {
std::vector<String> loadedList;
void loadBlackList() {
if (Config.blackList != "") {
String callsigns = Config.blackList;
int spaceIndex = callsigns.indexOf(" ");
String callsigns = list;
callsigns.trim();
while (callsigns.length() > 0) { // != ""
int spaceIndex = callsigns.indexOf(" ");
if (spaceIndex == -1) { // No more spaces, add the last part
loadedList.push_back(callsigns);
break;
while (spaceIndex >= 0) {
blackList.push_back(callsigns.substring(0, spaceIndex));
callsigns = callsigns.substring(spaceIndex + 1);
spaceIndex = callsigns.indexOf(" ");
}
loadedList.push_back(callsigns.substring(0, spaceIndex));
callsigns = callsigns.substring(spaceIndex + 1);
callsigns.trim(); // Trim in case of multiple spaces
callsigns.trim();
if (callsigns.length() > 0) blackList.push_back(callsigns); // Add the last word if available
}
return loadedList;
}
void loadBlacklistAndManagers() {
blacklist = loadCallSignList(Config.blacklist);
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;
bool checkBlackList(const String& callsign) {
for (int i = 0; i < blackList.size(); i++) {
if (blackList[i].indexOf("*") >= 0) { // use wild card
String wildCard = blackList[i].substring(0, blackList[i].indexOf("*"));
if (callsign.startsWith(wildCard))return true;
} else {
if (list[i] == callsign) return true;
}
if (blackList[i] == callsign) return true;
}
}
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
@@ -94,7 +74,7 @@ namespace STATION_Utils {
lastHeardObjects.emplace_back(LastHeardStation{millis(), object}); // Add new object and Tx
return true;
}
void deleteNotHeard() {
std::vector<LastHeardStation> lastHeardStation_temp;
for (int i = 0; i < lastHeardStations.size(); i++) {
@@ -149,24 +129,6 @@ namespace STATION_Utils {
return true;
}
void processOutputPacketBufferUltraEcoMode() {
size_t currentIndex = 0;
while (currentIndex < outputPacketBuffer.size()) { // this sends all packets from output buffer
delay(3000); // and cleans buffer to avoid sending packets with time offset
LoRa_Utils::sendNewPacket(outputPacketBuffer[currentIndex]); // next time it wakes up
currentIndex++;
}
outputPacketBuffer.clear();
//
if (saveNewDigiEcoModeConfig) {
Config.writeFile();
delay(1000);
displayToggle(false);
ESP.restart();
}
//
}
void processOutputPacketBuffer() {
int timeToWait = 3 * 1000; // 3 segs between packet Tx and also Rx ???
uint32_t lastRx = millis() - lastRxTime;
@@ -184,6 +146,7 @@ namespace STATION_Utils {
}
}
if (saveNewDigiEcoModeConfig) {
setCpuFrequencyMhz(80);
Config.writeFile();
delay(1000);
displayToggle(false);

View File

@@ -4,7 +4,6 @@
#include "syslog_utils.h"
#include "gps_utils.h"
extern Configuration Config;
WiFiUDP udpClient;
@@ -16,8 +15,8 @@ namespace SYSLOG_Utils {
if (Config.syslog.active && WiFi.status() == WL_CONNECTED) {
String syslogPacket = "<165>1 - ";
syslogPacket.concat(Config.callsign);
syslogPacket.concat(" CA2RXU_LoRa_iGate_3.0 - - - "); //RFC5424 The Syslog Protocol
syslogPacket.concat(" CA2RXU_LoRa_iGate_1.3 - - - "); //RFC5424 The Syslog Protocol
char signalData[35];
snprintf(signalData, sizeof(signalData), " / %ddBm / %.2fdB / %dHz", rssi, snr, freqError);
@@ -38,16 +37,15 @@ namespace SYSLOG_Utils {
syslogPacket.concat(sender);
syslogPacket.concat(" ---> ");
syslogPacket.concat(packet.substring(colonIndex + 2));
} else if (nextChar == '!' || nextChar == '=' || nextChar == '@') {
} else if (nextChar == '!' || nextChar == '=') {
syslogPacket.concat("GPS / ");
syslogPacket.concat(sender);
syslogPacket.concat(" / ");
int greaterThanIndex = packet.indexOf(">");
if (packet.indexOf("WIDE1-1") > 10) {
syslogPacket.concat(packet.substring(greaterThanIndex + 1, packet.indexOf(",")));
syslogPacket.concat(packet.substring(packet.indexOf(">") + 1, packet.indexOf(",")));
syslogPacket.concat(" / WIDE1-1");
} else {
syslogPacket.concat(packet.substring(greaterThanIndex + 1, colonIndex));
syslogPacket.concat(packet.substring(packet.indexOf(">") + 1, colonIndex));
syslogPacket.concat(" / -");
}
} else if (nextChar == '>') {
@@ -74,7 +72,7 @@ namespace SYSLOG_Utils {
syslogPacket.concat(packet);
}
syslogPacket.concat(signalData);
if (nextChar == '!' || nextChar == '=' || nextChar == '@') {
if (nextChar == '!' || nextChar == '=') {
syslogPacket.concat(" / ");
syslogPacket.concat(GPS_Utils::getDistanceAndComment(packet));
}

View File

@@ -5,7 +5,6 @@
#include "station_utils.h"
#include "utils.h"
extern Configuration Config;
#define MAX_CLIENTS 4
@@ -24,7 +23,7 @@ String inputSerialBuffer = "";
namespace TNC_Utils {
void setup() {
if (Config.tnc.enableServer && Config.digi.ecoMode == 0) {
if (Config.tnc.enableServer && !Config.digi.ecoMode) {
tncServer.stop();
tncServer.begin();
}
@@ -47,7 +46,7 @@ namespace TNC_Utils {
void handleInputData(char character, int bufferIndex) {
String* data = (bufferIndex == -1) ? &inputSerialBuffer : &inputServerBuffer[bufferIndex];
if (data->length() == 0 && character != (char)FEND) return;
data->concat(character);
if (character == (char)FEND && data->length() > 3) {
@@ -128,7 +127,7 @@ namespace TNC_Utils {
}
void loop() {
if (Config.digi.ecoMode == 0) {
if (!Config.digi.ecoMode) {
if (Config.tnc.enableServer) {
checkNewClients();
readFromClients();

View File

@@ -76,7 +76,7 @@ namespace Utils {
}
String getLocalIP() {
if (Config.digi.ecoMode == 1 || Config.digi.ecoMode == 2) {
if (Config.digi.ecoMode) {
return "** WiFi AP Killed **";
} else if (!WiFiConnected) {
return "IP : 192.168.4.1";
@@ -88,19 +88,12 @@ namespace Utils {
}
void setupDisplay() {
if (Config.digi.ecoMode != 1) displaySetup();
displaySetup();
#ifdef INTERNAL_LED_PIN
digitalWrite(INTERNAL_LED_PIN,HIGH);
#endif
Serial.println("\nStarting Station: " + Config.callsign + " Version: " + versionDate);
Serial.print("(DigiEcoMode: ");
if (Config.digi.ecoMode == 0) {
Serial.println("OFF)");
} else if (Config.digi.ecoMode == 1) {
Serial.println("ON)");
} else {
Serial.println("ON / Only Serial Output)");
}
Serial.println((Config.digi.ecoMode) ? "(DigiEcoMode: ON)" : "(DigiEcoMode: OFF)");
displayShow(" LoRa APRS", "", "", " ( iGATE & DIGI )", "", "" , " CA2RXU " + versionDate, 4000);
#ifdef INTERNAL_LED_PIN
digitalWrite(INTERNAL_LED_PIN,LOW);
@@ -189,7 +182,7 @@ namespace Utils {
void checkBeaconInterval() {
uint32_t lastTx = millis() - lastBeaconTx;
if (lastBeaconTx == 0 || lastTx >= Config.beacon.interval * 60 * 1000) {
beaconUpdate = true;
beaconUpdate = true;
}
#ifdef HAS_GPS
@@ -207,6 +200,7 @@ namespace Utils {
!Config.wxsensor.active &&
(Config.battery.sendInternalVoltage || Config.battery.sendExternalVoltage) &&
(lastBeaconTx > 0)) {
//(!Config.digi.ecoMode || lastBeaconTx > 0)) {
sendInitialTelemetryPackets();
}
@@ -217,7 +211,7 @@ namespace Utils {
beaconPacket = iGateBeaconPacket;
secondaryBeaconPacket = iGateLoRaBeaconPacket;
#ifdef HAS_GPS
if (Config.beacon.gpsActive && Config.digi.ecoMode == 0) {
if (Config.beacon.gpsActive && !Config.digi.ecoMode) {
GPS_Utils::getData();
if (gps.location.isUpdated() && gps.location.lat() != 0.0 && gps.location.lng() != 0.0) {
GPS_Utils::generateBeaconFirstPart();
@@ -229,7 +223,7 @@ namespace Utils {
#endif
if (Config.wxsensor.active) {
String sensorData = (wxModuleType == 0) ? ".../...g...t..." : WX_Utils::readDataSensor();
const char* sensorData = (wxModuleType == 0) ? ".../...g...t..." : WX_Utils::readDataSensor().c_str();
beaconPacket += sensorData;
secondaryBeaconPacket += sensorData;
}

View File

@@ -5,7 +5,6 @@
#include "display.h"
#include "utils.h"
extern Configuration Config;
extern uint32_t lastBeaconTx;
extern std::vector<ReceivedPacket> receivedPackets;
@@ -115,7 +114,7 @@ namespace WEB_Utils {
Config.wifiAutoAP.password = request->getParam("wifi.autoAP.password", true)->value();
Config.wifiAutoAP.timeout = request->getParam("wifi.autoAP.timeout", true)->value().toInt();
Config.aprs_is.active = request->hasParam("aprs_is.active", true);
Config.aprs_is.passcode = request->getParam("aprs_is.passcode", true)->value();
@@ -141,7 +140,7 @@ namespace WEB_Utils {
Config.digi.mode = request->getParam("digi.mode", true)->value().toInt();
Config.digi.ecoMode = request->getParam("digi.ecoMode", true)->value().toInt();;
Config.digi.ecoMode = request->hasParam("digi.ecoMode", true);
Config.loramodule.txFreq = request->getParam("lora.txFreq", true)->value().toInt();
@@ -175,7 +174,7 @@ namespace WEB_Utils {
Config.battery.externalSleepVoltage = request->getParam("battery.externalSleepVoltage", true)->value().toFloat();
Config.battery.sendVoltageAsTelemetry = request->hasParam("battery.sendVoltageAsTelemetry", true);
Config.wxsensor.active = request->hasParam("wxsensor.active", true);
Config.wxsensor.heightCorrection = request->getParam("wxsensor.heightCorrection", true)->value().toInt();
Config.wxsensor.temperatureCorrection = request->getParam("wxsensor.temperatureCorrection", true)->value().toFloat();
@@ -202,10 +201,12 @@ namespace WEB_Utils {
Config.rememberStationTime = request->getParam("other.rememberStationTime", true)->value().toInt();
Config.backupDigiMode = request->hasParam("other.backupDigiMode", true);
Config.lowPowerMode = request->hasParam("other.lowPowerMode", true);
Config.lowVoltageCutOff = request->getParam("other.lowVoltageCutOff", true)->value().toDouble();
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);
if (Config.webadmin.active) {
@@ -215,16 +216,12 @@ namespace WEB_Utils {
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();
AsyncWebServerResponse *response = request->beginResponse(302, "text/html", "");
response->addHeader("Location", "/");
request->send(response);
displayToggle(false);
delay(200);
ESP.restart();
}
@@ -270,7 +267,7 @@ namespace WEB_Utils {
}
void setup() {
if (Config.digi.ecoMode == 0) {
if (!Config.digi.ecoMode) {
server.on("/", HTTP_GET, handleHome);
server.on("/status", HTTP_GET, handleStatus);
server.on("/received-packets.json", HTTP_GET, handleReceivedPackets);

View File

@@ -5,7 +5,6 @@
#include "display.h"
#include "utils.h"
extern Configuration Config;
extern uint8_t myWiFiAPIndex;
@@ -24,7 +23,7 @@ uint32_t lastBackupDigiTime = millis();
namespace WIFI_Utils {
void checkWiFi() {
if (Config.digi.ecoMode == 0) {
if (!Config.digi.ecoMode) {
if (backUpDigiMode) {
uint32_t WiFiCheck = millis() - lastBackupDigiTime;
if (WiFi.status() != WL_CONNECTED && WiFiCheck >= 15 * 60 * 1000) {
@@ -154,7 +153,7 @@ namespace WIFI_Utils {
}
void setup() {
if (Config.digi.ecoMode == 0) startWiFi();
if (!Config.digi.ecoMode) startWiFi();
btStop();
}

View File

@@ -1,7 +1,4 @@
#include <TinyGPS++.h>
#ifdef LIGHTGATEWAY_PLUS_1_0
#include "Adafruit_SHTC3.h"
#endif
#include "configuration.h"
#include "board_pinout.h"
#include "wx_utils.h"
@@ -26,17 +23,15 @@ float newHum, newTemp, newPress, newGas;
Adafruit_BME280 bme280;
#if defined(HELTEC_V3) || defined(HELTEC_V3_2)
Adafruit_BMP280 bmp280(&Wire1);
Adafruit_Si7021 sensor = Adafruit_Si7021();
Adafruit_Si7021 sensor = Adafruit_Si7021();
#else
Adafruit_BMP280 bmp280;
Adafruit_BME680 bme680;
Adafruit_Si7021 si7021 = Adafruit_Si7021();
#endif
#ifdef LIGHTGATEWAY_PLUS_1_0
Adafruit_SHTC3 shtc3 = Adafruit_SHTC3();
Adafruit_Si7021 sensor = Adafruit_Si7021();
#endif
namespace WX_Utils {
void getWxModuleAddres() {
@@ -47,23 +42,16 @@ namespace WX_Utils {
err = Wire1.endTransmission();
#else
Wire.beginTransmission(addr);
#ifdef LIGHTGATEWAY_PLUS_1_0
Wire.write(0x35);
Wire.write(0x17);
#endif
err = Wire.endTransmission();
#endif
if (err == 0) {
//Serial.println(addr); //this shows any connected board to I2C
if (addr == 0x76 || addr == 0x77) { // BME or BMP
//Serial.println(addr); this shows any connected board to I2C
if (addr == 0x76 || addr == 0x77) { // BME/BMP
wxModuleAddress = addr;
return;
} else if (addr == 0x40) { // Si7011
wxModuleAddress = addr;
return;
} else if (addr == 0x70) { // SHTC3
wxModuleAddress = addr;
return;
}
}
}
@@ -78,49 +66,40 @@ namespace WX_Utils {
#if defined(HELTEC_V3) || defined(HELTEC_V3_2) || defined(HELTEC_WSL_V3) || defined(HELTEC_WSL_V3_DISPLAY)
if (bme280.begin(wxModuleAddress, &Wire1)) {
Serial.println("BME280 sensor found");
wxModuleType = 1;
wxModuleFound = true;
wxModuleType = 1;
wxModuleFound = true;
}
#else
if (bme280.begin(wxModuleAddress)) {
Serial.println("BME280 sensor found");
wxModuleType = 1;
wxModuleFound = true;
wxModuleType = 1;
wxModuleFound = true;
}
if (!wxModuleFound) {
if (bme680.begin(wxModuleAddress)) {
Serial.println("BME680 sensor found");
wxModuleType = 3;
wxModuleFound = true;
wxModuleType = 3;
wxModuleFound = true;
}
}
#endif
if (!wxModuleFound) {
if (bmp280.begin(wxModuleAddress)) {
Serial.println("BMP280 sensor found");
wxModuleType = 2;
wxModuleFound = true;
wxModuleType = 2;
wxModuleFound = true;
}
}
} else if (wxModuleAddress == 0x40) {
if(si7021.begin()) {
if(sensor.begin()) {
Serial.println("Si7021 sensor found");
wxModuleType = 4;
wxModuleFound = true;
wxModuleType = 4;
wxModuleFound = true;
}
}
#ifdef LIGHTGATEWAY_PLUS_1_0
else if (wxModuleAddress == 0x70) {
if (shtc3.begin()) {
Serial.println("SHTC3 sensor found");
wxModuleType = 5;
wxModuleFound = true;
}
}
#endif
}
if (!wxModuleFound) {
displayShow("ERROR", "", "BME/BMP/Si7021/SHTC3 sensor active", "but no sensor found...", 2000);
Serial.println("BME/BMP/Si7021/SHTC3 sensor Active in config but not found! Check Wiring");
displayShow("ERROR", "", "BME/BMP/Si7021 sensor active", "but no sensor found...", 2000);
Serial.println("BME/BMP/Si7021 sensor Active in config but not found! Check Wiring");
} else {
switch (wxModuleType) {
case 1:
@@ -233,18 +212,9 @@ namespace WX_Utils {
#endif
break;
case 4: // Si7021
newTemp = si7021.readTemperature();
newHum = si7021.readHumidity();
newTemp = sensor.readTemperature();
newPress = 0;
break;
case 5: // SHTC3
#ifdef LIGHTGATEWAY_PLUS_1_0
sensors_event_t humidity, temp;
shtc3.getEvent(&humidity, &temp);
newTemp = temp.temperature;
newHum = humidity.relative_humidity;
newPress = 0;
#endif
newHum = sensor.readHumidity();
break;
}
@@ -256,20 +226,20 @@ namespace WX_Utils {
String tempStr = generateTempString(((newTemp + Config.wxsensor.temperatureCorrection) * 1.8) + 32);
String humStr;
if (wxModuleType == 1 || wxModuleType == 3 || wxModuleType == 4 || wxModuleType == 5) {
if (wxModuleType == 1 || wxModuleType == 3 || wxModuleType == 4) {
humStr = generateHumString(newHum);
} else if (wxModuleType == 2) {
humStr = "..";
}
String presStr = (wxModuleType == 4 || wxModuleType == 5)
String presStr = (wxModuleAddress == 4)
? "....."
#ifdef HAS_GPS
: generatePresString(newPress + (gps.altitude.meters() / CORRECTION_FACTOR));
#else
: generatePresString(newPress + (Config.wxsensor.heightCorrection / CORRECTION_FACTOR));
#endif
fifthLine = "BME-> ";
fifthLine += String(int(newTemp + Config.wxsensor.temperatureCorrection));
fifthLine += "C ";

View File

@@ -11,8 +11,6 @@
#define RADIO_DIO1_PIN 3
#define RADIO_RST_PIN -1
#define RADIO_BUSY_PIN 8
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_NUM_3
// Display
#define HAS_DISPLAY

View File

@@ -13,8 +13,6 @@
#define RADIO_BUSY_PIN 14
#define RADIO_RXEN 32
#define RADIO_TXEN 25
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_12
// Display
#define HAS_DISPLAY

View File

@@ -13,8 +13,6 @@
#define RADIO_BUSY_PIN 14
#define RADIO_RXEN 32
#define RADIO_TXEN 25
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_12
// Display
#define HAS_DISPLAY

View File

@@ -13,8 +13,6 @@
#define RADIO_BUSY_PIN 14
#define RADIO_RXEN 32
#define RADIO_TXEN 25
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_12
// Display
#define HAS_DISPLAY

View File

@@ -13,8 +13,6 @@
#define RADIO_BUSY_PIN 32
#define RADIO_RXEN 14
#define RADIO_TXEN 13
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_33
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -13,8 +13,6 @@
#define RADIO_BUSY_PIN 26
#define RADIO_RXEN 14
#define RADIO_TXEN 13
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_33
// Display
#define HAS_DISPLAY

View File

@@ -13,8 +13,6 @@
#define RADIO_BUSY_PIN 6
#define RADIO_RXEN 42
#define RADIO_TXEN 14
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_5
// Display
#define HAS_DISPLAY

View File

@@ -1,36 +0,0 @@
#ifndef BOARD_PINOUT_H_
#define BOARD_PINOUT_H_
// LoRa Radio
#define HAS_SX1268
#define HAS_1W_LORA
#define RADIO_VCC_PIN 21
#define RADIO_SCLK_PIN 12
#define RADIO_MISO_PIN 13
#define RADIO_MOSI_PIN 11
#define RADIO_CS_PIN 10
#define RADIO_RST_PIN 9
#define RADIO_DIO1_PIN 5
#define RADIO_BUSY_PIN 6
#define RADIO_RXEN 42
#define RADIO_TXEN 14
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_5
// Display
#define HAS_DISPLAY
#undef OLED_SDA
#undef OLED_SCL
#undef OLED_RST
#define OLED_SDA 3
#define OLED_SCL 4
#define OLED_RST -1 // Reset pin # (or -1 if sharing Arduino reset pin)
// Aditional Config
#define INTERNAL_LED_PIN 16
#define BATTERY_PIN 1
#define BUTTON_PIN 0
#endif

View File

@@ -1,11 +0,0 @@
[env:QRPLabs_LightGateway_Plus_1_0]
board = esp32-s3-devkitc-1
board_build.mcu = esp32s3
build_flags =
${common.build_flags}
${common.usb_flags}
-D LIGHTGATEWAY_PLUS_1_0
lib_deps =
${common.lib_deps}
${common.display_libs}
adafruit/Adafruit SHTC3 Library @ 1.0.1

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 23
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 13
#define RADIO_DIO1_PIN 14
#define RADIO_BUSY_PIN 12
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_12
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 14
#define RADIO_RST_PIN 2
#define RADIO_BUSY_PIN 25
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_25
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 34
#define RADIO_RST_PIN 33
#define RADIO_BUSY_PIN 38
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_38
// Aditional Config
#define INTERNAL_LED_PIN 15

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 42
#define RADIO_DIO1_PIN 39
#define RADIO_BUSY_PIN 40
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_39
#define RADIO_HAS_RF_SWITCH // DIO02
#define RADIO_RF_SWITCH 38

View File

@@ -13,7 +13,5 @@
#define RADIO_BUSY_PIN 3
#define RADIO_RXEN 6
#define RADIO_TXEN 7
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_NUM_2
#endif

View File

@@ -13,7 +13,5 @@
#define RADIO_BUSY_PIN 3
#define RADIO_RXEN 6
#define RADIO_TXEN 7
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_NUM_2
#endif

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 5
#define RADIO_DIO1_PIN 3
#define RADIO_BUSY_PIN 4
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_NUM_3
// Aditional Config
#define BATTERY_PIN 1

View File

@@ -1,5 +1,5 @@
[env:heltec_ht-ct62]
board = esp32-c3-devkitm-1
board = heltec_wireless_stick_lite
board_build.mcu = esp32c3
build_flags =
${common.build_flags}

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 12
#define RADIO_DIO1_PIN 14
#define RADIO_BUSY_PIN 13
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_14
// Display
#define HAS_DISPLAY

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 12
#define RADIO_DIO1_PIN 14
#define RADIO_BUSY_PIN 13
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_14
// Display
#define HAS_DISPLAY

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 12
#define RADIO_DIO1_PIN 14
#define RADIO_BUSY_PIN 13
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_14
// Display
#define HAS_DISPLAY

View File

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

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 12
#define RADIO_DIO1_PIN 14
#define RADIO_BUSY_PIN 13
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_14
// Display
#define HAS_DISPLAY

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 12
#define RADIO_DIO1_PIN 14
#define RADIO_BUSY_PIN 13
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_14
// Aditional Config
#define INTERNAL_LED_PIN 35

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 12
#define RADIO_DIO1_PIN 14
#define RADIO_BUSY_PIN 13
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_14
// Display
#define HAS_DISPLAY

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 12 // SX1262 RST
#define RADIO_DIO1_PIN 14 // SX1262 DIO1
#define RADIO_BUSY_PIN 13 // SX1262 BUSY
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_14
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -11,8 +11,6 @@
#define RADIO_RST_PIN 23
#define RADIO_DIO1_PIN 33
#define RADIO_BUSY_PIN 32
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_33
// Display
#define HAS_DISPLAY

View File

@@ -9,8 +9,6 @@
#define RADIO_CS_PIN 18
#define RADIO_RST_PIN 14
#define RADIO_BUSY_PIN 26
#define RADIO_WAKEUP_PIN RADIO_BUSY_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_26
// Display
#define HAS_DISPLAY

View File

@@ -11,8 +11,6 @@
#define RADIO_RST_PIN 23
#define RADIO_DIO1_PIN 33
#define RADIO_BUSY_PIN 32
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_33
// Display
#define HAS_DISPLAY

View File

@@ -10,8 +10,6 @@
#define RADIO_RST_PIN 8
#define RADIO_DIO1_PIN 33
#define RADIO_BUSY_PIN 34
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_33
// Display
#define HAS_DISPLAY

View File

@@ -1,39 +0,0 @@
#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
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_1
// 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

@@ -1,12 +0,0 @@
[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

@@ -3,15 +3,13 @@
// 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
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_45
#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
@@ -22,17 +20,17 @@
#undef OLED_RST
// GPS
#define GPS_RX 43
#define GPS_TX 44
#define GPS_RX 43
#define GPS_TX 44
// Aditional Config
#define BATTERY_PIN 4
#define BATTERY_PIN 4
#define BOARD_POWERON 10
#define BOARD_SDCARD_CS 39
#define BOARD_BL_PIN 42
#define BOARD_POWERON 10
#define BOARD_SDCARD_CS 39
#define BOARD_BL_PIN 42
#define BOARD_I2C_SDA 18
#define BOARD_I2C_SCL 8
#define BOARD_I2C_SDA 18
#define BOARD_I2C_SCL 8
#endif

View File

@@ -18,7 +18,7 @@ debug_tool = esp-prog
build_flags =
${common.build_flags}
${common.usb_flags}
-D TTGO_T_DECK_GPS
-D TTGO_T_DECK_PLUS
-D BOARD_HAS_PSRAM
-D USER_SETUP_LOADED
-D ST7789_DRIVER

View File

@@ -3,15 +3,13 @@
// 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
#define RADIO_WAKEUP_PIN RADIO_DIO1_PIN
#define GPIO_WAKEUP_PIN GPIO_SEL_45
#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
@@ -22,18 +20,18 @@
#undef OLED_RST
// GPS
#define GPS_RX 43
#define GPS_TX 44
#define GPS_BAUDRATE 38400
#define GPS_RX 43
#define GPS_TX 44
#define GPS_BAUDRATE 38400
// Aditional Config
#define BATTERY_PIN 4
#define BATTERY_PIN 4
#define BOARD_POWERON 10
#define BOARD_SDCARD_CS 39
#define BOARD_BL_PIN 42
#define BOARD_POWERON 10
#define BOARD_SDCARD_CS 39
#define BOARD_BL_PIN 42
#define BOARD_I2C_SDA 18
#define BOARD_I2C_SCL 8
#define BOARD_I2C_SDA 18
#define BOARD_I2C_SCL 8
#endif