Merge pull request #56 from SQ2CPA/main

TNC and few more changes and fixes
This commit is contained in:
Ricardo Guzman (Richonguzman) 2024-03-22 15:28:14 -03:00 committed by GitHub
commit 0d1162786c
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
28 changed files with 963 additions and 366 deletions

View file

@ -20,7 +20,8 @@ jobs:
- "ttgo-t-beam-v1"
- "ttgo-t-beam-v1_SX1268"
- "ttgo-t-beam-v1_2_SX1262"
# - "heltec_wireless_stick_lite" # NOT FULLY TESTED
- "heltec_wireless_stick"
- "heltec_wireless_stick_lite"
steps:
- uses: actions/checkout@v3

40
.github/workflows/commit.yml vendored Normal file
View file

@ -0,0 +1,40 @@
name: Commit Test Build
on:
push:
branches:
- '*'
jobs:
build:
runs-on: ubuntu-latest
strategy:
fail-fast: false
matrix:
target:
- "ttgo-lora32-v21"
- "heltec-lora32-v2"
- "heltec_wifi_lora_32_V3"
- "ESP32_DIY_LoRa"
- "ESP32_DIY_1W_LoRa"
- "ttgo-t-beam-v1_2"
- "ttgo-t-beam-v1"
- "ttgo-t-beam-v1_SX1268"
- "ttgo-t-beam-v1_2_SX1262"
- "heltec_wireless_stick"
- "heltec_wireless_stick_lite"
steps:
- uses: actions/checkout@v3
- uses: actions/setup-python@v4
with:
python-version: "3.9"
- name: Install PlatformIO Core
run: pip install --upgrade platformio
- name: Build target
run: pio run -e ${{ matrix.target }}
- name: Build FS
run: pio run --target buildfs -e ${{ matrix.target }}

View file

@ -21,6 +21,11 @@
"digi": {
"mode": 0
},
"tnc": {
"enableServer": false,
"enableSerial": false,
"acceptOwn": false
},
"aprs_is": {
"active": false,
"passcode": "XYZVW",

View file

@ -11,101 +11,50 @@
<input type="file" accept="text/json,.json" style="display: none" />
<form autocomplete="off" action="/configuration.json" method="POST">
<nav
class="navbar bg-body-secondary shadow-sm border-bottom sticky-top"
class="navbar bg-body-secondary shadow-sm border-bottom sticky-top navbar-expand-lg"
>
<div class="container">
<a class="navbar-brand"
>CA2RXU's LoRa iGate Configuration</a
>CA2RXU's LoRa</a
>
<div class="d-flex">
<a href="/update" class="btn btn-warning mx-2"> OTA </a>
<button
class="btn btn-primary mx-2"
type="button"
id="backup"
>
Backup
</button>
<button
class="btn btn-primary mx-2"
type="button"
id="restore"
>
Restore
</button>
<button
class="btn btn-success mx-2"
type="submit"
id="save"
>
Save
</button>
<button class="navbar-toggler" type="button" data-bs-toggle="collapse" data-bs-target="#navbarColor01" aria-controls="navbarColor01" aria-expanded="false" aria-label="Toggle navigation">
<span class="navbar-toggler-icon"></span>
</button>
<div class="collapse navbar-collapse" id="navbarColor01">
<ul class="navbar-nav me-auto">
<li class="nav-item">
<a class="nav-link" href="/update">
Update <small>OTA</small>
</a>
</li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" data-bs-toggle="dropdown" href="#" role="button" aria-haspopup="true" aria-expanded="false">Backup</a>
<div class="dropdown-menu">
<a class="dropdown-item" href="#" id="backup">Download</a>
<a class="dropdown-item" href="#" id="restore">Restore</a>
</div>
</li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" data-bs-toggle="dropdown" href="#" role="button" aria-haspopup="true" aria-expanded="false">Device</a>
<div class="dropdown-menu">
<a class="dropdown-item" href="#" id="reboot">Reboot</a>
</div>
</li>
<!-- <li class="nav-item">
<a class="nav-link" href="#" id="received-packets">
Received packets
</a>
</li> -->
</ul>
<div class="d-flex">
<button class="btn btn-success my-2 my-sm-0" type="submit">Save</button>
</div>
</div>
</div>
</nav>
<div class="container">
<main>
<div class="col-10 my-5 mx-auto">
<!-- <div class="row">
<div class="d-flex align-items-center">
<img
src="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAHgAAAB4CAYAAAA5ZDbSAAAACXBIWXMAAAsTAAALEwEAmpwYAAAAAXNSR0IArs4c6QAAAARnQU1BAACxjwv8YQUAAAQ6SURBVHgB7d0/axRBGMfx50IMWPoKkpA02gUsLfZdqOCLOPBFWAliHbCUVNpaxQNrIY0WVjZaJlUsIsZ5uDu9bGb/zMwzs/PM/L7wIG4Ocflwl7ndvVsihBBCmTajunpk5uHG33+aOSGkvhdmLs1cW+bKzDEhle2a+UZ22Pacrx6PlMRYXc/arrkkIKvIBxfISgrBBXLmSeACOdMkcYGcWTFwgZxJMXGBPHEpcIE8USlxgSzcbGD2KD0ukIXKGRfIAuWOC+TANOACOSAtuEAemQ10a2P2KV9cIA+0ZZltMzurOaT8cYHcUx+wJlwgd9QFrBEXyJZswAekFxfIrdq4GhZUQO7Itlq+QzoXVEC21AdcIm51yF3AJeNWhWwDLmFBBeRVmg4/Atmj2nGLR/bCbZrm2qWx/+7Ekwx5i9LGO/XFzF2qO97/r5QAOSUwcG+WBDkVMHDtRUdOAcz/ed4J4NqLihwbGLjjioYcExi4bkVBjgUMXL/EkWMAAzcsUWRpYODKJIYsCQxc2USQpYCBG6dgZAlg4MYtCDkUGLhp8kYOAQZu2ryQfYGT4S7PAKJVzsg+wEmfubNZbd+XOpgTsiswXpbzaDSyCzBw82oU8lhg4ObZIPIYYODmXS/yEDBwdcQ+72w/6AMGrq6OaHnLghv1AQNXX6/bG7qAPxNwNbbf3mAD5qf5EaEisgG/IVRMNuA9QsVkA94mpLWP7Q2pP5uE4vayvQHA5bQw86m90Qb8i5C22Kyx/cAG/IGQphj3ftcPbcBzM78JaWiN+73rATZgfvAzWn4SHeXbIC7Xtcg6MfOUgJxro3C5vlU0kPNsNC439DYJyHnlhMuNeR8M5DxyxuXGHugA8rR54XIuR7KAPE3euJzroUogpy0Il/M5Fg3kNAXjcr4nG4AcNxFcLuTc78nqz7e0/A7KLDo9PbV+nkn6Q2xnZ2c0n88pQmK4XOjJ/eyQm6YhxYnichLng/FyLZM4Lid1wh/IYUXB5SSv6ACyX9FwOelLdoDsVlRcLsY1WUAeV3RcLtZFd0Duj3EfUGRcLuZVlUC2lwyXi32Re/D75IuLC1osFtYDFXxAo73dts21MV/8wgc6PEqKm7LHZv5QnndASTV8p5U9unl7oaJ6QvUi23CLA+YdqhGZcQ/Jfmu/olrvVE3Ia9wdqgB4sxp+JzPuPv2/+XV1lYzcxq32Q34lvlzbcKsF5h0vCZlxD+g2btXApSCvF1TbBOB/ba4oNSOvn7lr3KpWzC5pXHgVf4RKOk3P5CqOUEmn5eW6CxfAA2n4ndyHC+AR5YwMXOFyWngx7i4h8XJABm7kpkQGbqKmQAZu4lIiA3eiUiADd+JiIgM3k2IgAzezJJGBm2kSyMDNvBBk4CrJBxm4ynJB/kHAVRnf3OucumGvzBxTBZV+eouhn5u5t7HtvZlXhBBCCCEUsb+qGDWF0d8l5AAAAABJRU5ErkJggg=="
width="60"
height="60"
class="me-2"
/>
<div>
<label for="stationMode" class="form-label"
>Station Mode</label
>
<select
class="form-select form-select-lg"
name="stationMode"
id="stationMode"
>
<option value="1">
Rx (only) iGate with black diamond +
"L" as symbol.
</option>
<option value="2">
[HAM only] Rx + Tx iGate with red
diamond + "L" as symbol.
</option>
<option value="3">
[HAM only] Digipeater simplex,
green-star + "L" as symbol.
</option>
<option value="4">
[HAM only] Digipeater split
frequency, green-star + "L" as
symbol.
</option>
<option value="5">
[HAM only] Rx + Tx iGate connected
to WiFi, Digipeater mode as fallback
</option>
</select>
<div class="form-check form-switch mt-3">
<input
type="checkbox"
name="bme.active"
id="bme.active"
class="form-check-input"
/>
<label
for="bme.active"
class="form-check-label"
><b>Activate Wx Telemetry</b>
<small
>Requires a BME/BMP280 or BME680
sensor installed</small
></label
>
</div>
</div>
</div>
</div> -->
<div class="row my-5 d-flex align-items-top">
<div class="col-lg-3 col-sm-12">
<h5>
@ -174,8 +123,7 @@
name="beacon.path"
id="beacon.path"
class="form-control"
placeholder="WIDE1-1"
required=""
placeholder="We prefer WIDE1-1"
/>
</div>
<div class="col-8 mt-3">
@ -540,6 +488,91 @@
</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-database-fill"
viewBox="0 0 16 16"
>
<path
d="M3.904 1.777C4.978 1.289 6.427 1 8 1s3.022.289 4.096.777C13.125 2.245 14 2.993 14 4s-.875 1.755-1.904 2.223C11.022 6.711 9.573 7 8 7s-3.022-.289-4.096-.777C2.875 5.755 2 5.007 2 4s.875-1.755 1.904-2.223"
/>
<path
d="M2 6.161V7c0 1.007.875 1.755 1.904 2.223C4.978 9.71 6.427 10 8 10s3.022-.289 4.096-.777C13.125 8.755 14 8.007 14 7v-.839c-.457.432-1.004.751-1.49.972C11.278 7.693 9.682 8 8 8s-3.278-.307-4.51-.867c-.486-.22-1.033-.54-1.49-.972"
/>
<path
d="M2 9.161V10c0 1.007.875 1.755 1.904 2.223C4.978 12.711 6.427 13 8 13s3.022-.289 4.096-.777C13.125 11.755 14 11.007 14 10v-.839c-.457.432-1.004.751-1.49.972-1.232.56-2.828.867-4.51.867s-3.278-.307-4.51-.867c-.486-.22-1.033-.54-1.49-.972"
/>
<path
d="M2 12.161V13c0 1.007.875 1.755 1.904 2.223C4.978 15.711 6.427 16 8 16s3.022-.289 4.096-.777C13.125 14.755 14 14.007 14 13v-.839c-.457.432-1.004.751-1.49.972-1.232.56-2.828.867-4.51.867s-3.278-.307-4.51-.867c-.486-.22-1.033-.54-1.49-.972"
/>
</svg>
TNC
</h5>
<small
>TNC and KISS configuration</small
>
</div>
<div class="col-lg-9 col-sm-12">
<div class="row">
<div class="col-12">
<div class="form-check form-switch">
<div class="form-text">
Server will be available at port <strong>8001</strong>
</div>
<input
type="checkbox"
name="tnc.enableServer"
id="tnc.enableServer"
class="form-check-input"
/>
<label
for="tnc.enableServer"
class="form-label"
>Enable TNC server</label
>
</div>
</div>
<div class="col-12">
<div class="form-check form-switch">
<input
type="checkbox"
name="tnc.enableSerial"
id="tnc.enableSerial"
class="form-check-input"
/>
<label
for="tnc.enableSerial"
class="form-label"
>Enable Serial KISS</label
>
</div>
</div>
<div class="col-12">
<div class="form-check form-switch">
<input
type="checkbox"
name="tnc.acceptOwn"
id="tnc.acceptOwn"
class="form-check-input"
/>
<label
for="tnc.acceptOwn"
class="form-label"
>Accept own frames via KISS</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>
@ -680,39 +713,6 @@
</select>
</div>
</div>
<!-- <div class="row mt-3">
<div class="col-6">
<div class="form-check form-switch">
<input
type="checkbox"
name="beacon.igateSendsLoRaBeacon"
id="beacon.igateSendsLoRaBeacon"
class="form-check-input"
/>
<label
for="beacon.igateSendsLoRaBeacon"
class="form-label"
>IGate sends LoRa beacon</label
>
</div>
</div>
<div class="col-6">
<div class="form-check form-switch">
<input
type="checkbox"
name="beacon.igateRepeatLoRaPackets"
id="beacon.igateRepeatLoRaPackets"
class="form-check-input"
/>
<label
for="beacon.igateRepeatLoRaPackets"
class="form-label"
>IGate repeat LoRa
packets</label
>
</div>
</div>
</div> -->
</div>
</div>
<hr />
@ -837,7 +837,7 @@
</div>
<div class="col-lg-9 col-sm-12">
<div class="row">
<div class="col-12">
<div class="col-6">
<div class="form-check form-switch">
<input
type="checkbox"
@ -852,6 +852,9 @@
>
</div>
</div>
<div class="col-6 d-grid gap-2">
<button class="btn btn-primary" id="send-beacon">Send beacon now</button>
</div>
</div>
<div class="row mt-3">
<div class="col-12">
@ -900,7 +903,6 @@
name="other.externalVoltageMeasurement"
id="other.externalVoltageMeasurement"
class="form-check-input"
disabled
/>
<label
for="other.externalVoltageMeasurement"
@ -916,7 +918,6 @@
id="other.externalVoltagePin"
value="34"
class="form-control"
disabled
/>
<label
for="other.externalVoltagePin"
@ -1358,6 +1359,15 @@
</div>
</div>
</div>
<div class="position-fixed bottom-0 end-0 p-3" style="z-index: 11">
<div id="toast" class="toast hide" role="alert" aria-live="assertive" aria-atomic="true">
<div class="toast-header">
<strong class="me-auto">System Message</strong>
<button type="button" class="btn-close" data-bs-dismiss="toast" aria-label="Close"></button>
</div>
<div class="toast-body text-center"></div>
</div>
</div>
</body>
<script src="/bootstrap.js"></script>
<script src="/script.js"></script>

View file

@ -86,7 +86,7 @@ function loadSettings(settings) {
document.querySelector(".list-networks").innerHTML = "";
// Networks
const wifiNetworks = settings.wifi.AP;
const wifiNetworks = settings.wifi.AP || [];
const networksContainer = document.querySelector(".list-networks");
let networkCount = 0;
@ -150,6 +150,11 @@ function loadSettings(settings) {
// document.getElementById("digi.longitude").value = settings.digi.longitude;
document.getElementById("digi.mode").value = settings.digi.mode;
// TNC
document.getElementById("tnc.enableServer").checked = settings.tnc.enableServer;
document.getElementById("tnc.enableSerial").checked = settings.tnc.enableSerial;
document.getElementById("tnc.acceptOwn").checked = settings.tnc.acceptOwn;
// OTA
document.getElementById("ota.username").value = settings.ota.username;
document.getElementById("ota.password").value = settings.ota.password;
@ -162,6 +167,7 @@ function loadSettings(settings) {
settings.other.sendBatteryVoltage;
document.getElementById("other.externalVoltageMeasurement").checked =
settings.other.externalVoltageMeasurement;
document.getElementById("other.externalVoltagePin").value =
settings.other.externalVoltagePin;
// document.getElementById("beacon.igateSendsLoRaBeacon").value =
@ -207,8 +213,33 @@ function loadSettings(settings) {
updateImage();
refreshSpeedStandard();
toggleFields();
}
function showToast(message) {
const el = document.querySelector('#toast');
el.querySelector('.toast-body').innerHTML = message;
(new bootstrap.Toast(el)).show();
}
document.getElementById('send-beacon').addEventListener('click', function (e) {
e.preventDefault();
fetch("/action?type=send-beacon", { method: "POST" });
showToast("Your beacon will be sent in a moment. <br> <u>This action will be ignored if you have APRSIS and LoRa TX disabled!</u>");
});
document.getElementById('reboot').addEventListener('click', function (e) {
e.preventDefault();
fetch("/action?type=reboot", { method: "POST" });
showToast("Your device will be rebooted in a while");
});
const bmeCheckbox = document.querySelector("input[name='bme.active']");
const stationModeSelect = document.querySelector("select[name='stationMode']");
@ -239,9 +270,6 @@ function updateImage() {
}
function toggleFields() {
const sendBatteryVoltageCheckbox = document.querySelector(
'input[name="other.sendBatteryVoltage"]'
);
const externalVoltageMeasurementCheckbox = document.querySelector(
'input[name="other.externalVoltageMeasurement"]'
);
@ -249,15 +277,10 @@ function toggleFields() {
'input[name="other.externalVoltagePin"]'
);
externalVoltageMeasurementCheckbox.disabled =
!sendBatteryVoltageCheckbox.checked;
externalVoltagePinInput.disabled =
!externalVoltageMeasurementCheckbox.checked;
}
const sendBatteryVoltageCheckbox = document.querySelector(
'input[name="other.sendBatteryVoltage"]'
);
const externalVoltageMeasurementCheckbox = document.querySelector(
'input[name="other.externalVoltageMeasurement"]'
);
@ -265,10 +288,8 @@ const externalVoltagePinInput = document.querySelector(
'input[name="other.externalVoltagePin"]'
);
sendBatteryVoltageCheckbox.addEventListener("change", function () {
externalVoltageMeasurementCheckbox.disabled = !this.checked;
externalVoltagePinInput.disabled =
!externalVoltageMeasurementCheckbox.checked;
externalVoltageMeasurementCheckbox.addEventListener("change", function () {
externalVoltagePinInput.disabled = !this.checked;
});
document.querySelector(".new button").addEventListener("click", function () {
@ -378,8 +399,6 @@ document.getElementById("action.speed").addEventListener("change", function () {
}
});
toggleFields();
const form = document.querySelector("form");
const saveModal = new bootstrap.Modal(document.getElementById("saveModal"), {
@ -430,4 +449,4 @@ form.addEventListener("submit", async (event) => {
setTimeout(checkConnection, 2000);
});
fetchSettings();
fetchSettings();

View file

@ -0,0 +1,8 @@
.alert-fixed {
position:fixed;
top: 0px;
left: 0px;
width: 100%;
z-index:9999;
border-radius:0px
}

View file

@ -88,8 +88,7 @@ board = heltec_wifi_lora_32_V3
board_build.mcu = esp32s3
build_flags = -Werror -Wall -DHELTEC_WS -DELEGANTOTA_USE_ASYNC_WEBSERVER=1
;[env:heltec_wireless_stick_lite]
;board = heltec_wireless_stick_lite
;board_build.mcu = esp32c3
;board_build.f_cpu = 240000000L
;build_flags = -Werror -Wall -DHELTEC_WSL -DELEGANTOTA_USE_ASYNC_WEBSERVER=1
[env:heltec_wireless_stick_lite]
board = heltec_wireless_stick_lite
board_build.mcu = esp32c3
build_flags = -Werror -Wall -DHELTEC_WSL -DELEGANTOTA_USE_ASYNC_WEBSERVER=1

View file

@ -14,10 +14,11 @@
#include "gps_utils.h"
#include "bme_utils.h"
#include "web_utils.h"
#include "tnc_utils.h"
#include "display.h"
#include "utils.h"
#include <ElegantOTA.h>
#include "battery_utils.h"
Configuration Config;
WiFiClient espClient;
@ -41,6 +42,8 @@ bool WiFiConnected = false;
bool WiFiAutoAPStarted = false;
long WiFiAutoAPTime = false;
uint32_t lastBatteryCheck = 0;
uint32_t bmeLastReading = -60000;
String batteryVoltage;
@ -55,7 +58,7 @@ String firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seven
void setup() {
Serial.begin(115200);
#if defined(TTGO_T_LORA32_V2_1) || defined(HELTEC_V2)
#if defined(TTGO_T_LORA32_V2_1) || defined(HELTEC_V2) || defined(HELTEC_WSL)
pinMode(batteryPin, INPUT);
#endif
#ifdef HAS_INTERNAL_LED
@ -82,6 +85,7 @@ void setup() {
SYSLOG_Utils::setup();
BME_Utils::setup();
WEB_Utils::setup();
TNC_Utils::setup();
}
void loop() {
@ -92,6 +96,10 @@ void loop() {
return; // Don't process IGate and Digi during OTA update
}
if (BATTERY_Utils::checkIfShouldSleep()) {
ESP.deepSleep(1800000000); // 30 min sleep (60s = 60e6)
}
thirdLine = Utils::getLocalIP();
WIFI_Utils::checkWiFi(); // Always use WiFi, not related to IGate/Digi mode
@ -101,6 +109,8 @@ void loop() {
APRS_IS_Utils::connect();
}
TNC_Utils::loop();
Utils::checkDisplayInterval();
Utils::checkBeaconInterval();
@ -112,12 +122,22 @@ void loop() {
APRS_IS_Utils::checkStatus(); // Need that to update display, maybe split this and send APRSIS status to display func?
if (Config.aprs_is.active) { // If APRSIS enabled
APRS_IS_Utils::loop(packet); // Send received packet to APRSIS
}
if (packet != "") {
if (Config.aprs_is.active) { // If APRSIS enabled
APRS_IS_Utils::loop(packet); // Send received packet to APRSIS
}
if (Config.digi.mode == 2) { // If Digi enabled
DIGI_Utils::loop(packet); // Send received packet to Digi
if (Config.digi.mode == 2) { // If Digi enabled
DIGI_Utils::loop(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
}
}
show_display(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);

View file

@ -28,7 +28,7 @@ namespace APRS_IS_Utils {
espClient.print(line + "\r\n");
}
void connect(){
void connect() {
int count = 0;
String aprsauth;
Serial.print("Connecting to APRS-IS ... ");
@ -44,8 +44,9 @@ namespace APRS_IS_Utils {
}
if (count == 20) {
Serial.println("Tried: " + String(count) + " FAILED!");
} else {
Serial.println("Connected!\n(Server: " + String(Config.aprs_is.server) + " / Port: " + String(Config.aprs_is.port) +")");
}
else {
Serial.println("Connected!\n(Server: " + String(Config.aprs_is.server) + " / Port: " + String(Config.aprs_is.port) + ")");
// String filter = "t/m/" + Config.callsign + "/" + (String)Config.aprs_is.reportingDistance;
@ -58,8 +59,9 @@ namespace APRS_IS_Utils {
void checkStatus() {
String wifiState, aprsisState;
if (WiFi.status() == WL_CONNECTED) {
wifiState = "OK";
} else {
wifiState = "OK";
}
else {
wifiState = "AP";
if (!Config.display.alwaysOn) {
@ -70,10 +72,12 @@ namespace APRS_IS_Utils {
}
if (!Config.aprs_is.active) {
aprsisState = "OFF";
} else if (espClient.connected()) {
aprsisState = "OK";
} else {
aprsisState = "OFF";
}
else if (espClient.connected()) {
aprsisState = "OK";
}
else {
aprsisState = "--";
if (!Config.display.alwaysOn) {
@ -89,25 +93,27 @@ namespace APRS_IS_Utils {
String createPacket(String packet) {
if (!(Config.aprs_is.active && Config.digi.mode == 0)) { // Check if NOT only IGate
return packet.substring(3, packet.indexOf(":")) + ",qAR," + Config.callsign + packet.substring(packet.indexOf(":"));
} else {
}
else {
return packet.substring(3, packet.indexOf(":")) + ",qAO," + Config.callsign + packet.substring(packet.indexOf(":"));
}
}
bool processReceivedLoRaMessage(String sender, String packet) {
String ackMessage, receivedMessage;
if (packet.indexOf("{")>0) { // ack?
ackMessage = "ack" + packet.substring(packet.indexOf("{")+1);
if (packet.indexOf("{") > 0) { // ack?
ackMessage = "ack" + packet.substring(packet.indexOf("{") + 1);
ackMessage.trim();
delay(4000);
//Serial.println(ackMessage);
for(int i = sender.length(); i < 9; i++) {
for (int i = sender.length(); i < 9; i++) {
sender += ' ';
}
LoRa_Utils::sendNewPacket("APRS", Config.callsign + ">APLRG1,RFONLY,WIDE1-1::" + sender + ":" + ackMessage);
receivedMessage = packet.substring(packet.indexOf(":")+1, packet.indexOf("{"));
} else {
receivedMessage = packet.substring(packet.indexOf(":")+1);
receivedMessage = packet.substring(packet.indexOf(":") + 1, packet.indexOf("{"));
}
else {
receivedMessage = packet.substring(packet.indexOf(":") + 1);
}
if (receivedMessage.indexOf("?") == 0) {
delay(2000);
@ -116,9 +122,10 @@ namespace APRS_IS_Utils {
}
LoRa_Utils::sendNewPacket("APRS", QUERY_Utils::process(receivedMessage, sender, "LoRa"));
lastScreenOn = millis();
show_display(firstLine, secondLine, thirdLine, fourthLine, fifthLine, "Callsign = " + sender, "TYPE --> QUERY", 0);
show_display(firstLine, secondLine, thirdLine, fourthLine, fifthLine, "Callsign = " + sender, "TYPE --> QUERY", 0);
return true;
} else {
}
else {
return false;
}
}
@ -127,24 +134,16 @@ namespace APRS_IS_Utils {
bool queryMessage = false;
String aprsPacket, Sender, AddresseeAndMessage, Addressee;
if (packet != "") {
#ifdef TextSerialOutputForApp
Serial.println(packet.substring(3));
#else
Serial.print("Received Lora Packet : " + String(packet));
#endif
if ((packet.substring(0,3) == "\x3c\xff\x01") && (packet.indexOf("TCPIP") == -1) && (packet.indexOf("NOGATE") == -1) && (packet.indexOf("RFONLY") == -1)) {
#ifndef TextSerialOutputForApp
Serial.print(" ---> APRS LoRa Packet!");
#endif
Sender = packet.substring(3,packet.indexOf(">"));
if ((packet.substring(0, 3) == "\x3c\xff\x01") && (packet.indexOf("TCPIP") == -1) && (packet.indexOf("NOGATE") == -1) && (packet.indexOf("RFONLY") == -1)) {
Sender = packet.substring(3, packet.indexOf(">"));
STATION_Utils::updateLastHeard(Sender);
//STATION_Utils::updatePacketBuffer(packet);
Utils::typeOfPacket(aprsPacket, "LoRa-APRS");
if (Sender != Config.callsign) { // avoid listening yourself by digirepeating
AddresseeAndMessage = packet.substring(packet.indexOf("::")+2);
Addressee = AddresseeAndMessage.substring(0,AddresseeAndMessage.indexOf(":"));
AddresseeAndMessage = packet.substring(packet.indexOf("::") + 2);
Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":"));
Addressee.trim();
if (packet.indexOf("::") > 10 && Addressee == Config.callsign) { // its a message for me!
queryMessage = processReceivedLoRaMessage(Sender, AddresseeAndMessage);
}
@ -155,47 +154,41 @@ namespace APRS_IS_Utils {
}
lastScreenOn = millis();
upload(aprsPacket);
#ifndef TextSerialOutputForApp
Serial.println(" ---> Uploaded to APRS-IS");
#endif
Utils::println("---> Uploaded to APRS-IS");
STATION_Utils::updateLastHeard(Sender);
Utils::typeOfPacket(aprsPacket, "LoRa-APRS");
show_display(firstLine, secondLine, thirdLine, fourthLine, fifthLine, sixthLine, seventhLine, 0);
}
}
} else {
#ifndef TextSerialOutputForApp
Serial.println(" ---> LoRa Packet Ignored (first 3 bytes or TCPIP/NOGATE/RFONLY)\n");
#endif
}
}
}
}
void processAPRSISPacket(String packet) {
String Sender, AddresseeAndMessage, Addressee, receivedMessage;
if (!packet.startsWith("#")){
if (packet.indexOf("::")>0) {
Sender = packet.substring(0,packet.indexOf(">"));
AddresseeAndMessage = packet.substring(packet.indexOf("::")+2);
if (!packet.startsWith("#")) {
if (packet.indexOf("::") > 0) {
Sender = packet.substring(0, packet.indexOf(">"));
AddresseeAndMessage = packet.substring(packet.indexOf("::") + 2);
Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":"));
Addressee.trim();
if (Addressee == Config.callsign) { // its for me!
if (AddresseeAndMessage.indexOf("{")>0) { // ack?
String ackMessage = "ack" + AddresseeAndMessage.substring(AddresseeAndMessage.indexOf("{")+1);
if (AddresseeAndMessage.indexOf("{") > 0) { // ack?
String ackMessage = "ack" + AddresseeAndMessage.substring(AddresseeAndMessage.indexOf("{") + 1);
ackMessage.trim();
delay(4000);
//Serial.println(ackMessage);
for(int i = Sender.length(); i < 9; i++) {
for (int i = Sender.length(); i < 9; i++) {
Sender += ' ';
}
String ackPacket = Config.callsign + ">APLRG1,TCPIP,qAC::" + Sender + ":" + ackMessage;// + "\n";
upload(ackPacket);
receivedMessage = AddresseeAndMessage.substring(AddresseeAndMessage.indexOf(":")+1, AddresseeAndMessage.indexOf("{"));
} else {
receivedMessage = AddresseeAndMessage.substring(AddresseeAndMessage.indexOf(":")+1);
receivedMessage = AddresseeAndMessage.substring(AddresseeAndMessage.indexOf(":") + 1, AddresseeAndMessage.indexOf("{"));
}
else {
receivedMessage = AddresseeAndMessage.substring(AddresseeAndMessage.indexOf(":") + 1);
}
if (receivedMessage.indexOf("?") == 0) {
#ifndef TextSerialOutputForApp
Serial.println("Received Query APRS-IS : " + packet);
#endif
Utils::println("Received Query APRS-IS : " + packet);
String queryAnswer = QUERY_Utils::process(receivedMessage, Sender, "APRSIS");
//Serial.println("---> QUERY Answer : " + queryAnswer.substring(0,queryAnswer.indexOf("\n")));
if (!Config.display.alwaysOn) {
@ -204,19 +197,18 @@ namespace APRS_IS_Utils {
lastScreenOn = millis();
delay(500);
upload(queryAnswer);
SYSLOG_Utils::log("APRSIS Tx", queryAnswer,0,0,0);
SYSLOG_Utils::log("APRSIS Tx", queryAnswer, 0, 0, 0);
fifthLine = "APRS-IS ----> APRS-IS";
sixthLine = Config.callsign;
for (int j=sixthLine.length();j<9;j++) {
for (int j = sixthLine.length();j < 9;j++) {
sixthLine += " ";
}
sixthLine += "> " + Sender;
seventhLine = "QUERY = " + receivedMessage;
}
} else {
#ifndef TextSerialOutputForApp
Serial.print("Received from APRS-IS : " + packet);
#endif
}
else {
Utils::print("Received from APRS-IS : " + packet);
if (Config.aprs_is.toRF && STATION_Utils::wasHeard(Addressee)) {
LoRa_Utils::sendNewPacket("APRS", LoRa_Utils::generatePacket(packet));

View file

@ -4,13 +4,6 @@
#include <Arduino.h>
//#define TextSerialOutputForApp
/* uncomment the previous line to get text from Serial-Output over USB into PC for:
- PinPoint App ( https://www.pinpointaprs.com )
- APRSIS32 App ( http://aprsisce.wikidot.com )
*/
namespace APRS_IS_Utils {
void upload(String line);

View file

@ -2,7 +2,13 @@
#include "configuration.h"
#include "pins_config.h"
// Uncomment if you want to monitor voltage and sleep if voltage is too low (<3.1V)
#define LOW_VOLTAGE_CUTOFF
float cutOffVoltage = 3.1;
extern Configuration Config;
extern uint32_t lastBatteryCheck;
float adcReadingTransformation = (3.3/4095);
float voltageDividerCorrection = 0.288;
@ -16,11 +22,15 @@ float multiplyCorrection = 0.035;
namespace BATTERY_Utils {
float mapVoltage(float voltage, float in_min, float in_max, float out_min, float out_max) {
return (voltage - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
float checkBattery() {
int sample;
int sampleSum = 0;
for (int i=0; i<100; i++) {
#if defined(TTGO_T_LORA32_V2_1) || defined(HELTEC_V2)
#if defined(TTGO_T_LORA32_V2_1) || defined(HELTEC_V2) || defined(HELTEC_WSL)
sample = analogRead(batteryPin);
#endif
#if defined(HELTEC_V3) || defined(ESP32_DIY_LoRa) || defined(ESP32_DIY_1W_LoRa)
@ -29,7 +39,12 @@ namespace BATTERY_Utils {
sampleSum += sample;
delayMicroseconds(50);
}
return (2 * (sampleSum/100) * adcReadingTransformation) + voltageDividerCorrection;
float voltage = (2 * (sampleSum/100) * adcReadingTransformation) + voltageDividerCorrection;
return voltage; // raw voltage without mapping
// return mapVoltage(voltage, 3.34, 4.71, 3.0, 4.2); // mapped voltage
}
float checkExternalVoltage() {
@ -40,7 +55,28 @@ namespace BATTERY_Utils {
sampleSum += sample;
delayMicroseconds(50);
}
return ((((sampleSum/100)* adcReadingTransformation) + readingCorrection) * ((R1+R2)/R2)) - multiplyCorrection;
float voltage = ((((sampleSum/100)* adcReadingTransformation) + readingCorrection) * ((R1+R2)/R2)) - multiplyCorrection;
return voltage; // raw voltage without mapping
// return mapVoltage(voltage, 5.05, 6.32, 4.5, 5.5); // mapped voltage
}
bool checkIfShouldSleep() {
#ifdef LOW_VOLTAGE_CUTOFF
if (lastBatteryCheck == 0 || millis() - lastBatteryCheck >= 15 * 60 * 1000) {
lastBatteryCheck = millis();
float voltage = checkBattery();
if (voltage < cutOffVoltage) {
return true;
}
}
#endif
return false;
}
}

View file

@ -8,6 +8,7 @@ namespace BATTERY_Utils {
float checkBattery();
float checkExternalVoltage();
bool checkIfShouldSleep();
}

View file

@ -48,6 +48,10 @@ void Configuration::writeFile() {
// data["digi"]["latitude"] = digi.latitude;
// data["digi"]["longitude"] = digi.longitude;
data["tnc"]["enableServer"] = tnc.enableServer;
data["tnc"]["enableSerial"] = tnc.enableSerial;
data["tnc"]["acceptOwn"] = tnc.acceptOwn;
data["aprs_is"]["active"] = aprs_is.active;
data["aprs_is"]["passcode"] = aprs_is.passcode;
data["aprs_is"]["server"] = aprs_is.server;
@ -152,6 +156,10 @@ bool Configuration::readFile() {
ota.username = data["ota"]["username"].as<String>();
ota.password = data["ota"]["password"].as<String>();
tnc.enableServer = data["tnc"]["enableServer"].as<bool>();
tnc.enableSerial = data["tnc"]["enableSerial"].as<bool>();
tnc.acceptOwn = data["tnc"]["acceptOwn"].as<bool>();
int stationMode = data["stationMode"].as<int>(); // deprecated but need to specify config version
if (stationMode == 0) {
@ -279,6 +287,10 @@ void Configuration::init() {
// digi.latitude = 0.0; // deprecated
// digi.longitude = 0.0; // deprecated
tnc.enableServer = false;
tnc.enableSerial = false;
tnc.acceptOwn = false;
aprs_is.active = false; // new
aprs_is.passcode = "XYZVW";
aprs_is.server = "rotate.aprs2.net";

View file

@ -73,6 +73,13 @@ public:
bool turn180;
};
class TNC {
public:
bool enableServer;
bool enableSerial;
bool acceptOwn;
};
class SYSLOG {
public:
bool active;
@ -111,6 +118,7 @@ public:
WiFi_Auto_AP wifiAutoAP;
Beacon beacon; // new
DIGI digi;
TNC tnc; // new
APRS_IS aprs_is;
LoraModule loramodule;
Display display;

View file

@ -26,28 +26,32 @@ namespace DIGI_Utils {
String generateDigiRepeatedPacket(String packet, String callsign) {
String sender, temp0, tocall, path;
sender = packet.substring(0,packet.indexOf(">"));
temp0 = packet.substring(packet.indexOf(">")+1,packet.indexOf(":"));
sender = packet.substring(0, packet.indexOf(">"));
temp0 = packet.substring(packet.indexOf(">") + 1, packet.indexOf(":"));
if (temp0.indexOf(",") > 2) {
tocall = temp0.substring(0,temp0.indexOf(","));
path = temp0.substring(temp0.indexOf(",")+1,temp0.indexOf(":"));
if (path.indexOf("WIDE1-")>=0) {
String hop = path.substring(path.indexOf("WIDE1-")+6, path.indexOf("WIDE1-")+7);
if (hop.toInt()>=1 && hop.toInt()<=7) {
if (hop.toInt()==1) {
tocall = temp0.substring(0, temp0.indexOf(","));
path = temp0.substring(temp0.indexOf(",") + 1, temp0.indexOf(":"));
if (path.indexOf("WIDE1-") >= 0) {
String hop = path.substring(path.indexOf("WIDE1-") + 6, path.indexOf("WIDE1-") + 7);
if (hop.toInt() >= 1 && hop.toInt() <= 7) {
if (hop.toInt() == 1) {
path.replace("WIDE1-1", callsign + "*");
} else {
path.replace("WIDE1-" + hop , callsign + "*,WIDE1-" + String(hop.toInt()-1));
}
else {
path.replace("WIDE1-" + hop, callsign + "*,WIDE1-" + String(hop.toInt() - 1));
}
String repeatedPacket = sender + ">" + tocall + "," + path + packet.substring(packet.indexOf(":"));
return repeatedPacket;
} else {
}
else {
return "";
}
} else {
}
else {
return "";
}
} else {
}
else {
return "";
}
}
@ -56,34 +60,29 @@ namespace DIGI_Utils {
bool queryMessage = false;
String loraPacket, Sender, AddresseeAndMessage, Addressee;
if (packet != "") {
Serial.print("Received Lora Packet : " + String(packet));
if (packet.substring(0, 3) == "\x3c\xff\x01") {
Serial.println(" ---> APRS LoRa Packet");
Sender = packet.substring(3,packet.indexOf(">"));
if ((packet.substring(0, 3) == "\x3c\xff\x01") && (packet.indexOf("NOGATE") == -1)) {
if (Sender != Config.callsign) {
STATION_Utils::updateLastHeard(Sender);
//STATION_Utils::updatePacketBuffer(packet);
String sender = packet.substring(3, packet.indexOf(">"));
STATION_Utils::updateLastHeard(sender);
// STATION_Utils::updatePacketBuffer(packet);
Utils::typeOfPacket(packet.substring(3), "Digi");
AddresseeAndMessage = packet.substring(packet.indexOf("::")+2);
Addressee = AddresseeAndMessage.substring(0,AddresseeAndMessage.indexOf(":"));
AddresseeAndMessage = packet.substring(packet.indexOf("::") + 2);
Addressee = AddresseeAndMessage.substring(0, AddresseeAndMessage.indexOf(":"));
Addressee.trim();
if (packet.indexOf("::") > 10 && Addressee == Config.callsign) { // its a message for me!
queryMessage = APRS_IS_Utils::processReceivedLoRaMessage(Sender,AddresseeAndMessage);
queryMessage = APRS_IS_Utils::processReceivedLoRaMessage(Sender, AddresseeAndMessage);
}
if (!queryMessage && packet.indexOf("WIDE1-") > 10 && Config.digi.mode == 2) { // If should repeat packet (WIDE1 Digi)
loraPacket = generateDigiRepeatedPacket(packet.substring(3), Config.callsign);
if (loraPacket != "") {
delay(500);
Serial.println(loraPacket);
LoRa_Utils::sendNewPacket("APRS", loraPacket);
display_toggle(true);
lastScreenOn = millis();
}
}
}
} /*else {
Serial.println(" ---> LoRa Packet Ignored (first 3 bytes or NOGATE)\n");
}*/
}
}
}
}
}

View file

@ -5,11 +5,14 @@
#include "pins_config.h"
#include "display.h"
#ifdef HAS_DISPLAY
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RST);
#endif
extern Configuration Config;
void setup_display() {
#ifdef HAS_DISPLAY
Wire.begin(OLED_SDA, OLED_SCL);
if(!display.begin(SSD1306_SWITCHCAPVCC, SCREEN_ADDRESS)) {
@ -27,17 +30,21 @@ void setup_display() {
display.ssd1306_command(1);
display.display();
delay(1000);
#endif
}
void display_toggle(bool toggle) {
#ifdef HAS_DISPLAY
if (toggle) {
display.ssd1306_command(SSD1306_DISPLAYON);
} else {
display.ssd1306_command(SSD1306_DISPLAYOFF);
}
#endif
}
void show_display(String line1, int wait) {
#ifdef HAS_DISPLAY
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(1);
@ -47,9 +54,11 @@ void show_display(String line1, int wait) {
display.ssd1306_command(1);
display.display();
delay(wait);
#endif
}
void show_display(String line1, String line2, int wait) {
#ifdef HAS_DISPLAY
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(1);
@ -61,9 +70,11 @@ void show_display(String line1, String line2, int wait) {
display.ssd1306_command(1);
display.display();
delay(wait);
#endif
}
void show_display(String line1, String line2, String line3, int wait) {
#ifdef HAS_DISPLAY
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(1);
@ -77,9 +88,11 @@ void show_display(String line1, String line2, String line3, int wait) {
display.ssd1306_command(1);
display.display();
delay(wait);
#endif
}
void show_display(String line1, String line2, String line3, String line4, int wait) {
#ifdef HAS_DISPLAY
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(1);
@ -95,9 +108,11 @@ void show_display(String line1, String line2, String line3, String line4, int wa
display.ssd1306_command(1);
display.display();
delay(wait);
#endif
}
void show_display(String line1, String line2, String line3, String line4, String line5, int wait) {
#ifdef HAS_DISPLAY
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(1);
@ -115,9 +130,11 @@ void show_display(String line1, String line2, String line3, String line4, String
display.ssd1306_command(1);
display.display();
delay(wait);
#endif
}
void show_display(String line1, String line2, String line3, String line4, String line5, String line6, int wait) {
#ifdef HAS_DISPLAY
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(1);
@ -137,9 +154,11 @@ void show_display(String line1, String line2, String line3, String line4, String
display.ssd1306_command(1);
display.display();
delay(wait);
#endif
}
void show_display(String line1, String line2, String line3, String line4, String line5, String line6, String line7, int wait) {
#ifdef HAS_DISPLAY
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(2);
@ -162,4 +181,5 @@ void show_display(String line1, String line2, String line3, String line4, String
display.ssd1306_command(1);
display.display();
delay(wait);
#endif
}

View file

@ -35,7 +35,6 @@ namespace GPS_Utils {
if (abs(degrees.toFloat()) < 10) {
latitude += "0";
}
Serial.println(latitude);
if (degrees.indexOf("-") == 0) {
north_south = "S";
latitude += degrees.substring(1,degrees.indexOf("."));

23
src/kiss_protocol.h Normal file
View file

@ -0,0 +1,23 @@
#define DCD_ON 0x03
#define FEND 0xC0
#define FESC 0xDB
#define TFEND 0xDC
#define TFESC 0xDD
#define CMD_UNKNOWN 0xFE
#define CMD_DATA 0x00
#define CMD_HARDWARE 0x06
#define HW_RSSI 0x21
#define CMD_ERROR 0x90
#define ERROR_INITRADIO 0x01
#define ERROR_TXFAILED 0x02
#define ERROR_QUEUE_FULL 0x04
#define APRS_CONTROL_FIELD 0x03
#define APRS_INFORMATION_FIELD 0xf0
#define HAS_BEEN_DIGIPITED_MASK 0b10000000
#define IS_LAST_ADDRESS_POSITION_MASK 0b1

170
src/kiss_utils.cpp Normal file
View file

@ -0,0 +1,170 @@
#include <Arduino.h>
#include "kiss_protocol.h"
bool validateTNC2Frame(const String& tnc2FormattedFrame) {
return (tnc2FormattedFrame.indexOf(':') != -1) && (tnc2FormattedFrame.indexOf('>') != -1);
}
bool validateKISSFrame(const String& kissFormattedFrame) {
return kissFormattedFrame.charAt(0) == (char)FEND && kissFormattedFrame.charAt(kissFormattedFrame.length() - 1) == (char)FEND;
}
String encodeAddressAX25(String tnc2Address) {
bool hasBeenDigipited = tnc2Address.indexOf('*') != -1;
if (tnc2Address.indexOf('-') == -1) {
if (hasBeenDigipited) {
tnc2Address = tnc2Address.substring(0, tnc2Address.length() - 1);
}
tnc2Address += "-0";
}
int separatorIndex = tnc2Address.indexOf('-');
int ssid = tnc2Address.substring(separatorIndex + 1).toInt();
String kissAddress = "";
for (int i = 0; i < 6; ++i) {
char addressChar;
if (tnc2Address.length() > i && i < separatorIndex) {
addressChar = tnc2Address.charAt(i);
} else {
addressChar = ' ';
}
kissAddress += (char)(addressChar << 1);
}
kissAddress += (char)((ssid << 1) | 0b01100000 | (hasBeenDigipited ? HAS_BEEN_DIGIPITED_MASK : 0));
return kissAddress;
}
String decodeAddressAX25(const String& ax25Address, bool& isLast, bool isRelay) {
String address = "";
for (int i = 0; i < 6; ++i) {
uint8_t currentCharacter = ax25Address.charAt(i);
currentCharacter >>= 1;
if (currentCharacter != ' ') {
address += (char)currentCharacter;
}
}
auto ssidChar = (uint8_t)ax25Address.charAt(6);
bool hasBeenDigipited = ssidChar & HAS_BEEN_DIGIPITED_MASK;
isLast = ssidChar & IS_LAST_ADDRESS_POSITION_MASK;
ssidChar >>= 1;
int ssid = 0b1111 & ssidChar;
if (ssid) {
address += '-';
address += ssid;
}
if (isRelay && hasBeenDigipited) {
address += '*';
}
return address;
}
String encapsulateKISS(const String& ax25Frame, uint8_t cmd) {
String kissFrame = "";
kissFrame += (char)FEND;
kissFrame += (char)(0x0f & cmd);
for (int i = 0; i < ax25Frame.length(); ++i) {
char currentChar = ax25Frame.charAt(i);
if (currentChar == (char)FEND) {
kissFrame += (char)FESC;
kissFrame += (char)TFEND;
} else if (currentChar == (char)FESC) {
kissFrame += (char)FESC;
kissFrame += (char)TFESC;
} else {
kissFrame += currentChar;
}
}
kissFrame += (char)FEND; // end of frame
return kissFrame;
}
String decapsulateKISS(const String& frame) {
String ax25Frame = "";
for (int i = 2; i < frame.length() - 1; ++i) {
char currentChar = frame.charAt(i);
if (currentChar == (char)FESC) {
char nextChar = frame.charAt(i + 1);
if (nextChar == (char)TFEND) {
ax25Frame += (char)FEND;
} else if (nextChar == (char)TFESC) {
ax25Frame += (char)FESC;
}
i++;
} else {
ax25Frame += currentChar;
}
}
return ax25Frame;
}
String encodeKISS(const String& frame) {
String ax25Frame = "";
if (validateTNC2Frame(frame)) {
String address = "";
bool dstAddresWritten = false;
for (int p = 0; p <= frame.indexOf(':'); p++) {
char currentChar = frame.charAt(p);
if (currentChar == ':' || currentChar == '>' || currentChar == ',') {
if (!dstAddresWritten && (currentChar == ',' || currentChar == ':')) {
ax25Frame = encodeAddressAX25(address) + ax25Frame;
dstAddresWritten = true;
} else {
ax25Frame += encodeAddressAX25(address);
}
address = "";
} else {
address += currentChar;
}
}
auto lastAddressChar = (uint8_t)ax25Frame.charAt(ax25Frame.length() - 1);
ax25Frame.setCharAt(ax25Frame.length() - 1, (char)(lastAddressChar | IS_LAST_ADDRESS_POSITION_MASK));
ax25Frame += (char)APRS_CONTROL_FIELD;
ax25Frame += (char)APRS_INFORMATION_FIELD;
ax25Frame += frame.substring(frame.indexOf(':') + 1);
}
String kissFrame = encapsulateKISS(ax25Frame, CMD_DATA);
return kissFrame;
}
String decodeKISS(const String& inputFrame, bool& dataFrame) {
String frame = "";
if (validateKISSFrame(inputFrame)) {
dataFrame = inputFrame.charAt(1) == CMD_DATA;
if (dataFrame) {
String ax25Frame = decapsulateKISS(inputFrame);
bool isLast = false;
String dstAddr = decodeAddressAX25(ax25Frame.substring(0, 7), isLast, false);
String srcAddr = decodeAddressAX25(ax25Frame.substring(7, 14), isLast, false);
frame = srcAddr + ">" + dstAddr;
int digiInfoIndex = 14;
while (!isLast && digiInfoIndex + 7 < ax25Frame.length()) {
String digiAddr = decodeAddressAX25(ax25Frame.substring(digiInfoIndex, digiInfoIndex + 7), isLast, true);
frame += ',' + digiAddr;
digiInfoIndex += 7;
}
frame += ':';
frame += ax25Frame.substring(digiInfoIndex + 2);
} else {
frame += inputFrame;
}
}
return frame;
}

15
src/kiss_utils.h Normal file
View file

@ -0,0 +1,15 @@
#ifndef KISS_UTILS_H_
#define KISS_UTILS_H_
#include <Arduino.h>
String encodeAddressAX25(String tnc2Address);
String decodeAddressAX25(const String& ax25Address, bool& isLast, bool isRelay);
String encapsulateKISS(const String& ax25Frame, uint8_t cmd);
String decapsulateKISS(const String& frame);
String encodeKISS(const String& frame);
String decodeKISS(const String& inputFrame, bool& dataFrame);
#endif

View file

@ -6,10 +6,11 @@
#include "syslog_utils.h"
#include "pins_config.h"
#include "display.h"
#include "utils.h"
extern Configuration Config;
#if defined(HELTEC_V3) || defined(HELTEC_WS) || defined(TTGO_T_Beam_V1_2_SX1262)
#if defined(HELTEC_V3) || defined(HELTEC_WS) || defined(TTGO_T_Beam_V1_2_SX1262) || defined(HELTEC_WSL)
SX1262 radio = new Module(RADIO_CS_PIN, RADIO_DIO1_PIN, RADIO_RST_PIN, RADIO_BUSY_PIN);
bool transmissionFlag = true;
bool enableInterrupt = true;
@ -27,13 +28,13 @@ float snr;
namespace LoRa_Utils {
void setFlag(void) {
#ifdef HAS_SX126X
#ifdef HAS_SX126X
transmissionFlag = true;
#endif
#endif
}
void setup() {
#ifdef HAS_SX127X
#ifdef HAS_SX127X
SPI.begin(LORA_SCK, LORA_MISO, LORA_MOSI, LORA_CS);
LoRa.setPins(LORA_CS, LORA_RST, LORA_IRQ);
long freq = Config.loramodule.rxFreq;
@ -50,16 +51,17 @@ namespace LoRa_Utils {
LoRa.enableCrc();
LoRa.setTxPower(Config.loramodule.power);
Serial.print("init : LoRa Module ... done!");
#endif
#ifdef HAS_SX126X
#endif
#ifdef HAS_SX126X
SPI.begin(RADIO_SCLK_PIN, RADIO_MISO_PIN, RADIO_MOSI_PIN);
float freq = (float)Config.loramodule.rxFreq/1000000;
float freq = (float)Config.loramodule.rxFreq / 1000000;
int state = radio.begin(freq);
if (state == RADIOLIB_ERR_NONE) {
Serial.print("Initializing SX126X LoRa Module");
} else {
}
else {
Serial.println("Starting LoRa failed!");
while (true);
while (true);
}
radio.setDio1Action(setFlag);
radio.setSpreadingFactor(Config.loramodule.spreadingFactor);
@ -67,87 +69,93 @@ namespace LoRa_Utils {
radio.setBandwidth(signalBandwidth);
radio.setCodingRate(Config.loramodule.codingRate4);
radio.setCRC(true);
#if defined(ESP32_DIY_1W_LoRa)
#if defined(ESP32_DIY_1W_LoRa)
radio.setRfSwitchPins(RADIO_RXEN, RADIO_TXEN);
#endif
#if defined(HELTEC_V3) || defined(HELTEC_WS) || defined(TTGO_T_Beam_V1_0_SX1268) || defined(TTGO_T_Beam_V1_2_SX1262)
#endif
#if defined(HELTEC_V3) || defined(HELTEC_WS) || defined(TTGO_T_Beam_V1_0_SX1268) || defined(TTGO_T_Beam_V1_2_SX1262)
state = radio.setOutputPower(Config.loramodule.power + 2); // values available: 10, 17, 22 --> if 20 in tracker_conf.json it will be updated to 22.
#endif
#ifdef ESP32_DIY_1W_LoRa_GPS
#endif
#ifdef ESP32_DIY_1W_LoRa_GPS
state = radio.setOutputPower(Config.loramodule.power); // max value 20 (when 20dB in setup 30dB in output as 400M30S has Low Noise Amp)
#endif
#endif
if (state == RADIOLIB_ERR_NONE) {
Serial.println("init : LoRa Module ... done!");
} else {
}
else {
Serial.println("Starting LoRa failed!");
while (true);
}
#endif
#endif
}
void changeFreqTx() {
delay(500);
#ifdef HAS_SX127X
#ifdef HAS_SX127X
LoRa.setFrequency(Config.loramodule.txFreq);
#endif
#ifdef HAS_SX126X
float freq = (float)Config.loramodule.txFreq/1000000;
#endif
#ifdef HAS_SX126X
float freq = (float)Config.loramodule.txFreq / 1000000;
radio.setFrequency(freq);
#endif
#endif
}
void changeFreqRx() {
delay(500);
#ifdef HAS_SX127X
#ifdef HAS_SX127X
LoRa.setFrequency(Config.loramodule.rxFreq);
#endif
#ifdef HAS_SX126X
float freq = (float)Config.loramodule.rxFreq/1000000;
#endif
#ifdef HAS_SX126X
float freq = (float)Config.loramodule.rxFreq / 1000000;
radio.setFrequency(freq);
#endif
#endif
}
void sendNewPacket(const String &typeOfMessage, const String &newPacket) {
void sendNewPacket(const String& typeOfMessage, const String& newPacket) {
if (!Config.loramodule.txActive) return;
if (Config.loramodule.txFreq != Config.loramodule.rxFreq) {
changeFreqTx();
changeFreqTx();
}
#ifdef HAS_INTERNAL_LED
digitalWrite(internalLedPin,HIGH);
#endif
#ifdef HAS_SX127X
#ifdef HAS_INTERNAL_LED
digitalWrite(internalLedPin, HIGH);
#endif
#ifdef HAS_SX127X
LoRa.beginPacket();
LoRa.write('<');
if (typeOfMessage == "APRS") {
if (typeOfMessage == "APRS") {
LoRa.write(0xFF);
} else if (typeOfMessage == "LoRa") {
}
else if (typeOfMessage == "LoRa") {
LoRa.write(0xF8);
}
LoRa.write(0x01);
LoRa.write((const uint8_t *)newPacket.c_str(), newPacket.length());
LoRa.write((const uint8_t*)newPacket.c_str(), newPacket.length());
LoRa.endPacket();
#endif
#ifdef HAS_SX126X
#endif
#ifdef HAS_SX126X
int state = radio.transmit("\x3c\xff\x01" + newPacket);
if (state == RADIOLIB_ERR_NONE) {
//Serial.println(F("success!"));
} else if (state == RADIOLIB_ERR_PACKET_TOO_LONG) {
}
else if (state == RADIOLIB_ERR_PACKET_TOO_LONG) {
Serial.println(F("too long!"));
} else if (state == RADIOLIB_ERR_TX_TIMEOUT) {
}
else if (state == RADIOLIB_ERR_TX_TIMEOUT) {
Serial.println(F("timeout!"));
} else {
}
else {
Serial.print(F("failed, code "));
Serial.println(state);
}
#endif
#ifdef HAS_INTERNAL_LED
digitalWrite(internalLedPin,LOW);
#endif
SYSLOG_Utils::log("Tx", newPacket,0,0,0);
Serial.print("---> LoRa Packet Tx : ");
Serial.println(newPacket);
#endif
#ifdef HAS_INTERNAL_LED
digitalWrite(internalLedPin, LOW);
#endif
SYSLOG_Utils::log("Tx", newPacket, 0, 0, 0);
Utils::print("---> LoRa Packet Tx : ");
Utils::println(newPacket);
if (Config.loramodule.txFreq != Config.loramodule.rxFreq) {
changeFreqRx();
@ -158,71 +166,69 @@ namespace LoRa_Utils {
String firstPart, messagePart;
aprsisPacket.trim();
firstPart = aprsisPacket.substring(0, aprsisPacket.indexOf(","));
messagePart = aprsisPacket.substring(aprsisPacket.indexOf("::")+2);
messagePart = aprsisPacket.substring(aprsisPacket.indexOf("::") + 2);
return firstPart + ",TCPIP,WIDE1-1," + Config.callsign + "::" + messagePart;
}
String packetSanitization(String packet) {
//Serial.println(packet);
if (packet.indexOf("\0")>0) {
packet.replace("\0","");
if (packet.indexOf("\0") > 0) {
packet.replace("\0", "");
}
if (packet.indexOf("\r")>0) {
packet.replace("\r","");
if (packet.indexOf("\r") > 0) {
packet.replace("\r", "");
}
if (packet.indexOf("\n")>0) {
packet.replace("\n","");
if (packet.indexOf("\n") > 0) {
packet.replace("\n", "");
}
return packet;
}
String receivePacket() {
String loraPacket = "";
#ifdef HAS_SX127X
#ifdef HAS_SX127X
int packetSize = LoRa.parsePacket();
if (packetSize) {
while (LoRa.available()) {
int inChar = LoRa.read();
loraPacket += (char)inChar;
}
rssi = LoRa.packetRssi();
snr = LoRa.packetSnr();
rssi = LoRa.packetRssi();
snr = LoRa.packetSnr();
freqError = LoRa.packetFrequencyError();
}
#endif
#ifdef HAS_SX126X
#endif
#ifdef HAS_SX126X
if (transmissionFlag) {
transmissionFlag = false;
radio.startReceive();
int state = radio.readData(loraPacket);
if (state == RADIOLIB_ERR_NONE) {
if(!loraPacket.isEmpty()) {
Serial.println("LoRa Rx ---> " + loraPacket);
}
rssi = radio.getRSSI();
snr = radio.getSNR();
rssi = radio.getRSSI();
snr = radio.getSNR();
freqError = radio.getFrequencyError();
} else if (state == RADIOLIB_ERR_RX_TIMEOUT) {
}
else if (state == RADIOLIB_ERR_RX_TIMEOUT) {
// timeout occurred while waiting for a packet
} else if (state == RADIOLIB_ERR_CRC_MISMATCH) {
}
else if (state == RADIOLIB_ERR_CRC_MISMATCH) {
Serial.println(F("CRC error!"));
} else {
}
else {
Serial.print(F("failed, code "));
Serial.println(state);
}
}
#endif
#endif
if ((loraPacket.indexOf("\0")!=-1) || (loraPacket.indexOf("\r")!=-1) || (loraPacket.indexOf("\n")!=-1)) {
if ((loraPacket.indexOf("\0") != -1) || (loraPacket.indexOf("\r") != -1) || (loraPacket.indexOf("\n") != -1)) {
loraPacket = packetSanitization(loraPacket);
}
#ifndef TextSerialOutputForApp
if (loraPacket!="") {
Serial.println("(RSSI:" +String(rssi) + " / SNR:" + String(snr) + " / FreqErr:" + String(freqError) + ")");
if (loraPacket != "") {
Utils::println("<--- LoRa Packet Rx : " + loraPacket);
Utils::println("(RSSI:" + String(rssi) + " / SNR:" + String(snr) + " / FreqErr:" + String(freqError) + ")");
}
#endif
if (Config.syslog.active && WiFi.status() == WL_CONNECTED && loraPacket != "") {
SYSLOG_Utils::log("Rx", loraPacket, rssi, snr, freqError);
}

View file

@ -7,7 +7,7 @@
#undef OLED_SCL
#undef OLED_RST
#if defined(HELTEC_V3) || defined(HELTEC_WS) || defined(ESP32_DIY_1W_LoRa) || defined(TTGO_T_Beam_V1_0_SX1268) || defined(TTGO_T_Beam_V1_2_SX1262) || defined(OE5HWN_MeshCom)
#if defined(HELTEC_V3) || defined(HELTEC_WS) || defined(ESP32_DIY_1W_LoRa) || defined(TTGO_T_Beam_V1_0_SX1268) || defined(TTGO_T_Beam_V1_2_SX1262) || defined(OE5HWN_MeshCom) || defined(HELTEC_WSL)
#define HAS_SX126X
#endif
@ -79,6 +79,16 @@
#define RADIO_TXEN 13
#endif
#ifdef HELTEC_WSL
#define RADIO_SCLK_PIN 10 // SX1262 SCK
#define RADIO_MISO_PIN 6 // SX1262 MISO
#define RADIO_MOSI_PIN 7 // SX1262 MOSI
#define RADIO_CS_PIN 8 // SX1262 NSS
#define RADIO_RST_PIN 5 // SX1262 RST
#define RADIO_DIO1_PIN 3 // SX1262 DIO1
#define RADIO_BUSY_PIN 4 // SX1262 BUSY
#endif
// OLED
#if defined(TTGO_T_LORA32_V2_1) || defined(ESP32_DIY_LoRa) || defined(ESP32_DIY_1W_LoRa) || defined(TTGO_T_Beam_V1_0) || defined(TTGO_T_Beam_V1_2) || defined(TTGO_T_Beam_V1_0_SX1268) || defined(TTGO_T_Beam_V1_2_SX1262) || defined(OE5HWN_MeshCom)
@ -99,12 +109,19 @@
#define OLED_RST 21
#endif
#ifndef HELTEC_WSL
#define HAS_DISPLAY
#endif
// Leds and other stuff
#if defined(TTGO_T_LORA32_V2_1) || defined(HELTEC_V2) || defined(HELTEC_V3) || defined(HELTEC_WS) || defined(ESP32_DIY_LoRa) || defined(ESP32_DIY_1W_LoRa)
#define HAS_INTERNAL_LED
#endif
#ifdef HELTEC_WSL
#define batteryPin 1
#endif
#if defined(TTGO_T_LORA32_V2_1) || defined(HELTEC_V2)
#define internalLedPin 25 // Green Led
#define batteryPin 35

View file

@ -1,6 +1,7 @@
#include "station_utils.h"
#include "aprs_is_utils.h"
#include "configuration.h"
#include "utils.h"
#include <vector>
extern Configuration Config;
@ -14,15 +15,15 @@ extern String fourthLine;
namespace STATION_Utils {
void deleteNotHeard() {
for (int i=0; i<lastHeardStation.size(); i++) {
String deltaTimeString = lastHeardStation[i].substring(lastHeardStation[i].indexOf(",")+1);
for (int i = 0; i < lastHeardStation.size(); i++) {
String deltaTimeString = lastHeardStation[i].substring(lastHeardStation[i].indexOf(",") + 1);
uint32_t deltaTime = deltaTimeString.toInt();
if ((millis() - deltaTime) < Config.rememberStationTime*60*1000) {
if ((millis() - deltaTime) < Config.rememberStationTime * 60 * 1000) {
lastHeardStation_temp.push_back(lastHeardStation[i]);
}
}
lastHeardStation.clear();
for (int j=0; j<lastHeardStation_temp.size(); j++) {
for (int j = 0; j < lastHeardStation_temp.size(); j++) {
lastHeardStation.push_back(lastHeardStation_temp[j]);
}
lastHeardStation_temp.clear();
@ -31,8 +32,8 @@ namespace STATION_Utils {
void updateLastHeard(String station) {
deleteNotHeard();
bool stationHeard = false;
for (int i=0; i<lastHeardStation.size(); i++) {
if (lastHeardStation[i].substring(0,lastHeardStation[i].indexOf(",")) == station) {
for (int i = 0; i < lastHeardStation.size(); i++) {
if (lastHeardStation[i].substring(0, lastHeardStation[i].indexOf(",")) == station) {
lastHeardStation[i] = station + "," + String(millis());
stationHeard = true;
}
@ -47,55 +48,53 @@ namespace STATION_Utils {
}
fourthLine += String(lastHeardStation.size());
#ifndef TextSerialOutputForApp ////// This is just for debugging
Serial.print("Stations Near (last " + String(Config.rememberStationTime) + " minutes): ");
for (int k=0; k<lastHeardStation.size(); k++) {
Serial.print(lastHeardStation[k].substring(0,lastHeardStation[k].indexOf(","))); Serial.print(" ");
}
Serial.println("");
#endif
// DEBUG ONLY
// Serial.print("Stations Near (last " + String(Config.rememberStationTime) + " minutes): ");
// for (int k=0; k<lastHeardStation.size(); k++) {
// Serial.print(lastHeardStation[k].substring(0,lastHeardStation[k].indexOf(","))); Serial.print(" ");
// }
// Serial.println("");
}
bool wasHeard(String station) {
deleteNotHeard();
for (int i=0; i<lastHeardStation.size(); i++) {
if (lastHeardStation[i].substring(0,lastHeardStation[i].indexOf(",")) == station) {
Serial.println(" ---> Listened Station");
for (int i = 0; i < lastHeardStation.size(); i++) {
if (lastHeardStation[i].substring(0, lastHeardStation[i].indexOf(",")) == station) {
Utils::println(" ---> Listened Station");
return true;
}
}
}
Serial.println(" ---> Station not Heard for last 30 min (Not Tx)\n");
Utils::println(" ---> Station not Heard for last 30 min (Not Tx)\n");
return false;
}
void checkBuffer() {
for (int i=0; i<packetBuffer.size(); i++) {
String deltaTimeString = packetBuffer[i].substring(0,packetBuffer[i].indexOf(","));
for (int i = 0; i < packetBuffer.size(); i++) {
String deltaTimeString = packetBuffer[i].substring(0, packetBuffer[i].indexOf(","));
uint32_t deltaTime = deltaTimeString.toInt();
if ((millis() - deltaTime) < 60*1000) { // cambiar a 15 segundos?
if ((millis() - deltaTime) < 60 * 1000) { // cambiar a 15 segundos?
packetBuffer_temp.push_back(packetBuffer[i]);
}
}
packetBuffer.clear();
for (int j=0; j<packetBuffer_temp.size(); j++) {
for (int j = 0; j < packetBuffer_temp.size(); j++) {
packetBuffer.push_back(packetBuffer_temp[j]);
}
packetBuffer_temp.clear();
// BORRAR ESTO !!
/*for (int i=0; i<packetBuffer.size(); i++) {
Serial.println(packetBuffer[i]);
}*/
//
// DEBUG ONLY
// for (int i=0; i<packetBuffer.size(); i++) {
// Serial.println(packetBuffer[i]);
// }
}
void updatePacketBuffer(String packet) {
if ((packet.indexOf(":!") == -1) && (packet.indexOf(":=") == -1) && (packet.indexOf(":>") == -1) && (packet.indexOf(":`") == -1)) {
String sender = packet.substring(3,packet.indexOf(">"));
String sender = packet.substring(3, packet.indexOf(">"));
String tempAddressee = packet.substring(packet.indexOf("::") + 2);
String addressee = tempAddressee.substring(0,tempAddressee.indexOf(":"));
String addressee = tempAddressee.substring(0, tempAddressee.indexOf(":"));
addressee.trim();
String message = tempAddressee.substring(tempAddressee.indexOf(":")+1);
String message = tempAddressee.substring(tempAddressee.indexOf(":") + 1);
//Serial.println(String(millis()) + "," + sender + "," + addressee + "," + message);
packetBuffer.push_back(String(millis()) + "," + sender + "," + addressee + "," + message);
checkBuffer();

154
src/tnc_utils.cpp Normal file
View file

@ -0,0 +1,154 @@
#include <WiFi.h>
#include "kiss_utils.h"
#include "kiss_protocol.h"
#include "lora_utils.h"
#include "configuration.h"
#include "utils.h"
extern Configuration Config;
#define MAX_CLIENTS 4
#define INPUT_BUFFER_SIZE (2 + MAX_CLIENTS)
#define TNC_PORT 8001
WiFiClient* clients[MAX_CLIENTS];
WiFiServer tncServer(TNC_PORT);
String inputServerBuffer[INPUT_BUFFER_SIZE];
String inputSerialBuffer = "";
namespace TNC_Utils {
void setup() {
if (Config.tnc.enableServer) {
tncServer.stop();
tncServer.begin();
}
}
void checkNewClients() {
WiFiClient new_client = tncServer.available();
if (new_client.connected()) {
for (int i = 0; i < MAX_CLIENTS; i++) {
WiFiClient* client = clients[i];
if (client == nullptr) {
clients[i] = new WiFiClient(new_client);
Utils::println("New TNC client connected");
break;
}
}
}
}
void handleInputData(char character, int bufferIndex) {
String* data;
if (bufferIndex == -1) {
data = &inputSerialBuffer;
} else {
data = &inputServerBuffer[bufferIndex];
}
if (data->length() == 0 && character != (char)FEND) {
return;
}
data->concat(character);
if (character == (char)FEND && data->length() > 3) {
bool isDataFrame = false;
const String& frame = decodeKISS(*data, isDataFrame);
if (isDataFrame) {
if (bufferIndex != -1) {
Utils::print("<--- Got from TNC : ");
Utils::println(frame);
}
String sender = frame.substring(0,frame.indexOf(">"));
if (Config.tnc.acceptOwn || sender != Config.callsign) {
LoRa_Utils::sendNewPacket("APRS", frame);
} else {
Utils::println("Ignored own frame from KISS");
}
}
data->clear();
}
if (data->length() > 255) {
data->clear();
}
}
void readFromClients() {
for (int i = 0; i < MAX_CLIENTS; i++) {
auto client = clients[i];
if (client != nullptr) {
if (client->connected()) {
while (client->available() > 0) {
char character = client->read();
handleInputData(character, 2 + i);
}
} else {
delete client;
clients[i] = nullptr;
}
}
}
}
void readFromSerial() {
while (Serial.available() > 0) {
char character = Serial.read();
handleInputData(character, -1);
}
}
void sendToClients(String packet) {
packet = packet.substring(3);
const String kissEncoded = encodeKISS(packet);
for (int i = 0; i < MAX_CLIENTS; i++) {
auto client = clients[i];
if (client != nullptr) {
if (client->connected()) {
client->print(kissEncoded);
client->flush();
} else {
delete client;
clients[i] = nullptr;
}
}
}
Utils::print("---> Sent to TNC : ");
Utils::println(packet);
}
void sendToSerial(String packet) {
packet = packet.substring(3);
Serial.print(encodeKISS(packet));
Serial.flush();
}
void loop() {
if (Config.tnc.enableServer) {
checkNewClients();
readFromClients();
}
if (Config.tnc.enableSerial) {
readFromSerial();
}
}
}

16
src/tnc_utils.h Normal file
View file

@ -0,0 +1,16 @@
#ifndef TNC_UTILS_H_
#define TNC_UTILS_H_
#include <Arduino.h>
namespace TNC_Utils {
void setup();
void loop();
void sendToClients(String packet);
void sendToSerial(String packet);
}
#endif

View file

@ -93,13 +93,15 @@ namespace Utils {
uint32_t lastTx = millis() - lastBeaconTx;
String beaconPacket, secondaryBeaconPacket;
if (lastTx >= Config.beacon.interval*60*1000) {
if (lastBeaconTx == 0 || lastTx >= Config.beacon.interval*60*1000) {
beaconUpdate = true;
}
if (beaconUpdate) {
display_toggle(true);
Serial.println("-- Sending Beacon to APRSIS --");
Utils::println("-- Sending Beacon to APRSIS --");
STATION_Utils::deleteNotHeard();
activeStations();
@ -113,15 +115,17 @@ namespace Utils {
secondaryBeaconPacket = iGateLoRaBeaconPacket + Config.beacon.comment;
}
#if defined(TTGO_T_LORA32_V2_1) || defined(HELTEC_V2)
#if defined(TTGO_T_LORA32_V2_1) || defined(HELTEC_V2) || defined(HELTEC_WSL)
if (Config.sendBatteryVoltage) {
beaconPacket += " (Batt=" + String(BATTERY_Utils::checkBattery(),2) + "V)";
beaconPacket += " Batt=" + String(BATTERY_Utils::checkBattery(),2) + "V";
secondaryBeaconPacket += " Batt=" + String(BATTERY_Utils::checkBattery(),2) + "V";
sixthLine = " (Batt=" + String(BATTERY_Utils::checkBattery(),2) + "V)";
}
#endif
if (Config.externalVoltageMeasurement) {
beaconPacket += " (Ext V=" + String(BATTERY_Utils::checkExternalVoltage(),2) + "V)";
beaconPacket += " Ext=" + String(BATTERY_Utils::checkExternalVoltage(),2) + "V";
secondaryBeaconPacket += " Ext=" + String(BATTERY_Utils::checkExternalVoltage(),2) + "V";
sixthLine = " (Ext V=" + String(BATTERY_Utils::checkExternalVoltage(),2) + "V)";
}
@ -232,4 +236,16 @@ namespace Utils {
}
}
void print(String text) {
if (!Config.tnc.enableSerial) {
Serial.print(text);
}
}
void println(String text) {
if (!Config.tnc.enableSerial) {
Serial.println(text);
}
}
}

View file

@ -15,9 +15,8 @@ namespace Utils {
void checkWiFiInterval();
void validateFreqs();
void typeOfPacket(String packet, String packetType);
void onOTAStart();
void onOTAProgress(size_t current, size_t final);
void onOTAEnd(bool success);
void print(String text);
void println(String text);
}

View file

@ -3,6 +3,7 @@
#include "web_utils.h"
extern Configuration Config;
extern uint32_t lastBeaconTx;
extern const char web_index_html[] asm("_binary_data_embed_index_html_gz_start");
extern const char web_index_html_end[] asm("_binary_data_embed_index_html_gz_end");
@ -84,6 +85,10 @@ namespace WEB_Utils {
// Config.digi.latitude = request->getParam("digi.latitude", true)->value().toDouble();
// Config.digi.longitude = request->getParam("digi.longitude", true)->value().toDouble();
Config.tnc.enableServer = request->hasParam("tnc.enableServer", true);
Config.tnc.enableSerial = request->hasParam("tnc.enableSerial", true);
Config.tnc.acceptOwn = request->hasParam("tnc.acceptOwn", true);
Config.aprs_is.active = request->hasParam("aprs_is.active", true);
Config.aprs_is.passcode = request->getParam("aprs_is.passcode", true)->value();
Config.aprs_is.server = request->getParam("aprs_is.server", true)->value();
@ -159,6 +164,20 @@ namespace WEB_Utils {
ESP.restart();
}
void handleAction(AsyncWebServerRequest *request) {
String type = request->getParam("type", false)->value();
if (type == "send-beacon") {
lastBeaconTx = 0;
request->send(200, "text/plain", "Beacon will be sent in a while");
} else if (type == "reboot") {
ESP.restart();
} else {
request->send(404, "text/plain", "Not Found");
}
}
void handleStyle(AsyncWebServerRequest *request) {
AsyncWebServerResponse *response = request->beginResponse_P(200, "text/css", (const uint8_t*)web_style_css, web_style_css_len);
response->addHeader("Content-Encoding", "gzip");
@ -190,6 +209,7 @@ namespace WEB_Utils {
server.on("/status", HTTP_GET, handleStatus);
server.on("/configuration.json", HTTP_GET, handleReadConfiguration);
server.on("/configuration.json", HTTP_POST, handleWriteConfiguration);
server.on("/action", HTTP_POST, handleAction);
server.on("/style.css", HTTP_GET, handleStyle);
server.on("/script.js", HTTP_GET, handleScript);
server.on("/bootstrap.css", HTTP_GET, handleBootstrapStyle);