From 4b70ee863df0b6711da561c4694f97c2e765716e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Fri, 27 Jun 2025 19:55:17 +0100 Subject: [PATCH 01/50] Serial bridge implementation --- examples/simple_repeater/main.cpp | 18 +++- platformio.ini | 1 + src/Dispatcher.cpp | 24 ++++- src/Dispatcher.h | 5 ++ src/bridge/serial/Packet.h | 58 +++++++++++++ src/bridge/serial/PacketQueue.h | 113 ++++++++++++++++++++++++ src/bridge/serial/SerialBridge.cpp | 135 +++++++++++++++++++++++++++++ src/bridge/serial/SerialBridge.h | 73 ++++++++++++++++ 8 files changed, 422 insertions(+), 5 deletions(-) create mode 100644 src/bridge/serial/Packet.h create mode 100644 src/bridge/serial/PacketQueue.h create mode 100644 src/bridge/serial/SerialBridge.cpp create mode 100644 src/bridge/serial/SerialBridge.h diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index c33cadd..4edca23 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -72,6 +72,11 @@ static UITask ui_task(display); #endif +#ifdef BRIDGE_OVER_SERIAL +#include "bridge/serial/SerialBridge.h" +bridge::SerialBridge *bridge_interface; +#endif + #define FIRMWARE_ROLE "repeater" #define PACKET_LOG_FILE "/packet_log" @@ -752,7 +757,14 @@ void setup() { } #endif - if (!radio_init()) { halt(); } +#ifdef BRIDGE_OVER_SERIAL + bridge_interface = new bridge::SerialBridge(); + bridge_interface->setup(); +#endif + + if (!radio_init()) { + halt(); + } fast_rng.begin(radio_get_rng_seed()); @@ -825,6 +837,10 @@ void loop() { command[0] = 0; // reset command buffer } +#ifdef BRIDGE_OVER_SERIAL + bridge_interface->loop(); +#endif + the_mesh.loop(); sensors.loop(); } diff --git a/platformio.ini b/platformio.ini index 90e7cfb..36cdf76 100644 --- a/platformio.ini +++ b/platformio.ini @@ -32,6 +32,7 @@ build_flags = -w -DNDEBUG -DRADIOLIB_STATIC_ONLY=1 -DRADIOLIB_GODMODE=1 build_src_filter = +<*.cpp> + + + ; ----------------- ESP32 --------------------- diff --git a/src/Dispatcher.cpp b/src/Dispatcher.cpp index 7f39dc4..08cca61 100644 --- a/src/Dispatcher.cpp +++ b/src/Dispatcher.cpp @@ -1,7 +1,7 @@ #include "Dispatcher.h" #if MESH_PACKET_LOGGING - #include +#include #endif #include @@ -104,6 +104,7 @@ void Dispatcher::loop() { processRecvPacket(pkt); } } + checkRecv(); checkSend(); } @@ -115,6 +116,18 @@ void Dispatcher::checkRecv() { { uint8_t raw[MAX_TRANS_UNIT+1]; int len = _radio->recvRaw(raw, MAX_TRANS_UNIT); + +#ifdef BRIDGE_OVER_SERIAL + // We are basically stamping metadata from the last RF packet into something that came from serial, + // it works for now. But long term the code on checkRecv() should be refactored to be able to deal + // with both use cases without dupeing the existing code. I've chosen [for now] not to dupe and just + // fake the metadata. + + if (len == 0) { + len = bridge_interface->getPacket(raw); + } +#endif + if (len > 0) { logRxRaw(_radio->getLastSNR(), _radio->getLastRSSI(), raw, len); @@ -280,7 +293,11 @@ void Dispatcher::checkSend() { } outbound_expiry = futureMillis(max_airtime); - #if MESH_PACKET_LOGGING +#ifdef BRIDGE_OVER_SERIAL + bridge_interface->sendPacket(outbound); +#endif + +#if MESH_PACKET_LOGGING Serial.print(getLogDateTime()); Serial.printf(": TX, len=%d (type=%d, route=%s, payload_len=%d)", len, outbound->getPayloadType(), outbound->isRouteDirect() ? "D" : "F", outbound->payload_len); @@ -290,7 +307,7 @@ void Dispatcher::checkSend() { } else { Serial.printf("\n"); } - #endif +#endif } } } @@ -328,5 +345,4 @@ bool Dispatcher::millisHasNowPassed(unsigned long timestamp) const { unsigned long Dispatcher::futureMillis(int millis_from_now) const { return _ms->getMillis() + millis_from_now; } - } \ No newline at end of file diff --git a/src/Dispatcher.h b/src/Dispatcher.h index 2200f81..98184b5 100644 --- a/src/Dispatcher.h +++ b/src/Dispatcher.h @@ -6,6 +6,11 @@ #include #include +#ifdef BRIDGE_OVER_SERIAL +#include "bridge/serial/SerialBridge.h" +extern bridge::SerialBridge *bridge_interface; +#endif + namespace mesh { /** diff --git a/src/bridge/serial/Packet.h b/src/bridge/serial/Packet.h new file mode 100644 index 0000000..fbb4155 --- /dev/null +++ b/src/bridge/serial/Packet.h @@ -0,0 +1,58 @@ +/** + * MeshCore - A new lightweight, hybrid routing mesh protocol for packet radios + * Copyright (c) 2025 Scott Powell / rippleradios.com + * + * This project is maintained by the contributors listed in + * https://github.com/ripplebiz/MeshCore/graphs/contributors + * + * MIT License + * + * 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. + * + */ +#pragma once + +#include "MeshCore.h" + +#include + +namespace bridge { + +/* + * +----------------------------------------------------+ + * | SERIAL PACKET SPEC | + * +-----------+---------+------------------------------+ + * | TYPE | NAME | DESCRIPTION | + * +-----------+---------+------------------------------+ + * | uint16_t | MAGIC | The packet start marker | + * | uint16_t | LEN | Length of the payload | + * | uint16_t | CRC | Checksum for error checking | + * | uint8_t[] | PAYLOAD | Actual rf packet data | + * +-----------+---------+------------------------------+ + */ +#define SERIAL_PKT_MAGIC 0xdead + +struct Packet { + uint16_t magic, len, crc; + uint8_t payload[MAX_TRANS_UNIT]; + + Packet() : magic(SERIAL_PKT_MAGIC), len(0), crc(0) {} +}; + +} // namespace bridge \ No newline at end of file diff --git a/src/bridge/serial/PacketQueue.h b/src/bridge/serial/PacketQueue.h new file mode 100644 index 0000000..a83d8f2 --- /dev/null +++ b/src/bridge/serial/PacketQueue.h @@ -0,0 +1,113 @@ +/** + * MeshCore - A new lightweight, hybrid routing mesh protocol for packet radios + * Copyright (c) 2025 Scott Powell / rippleradios.com + * + * This project is maintained by the contributors listed in + * https://github.com/ripplebiz/MeshCore/graphs/contributors + * + * MIT License + * + * 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. + * + */ +#pragma once + +#include "MeshCore.h" + +#include +#include + +#if MESH_PACKET_LOGGING +#include +#endif + +#ifndef MAX_QUEUE_SIZE +#define MAX_QUEUE_SIZE 8 +#endif + +namespace bridge { + +class PacketQueue { +private: + struct { + size_t len; + uint8_t bytes[MAX_TRANS_UNIT]; + } buffer[MAX_QUEUE_SIZE]; + +protected: + uint16_t head = 0, tail = 0; + +public: + size_t available() const { return (tail - head + MAX_QUEUE_SIZE) % MAX_QUEUE_SIZE; } + + size_t enqueue(const uint8_t *bytes, const uint8_t len) { + if (len == 0 || len > MAX_TRANS_UNIT) { +#if BRIDGE_DEBUG + Serial.printf("BRIDGE: enqueue() failed len=%d\n", len); +#endif + return 0; + } + + if ((tail + 1) % MAX_QUEUE_SIZE == head) { // Buffer full + head = (head + 1) % MAX_QUEUE_SIZE; // Overwrite oldest packet + } + + buffer[tail].len = len; + memcpy(buffer[tail].bytes, bytes, len); + +#if MESH_PACKET_LOGGING + Serial.printf("BRIDGE: enqueue() len=%d payload[5]=", len); + for (size_t i = 0; i < len && i < 5; ++i) { + Serial.printf("0x%02x ", buffer[tail].bytes[i]); + } + Serial.printf("\n"); +#endif + + tail = (tail + 1) % MAX_QUEUE_SIZE; + return len; + } + + size_t enqueue(const mesh::Packet *pkt) { + uint8_t bytes[MAX_TRANS_UNIT]; + const size_t len = pkt->writeTo(bytes); + return enqueue(bytes, len); + } + + size_t dequeue(uint8_t *bytes) { + if (head == tail) { // Buffer empty + return 0; + } + + const size_t len = buffer[head].len; + memcpy(bytes, buffer[head].bytes, len); + head = (head + 1) % MAX_QUEUE_SIZE; + +#if MESH_PACKET_LOGGING + Serial.printf("BRIDGE: dequeue() payload[5]="); + for (size_t i = 0; i < len && i < 5; ++i) { + Serial.printf("0x%02x ", bytes[i]); + } + Serial.printf("\n"); +#endif + + return len; + } +}; + +} // namespace bridge diff --git a/src/bridge/serial/SerialBridge.cpp b/src/bridge/serial/SerialBridge.cpp new file mode 100644 index 0000000..1e83f9e --- /dev/null +++ b/src/bridge/serial/SerialBridge.cpp @@ -0,0 +1,135 @@ +/** + * MeshCore - A new lightweight, hybrid routing mesh protocol for packet radios + * Copyright (c) 2025 Scott Powell / rippleradios.com + * + * This project is maintained by the contributors listed in + * https://github.com/ripplebiz/MeshCore/graphs/contributors + * + * MIT License + * + * 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. + * + */ +#include "SerialBridge.h" + +#include "MeshCore.h" +#include "Packet.h" + +// Alternative for ESP32 +// Alternative for RP2040 +#include + +namespace bridge { +#ifdef BRIDGE_OVER_SERIAL + +#if !defined(BRIDGE_OVER_SERIAL_RX) || !defined(BRIDGE_OVER_SERIAL_TX) +#error You must define RX and TX pins +#endif + +void SerialBridge::setup() { +#if defined(ESP32) + BRIDGE_OVER_SERIAL.setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); +#elif defined(RP2040_PLATFORM) + BRIDGE_OVER_SERIAL.setPinout(BRIDGE_OVER_SERIAL_TX, BRIDGE_OVER_SERIAL_RX); +#else +#error SerialBridge was not tested on the current platform +#endif + BRIDGE_OVER_SERIAL.begin(115200); + Serial.printf("Bridge over serial: enabled\n"); +} + +void SerialBridge::loop() { + readFromSerial(); + writeToSerial(); +} + +bool SerialBridge::shouldRetransmit(const mesh::Packet *pkt) { + if (pkt->isMarkedDoNotRetransmit()) { + return false; + } +} + +size_t SerialBridge::getPacket(uint8_t *bytes) { + return rx_queue.dequeue(bytes); +} + +size_t SerialBridge::sendPacket(const mesh::Packet *pkt) { + if (shouldRetransmit(pkt)) return 0; + const size_t len = tx_queue.enqueue(pkt); + return len; +} + +void SerialBridge::readFromSerial() { + static constexpr uint16_t size = sizeof(bridge::Packet) + 1; + static uint8_t buffer[size]; + static uint16_t tail = 0; + + while (BRIDGE_OVER_SERIAL.available()) { + buffer[tail] = (uint8_t)BRIDGE_OVER_SERIAL.read(); + tail = (tail + 1) % size; + +#if BRIDGE_OVER_SERIAL_DEBUG + Serial.printf("%02x ", buffer[(tail - 1 + size) % size]); +#endif + + // Check for complete packet by looking back to where the magic number should be + uint16_t head = (tail - sizeof(bridge::Packet) + size) % size; + const uint16_t magic = buffer[head] | (buffer[(head + 1) % size] << 8); + + if (magic == SERIAL_PKT_MAGIC) { + const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); + const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); + + uint8_t payload[MAX_TRANS_UNIT]; + for (size_t i = 0; i < len; i++) { + payload[i] = buffer[(head + 6 + i) % size]; + } + + const bool valid = verifyCRC(payload, len, crc); + +#if MESH_PACKET_LOGGING + Serial.printf("BRIDGE: Read from serial len=%d crc=0x%04x\n", len, crc); +#endif + + if (verifyCRC(payload, len, crc)) { +#if MESH_PACKET_LOGGING + Serial.printf("BRIDGE: Received packet was validated\n"); +#endif + rx_queue.enqueue(payload, len); + } + } + } +} + +void SerialBridge::writeToSerial() { + bridge::Packet pkt; + if (!tx_queue.available()) return; + pkt.len = tx_queue.dequeue(pkt.payload); + + if (pkt.len > 0) { + pkt.crc = SerialBridge::calculateCRC(pkt.payload, pkt.len); + BRIDGE_OVER_SERIAL.write((uint8_t *)&pkt, sizeof(bridge::Packet)); +#if MESH_PACKET_LOGGING + Serial.printf("BRIDGE: Write to serial len=%d crc=0x%04x\n", pkt.len, pkt.crc); +#endif + } +} + +#endif +} // namespace bridge diff --git a/src/bridge/serial/SerialBridge.h b/src/bridge/serial/SerialBridge.h new file mode 100644 index 0000000..80bb236 --- /dev/null +++ b/src/bridge/serial/SerialBridge.h @@ -0,0 +1,73 @@ +/** + * MeshCore - A new lightweight, hybrid routing mesh protocol for packet radios + * Copyright (c) 2025 Scott Powell / rippleradios.com + * + * This project is maintained by the contributors listed in + * https://github.com/ripplebiz/MeshCore/graphs/contributors + * + * MIT License + * + * 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. + * + */ +#pragma once + +#include "Packet.h" +#include "PacketQueue.h" + +#include + +namespace bridge { + +class SerialBridge { +private: + PacketQueue rx_queue, tx_queue; + +protected: + bool shouldRetransmit(const mesh::Packet *); + +public: + void loop(); + void setup(); + void readFromSerial(); + void writeToSerial(); + + size_t getPacket(uint8_t *); + size_t sendPacket(const mesh::Packet *); + + static uint16_t calculateCRC(const uint8_t *bytes, size_t len) { + // Fletcher-16 + // https://en.wikipedia.org/wiki/Fletcher%27s_checksum + uint8_t sum1 = 0, sum2 = 0; + + for (size_t i = 0; i < len; i++) { + sum1 = (sum1 + bytes[i]) % 255; + sum2 = (sum2 + sum1) % 255; + } + + return (sum2 << 8) | sum1; + }; + + static bool verifyCRC(const uint8_t *bytes, size_t len, uint16_t crc) { + uint16_t computedChecksum = calculateCRC(bytes, len); + return (computedChecksum == crc); + } +}; + +} // namespace bridge From 2f77cef04b65f1d76a01e3b8c74086732d43a8e0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Sun, 29 Jun 2025 16:28:11 +0100 Subject: [PATCH 02/50] Add config flags to variants --- variants/heltec_v3/platformio.ini | 3 +++ variants/lilygo_tlora_v2_1/platformio.ini | 3 +++ variants/waveshare_rp2040_lora/platformio.ini | 3 +++ 3 files changed, 9 insertions(+) diff --git a/variants/heltec_v3/platformio.ini b/variants/heltec_v3/platformio.ini index 8f9b1a2..173be80 100644 --- a/variants/heltec_v3/platformio.ini +++ b/variants/heltec_v3/platformio.ini @@ -47,6 +47,9 @@ build_flags = -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 +; -D BRIDGE_OVER_SERIAL=Serial2 +; -D BRIDGE_OVER_SERIAL_RX=5 +; -D BRIDGE_OVER_SERIAL_TX=6 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${Heltec_lora32_v3.build_src_filter} diff --git a/variants/lilygo_tlora_v2_1/platformio.ini b/variants/lilygo_tlora_v2_1/platformio.ini index d9cecfc..bd351c5 100644 --- a/variants/lilygo_tlora_v2_1/platformio.ini +++ b/variants/lilygo_tlora_v2_1/platformio.ini @@ -44,6 +44,9 @@ build_flags = -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 +; -D BRIDGE_OVER_SERIAL=Serial2 +; -D BRIDGE_OVER_SERIAL_RX=34 +; -D BRIDGE_OVER_SERIAL_TX=25 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 ; -D CORE_DEBUG_LEVEL=3 diff --git a/variants/waveshare_rp2040_lora/platformio.ini b/variants/waveshare_rp2040_lora/platformio.ini index 2730734..b1e4714 100644 --- a/variants/waveshare_rp2040_lora/platformio.ini +++ b/variants/waveshare_rp2040_lora/platformio.ini @@ -35,6 +35,9 @@ build_flags = ${waveshare_rp2040_lora.build_flags} -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 +; -D BRIDGE_OVER_SERIAL=Serial2 +; -D BRIDGE_OVER_SERIAL_RX=9 +; -D BRIDGE_OVER_SERIAL_TX=8 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${waveshare_rp2040_lora.build_src_filter} From ac056fb0b98ecd9ce0da6cda8693f1cdffb97cb6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Tue, 8 Jul 2025 14:04:21 +0100 Subject: [PATCH 03/50] Remove serial bridge implementation and implement simplified version directly in the repeater source code. --- examples/simple_repeater/main.cpp | 121 +++++++++++++++++++++----- src/Dispatcher.cpp | 15 ---- src/Dispatcher.h | 5 -- src/bridge/serial/Packet.h | 58 ------------- src/bridge/serial/PacketQueue.h | 113 ------------------------ src/bridge/serial/SerialBridge.cpp | 135 ----------------------------- src/bridge/serial/SerialBridge.h | 73 ---------------- 7 files changed, 100 insertions(+), 420 deletions(-) delete mode 100644 src/bridge/serial/Packet.h delete mode 100644 src/bridge/serial/PacketQueue.h delete mode 100644 src/bridge/serial/SerialBridge.cpp delete mode 100644 src/bridge/serial/SerialBridge.h diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 131dc49..96969f9 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -72,17 +72,35 @@ static UITask ui_task(display); #endif -#ifdef BRIDGE_OVER_SERIAL -#include "bridge/serial/SerialBridge.h" -bridge::SerialBridge *bridge_interface; -#endif - #define FIRMWARE_ROLE "repeater" #define PACKET_LOG_FILE "/packet_log" /* ------------------------------ Code -------------------------------- */ +#ifdef BRIDGE_OVER_SERIAL +#define SERIAL_PKT_MAGIC 0xbeef + +struct SerialPacket { + uint16_t magic, len, crc; + uint8_t payload[MAX_TRANS_UNIT]; + SerialPacket() : magic(SERIAL_PKT_MAGIC), len(0), crc(0) {} +}; + +// Fletcher-16 +// https://en.wikipedia.org/wiki/Fletcher%27s_checksum +static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { + uint8_t sum1 = 0, sum2 = 0; + + for (size_t i = 0; i < len; i++) { + sum1 = (sum1 + bytes[i]) % 255; + sum2 = (sum2 + sum1) % 255; + } + + return (sum2 << 8) | sum1; +}; +#endif + #define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS #define REQ_TYPE_KEEP_ALIVE 0x02 #define REQ_TYPE_GET_TELEMETRY_DATA 0x03 @@ -297,6 +315,20 @@ protected: } } void logTx(mesh::Packet* pkt, int len) override { +#ifdef BRIDGE_OVER_SERIAL + SerialPacket spkt; + spkt.len = pkt->writeTo(spkt.payload); + + if (spkt.len > 0) { + spkt.crc = fletcher16(spkt.payload, spkt.len); + BRIDGE_OVER_SERIAL.write((uint8_t *)&spkt, sizeof(SerialPacket)); + +#if MESH_PACKET_LOGGING + Serial.printf("BRIDGE: Write to serial len=%d crc=0x%04x\n", spkt.len, spkt.crc); +#endif + } +#endif + if (_logging) { File f = openAppend(PACKET_LOG_FILE); if (f) { @@ -358,9 +390,9 @@ protected: } else if (strcmp((char *) &data[4], _prefs.guest_password) == 0) { // check guest password is_admin = false; } else { - #if MESH_DEBUG +#if MESH_DEBUG MESH_DEBUG_PRINTLN("Invalid password: %s", &data[4]); - #endif +#endif return; } @@ -377,15 +409,15 @@ protected: uint32_t now = getRTCClock()->getCurrentTimeUnique(); memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp - #if 0 +#if 0 memcpy(&reply_data[4], "OK", 2); // legacy response - #else +#else reply_data[4] = RESP_SERVER_LOGIN_OK; reply_data[5] = 0; // NEW: recommended keep-alive interval (secs / 16) reply_data[6] = is_admin ? 1 : 0; reply_data[7] = 0; // FUTURE: reserved getRNG()->random(&reply_data[8], 4); // random blob to help packet-hash uniqueness - #endif +#endif if (packet->isRouteFlood()) { // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response @@ -562,9 +594,9 @@ public: next_local_advert = next_flood_advert = 0; _logging = false; - #if MAX_NEIGHBOURS +#if MAX_NEIGHBOURS memset(neighbours, 0, sizeof(neighbours)); - #endif +#endif // defaults memset(&_prefs, 0, sizeof(_prefs)); @@ -712,6 +744,44 @@ public: } void loop() { +#ifdef BRIDGE_OVER_SERIAL + static constexpr uint16_t size = sizeof(SerialPacket) + 1; + static uint8_t buffer[size]; + static uint16_t tail = 0; + + while (BRIDGE_OVER_SERIAL.available()) { + buffer[tail] = (uint8_t)BRIDGE_OVER_SERIAL.read(); + MESH_DEBUG_PRINT("%02x ", buffer[tail]); + tail = (tail + 1) % size; + + // Check for complete packet by looking back to where the magic number should be + uint16_t head = (tail - sizeof(SerialPacket) + size) % size; + const uint16_t magic = buffer[head] | (buffer[(head + 1) % size] << 8); + + if (magic == SERIAL_PKT_MAGIC) { + uint8_t bytes[MAX_TRANS_UNIT]; + const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); + const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); + + for (size_t i = 0; i < len; i++) { + bytes[i] = buffer[(head + 6 + i) % size]; + } + + uint16_t f16 = fletcher16(bytes, len); + +#if MESH_PACKET_LOGGING + Serial.printf("BRIDGE: Read from serial len=%d crc=0x%04x valid=%s\n", len, crc, (f16 == crc) ? "true" : "false"); +#endif + + if (f16 == crc) { + mesh::Packet *pkt = _mgr->allocNew(); + pkt->readFrom(bytes, len); + _mgr->queueInbound(pkt, millis()); + } + } + } +#endif + mesh::Mesh::loop(); if (next_flood_advert && millisHasNowPassed(next_flood_advert)) { @@ -745,6 +815,24 @@ static char command[80]; void setup() { Serial.begin(115200); + +#ifdef BRIDGE_OVER_SERIAL +#if defined(ESP32) + BRIDGE_OVER_SERIAL.setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); +#elif defined(RP2040_PLATFORM) + BRIDGE_OVER_SERIAL.setRX(BRIDGE_OVER_SERIAL_RX); + BRIDGE_OVER_SERIAL.setTX(BRIDGE_OVER_SERIAL_TX); +#elif defined(STM32_PLATFORM) + BRIDGE_OVER_SERIAL.setRx(BRIDGE_OVER_SERIAL_RX); + BRIDGE_OVER_SERIAL.setTx(BRIDGE_OVER_SERIAL_TX); +#else +#error SerialBridge was not tested on the current platform +#endif + + BRIDGE_OVER_SERIAL.begin(115200); + MESH_DEBUG_PRINTLN("Bridge over serial: enabled"); +#endif + delay(1000); board.begin(); @@ -757,11 +845,6 @@ void setup() { } #endif -#ifdef BRIDGE_OVER_SERIAL - bridge_interface = new bridge::SerialBridge(); - bridge_interface->setup(); -#endif - if (!radio_init()) { halt(); } @@ -837,10 +920,6 @@ void loop() { command[0] = 0; // reset command buffer } -#ifdef BRIDGE_OVER_SERIAL - bridge_interface->loop(); -#endif - the_mesh.loop(); sensors.loop(); } diff --git a/src/Dispatcher.cpp b/src/Dispatcher.cpp index 08cca61..1a6e833 100644 --- a/src/Dispatcher.cpp +++ b/src/Dispatcher.cpp @@ -117,17 +117,6 @@ void Dispatcher::checkRecv() { uint8_t raw[MAX_TRANS_UNIT+1]; int len = _radio->recvRaw(raw, MAX_TRANS_UNIT); -#ifdef BRIDGE_OVER_SERIAL - // We are basically stamping metadata from the last RF packet into something that came from serial, - // it works for now. But long term the code on checkRecv() should be refactored to be able to deal - // with both use cases without dupeing the existing code. I've chosen [for now] not to dupe and just - // fake the metadata. - - if (len == 0) { - len = bridge_interface->getPacket(raw); - } -#endif - if (len > 0) { logRxRaw(_radio->getLastSNR(), _radio->getLastRSSI(), raw, len); @@ -293,10 +282,6 @@ void Dispatcher::checkSend() { } outbound_expiry = futureMillis(max_airtime); -#ifdef BRIDGE_OVER_SERIAL - bridge_interface->sendPacket(outbound); -#endif - #if MESH_PACKET_LOGGING Serial.print(getLogDateTime()); Serial.printf(": TX, len=%d (type=%d, route=%s, payload_len=%d)", diff --git a/src/Dispatcher.h b/src/Dispatcher.h index 98184b5..2200f81 100644 --- a/src/Dispatcher.h +++ b/src/Dispatcher.h @@ -6,11 +6,6 @@ #include #include -#ifdef BRIDGE_OVER_SERIAL -#include "bridge/serial/SerialBridge.h" -extern bridge::SerialBridge *bridge_interface; -#endif - namespace mesh { /** diff --git a/src/bridge/serial/Packet.h b/src/bridge/serial/Packet.h deleted file mode 100644 index fbb4155..0000000 --- a/src/bridge/serial/Packet.h +++ /dev/null @@ -1,58 +0,0 @@ -/** - * MeshCore - A new lightweight, hybrid routing mesh protocol for packet radios - * Copyright (c) 2025 Scott Powell / rippleradios.com - * - * This project is maintained by the contributors listed in - * https://github.com/ripplebiz/MeshCore/graphs/contributors - * - * MIT License - * - * 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. - * - */ -#pragma once - -#include "MeshCore.h" - -#include - -namespace bridge { - -/* - * +----------------------------------------------------+ - * | SERIAL PACKET SPEC | - * +-----------+---------+------------------------------+ - * | TYPE | NAME | DESCRIPTION | - * +-----------+---------+------------------------------+ - * | uint16_t | MAGIC | The packet start marker | - * | uint16_t | LEN | Length of the payload | - * | uint16_t | CRC | Checksum for error checking | - * | uint8_t[] | PAYLOAD | Actual rf packet data | - * +-----------+---------+------------------------------+ - */ -#define SERIAL_PKT_MAGIC 0xdead - -struct Packet { - uint16_t magic, len, crc; - uint8_t payload[MAX_TRANS_UNIT]; - - Packet() : magic(SERIAL_PKT_MAGIC), len(0), crc(0) {} -}; - -} // namespace bridge \ No newline at end of file diff --git a/src/bridge/serial/PacketQueue.h b/src/bridge/serial/PacketQueue.h deleted file mode 100644 index a83d8f2..0000000 --- a/src/bridge/serial/PacketQueue.h +++ /dev/null @@ -1,113 +0,0 @@ -/** - * MeshCore - A new lightweight, hybrid routing mesh protocol for packet radios - * Copyright (c) 2025 Scott Powell / rippleradios.com - * - * This project is maintained by the contributors listed in - * https://github.com/ripplebiz/MeshCore/graphs/contributors - * - * MIT License - * - * 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. - * - */ -#pragma once - -#include "MeshCore.h" - -#include -#include - -#if MESH_PACKET_LOGGING -#include -#endif - -#ifndef MAX_QUEUE_SIZE -#define MAX_QUEUE_SIZE 8 -#endif - -namespace bridge { - -class PacketQueue { -private: - struct { - size_t len; - uint8_t bytes[MAX_TRANS_UNIT]; - } buffer[MAX_QUEUE_SIZE]; - -protected: - uint16_t head = 0, tail = 0; - -public: - size_t available() const { return (tail - head + MAX_QUEUE_SIZE) % MAX_QUEUE_SIZE; } - - size_t enqueue(const uint8_t *bytes, const uint8_t len) { - if (len == 0 || len > MAX_TRANS_UNIT) { -#if BRIDGE_DEBUG - Serial.printf("BRIDGE: enqueue() failed len=%d\n", len); -#endif - return 0; - } - - if ((tail + 1) % MAX_QUEUE_SIZE == head) { // Buffer full - head = (head + 1) % MAX_QUEUE_SIZE; // Overwrite oldest packet - } - - buffer[tail].len = len; - memcpy(buffer[tail].bytes, bytes, len); - -#if MESH_PACKET_LOGGING - Serial.printf("BRIDGE: enqueue() len=%d payload[5]=", len); - for (size_t i = 0; i < len && i < 5; ++i) { - Serial.printf("0x%02x ", buffer[tail].bytes[i]); - } - Serial.printf("\n"); -#endif - - tail = (tail + 1) % MAX_QUEUE_SIZE; - return len; - } - - size_t enqueue(const mesh::Packet *pkt) { - uint8_t bytes[MAX_TRANS_UNIT]; - const size_t len = pkt->writeTo(bytes); - return enqueue(bytes, len); - } - - size_t dequeue(uint8_t *bytes) { - if (head == tail) { // Buffer empty - return 0; - } - - const size_t len = buffer[head].len; - memcpy(bytes, buffer[head].bytes, len); - head = (head + 1) % MAX_QUEUE_SIZE; - -#if MESH_PACKET_LOGGING - Serial.printf("BRIDGE: dequeue() payload[5]="); - for (size_t i = 0; i < len && i < 5; ++i) { - Serial.printf("0x%02x ", bytes[i]); - } - Serial.printf("\n"); -#endif - - return len; - } -}; - -} // namespace bridge diff --git a/src/bridge/serial/SerialBridge.cpp b/src/bridge/serial/SerialBridge.cpp deleted file mode 100644 index 1e83f9e..0000000 --- a/src/bridge/serial/SerialBridge.cpp +++ /dev/null @@ -1,135 +0,0 @@ -/** - * MeshCore - A new lightweight, hybrid routing mesh protocol for packet radios - * Copyright (c) 2025 Scott Powell / rippleradios.com - * - * This project is maintained by the contributors listed in - * https://github.com/ripplebiz/MeshCore/graphs/contributors - * - * MIT License - * - * 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. - * - */ -#include "SerialBridge.h" - -#include "MeshCore.h" -#include "Packet.h" - -// Alternative for ESP32 -// Alternative for RP2040 -#include - -namespace bridge { -#ifdef BRIDGE_OVER_SERIAL - -#if !defined(BRIDGE_OVER_SERIAL_RX) || !defined(BRIDGE_OVER_SERIAL_TX) -#error You must define RX and TX pins -#endif - -void SerialBridge::setup() { -#if defined(ESP32) - BRIDGE_OVER_SERIAL.setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); -#elif defined(RP2040_PLATFORM) - BRIDGE_OVER_SERIAL.setPinout(BRIDGE_OVER_SERIAL_TX, BRIDGE_OVER_SERIAL_RX); -#else -#error SerialBridge was not tested on the current platform -#endif - BRIDGE_OVER_SERIAL.begin(115200); - Serial.printf("Bridge over serial: enabled\n"); -} - -void SerialBridge::loop() { - readFromSerial(); - writeToSerial(); -} - -bool SerialBridge::shouldRetransmit(const mesh::Packet *pkt) { - if (pkt->isMarkedDoNotRetransmit()) { - return false; - } -} - -size_t SerialBridge::getPacket(uint8_t *bytes) { - return rx_queue.dequeue(bytes); -} - -size_t SerialBridge::sendPacket(const mesh::Packet *pkt) { - if (shouldRetransmit(pkt)) return 0; - const size_t len = tx_queue.enqueue(pkt); - return len; -} - -void SerialBridge::readFromSerial() { - static constexpr uint16_t size = sizeof(bridge::Packet) + 1; - static uint8_t buffer[size]; - static uint16_t tail = 0; - - while (BRIDGE_OVER_SERIAL.available()) { - buffer[tail] = (uint8_t)BRIDGE_OVER_SERIAL.read(); - tail = (tail + 1) % size; - -#if BRIDGE_OVER_SERIAL_DEBUG - Serial.printf("%02x ", buffer[(tail - 1 + size) % size]); -#endif - - // Check for complete packet by looking back to where the magic number should be - uint16_t head = (tail - sizeof(bridge::Packet) + size) % size; - const uint16_t magic = buffer[head] | (buffer[(head + 1) % size] << 8); - - if (magic == SERIAL_PKT_MAGIC) { - const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); - const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); - - uint8_t payload[MAX_TRANS_UNIT]; - for (size_t i = 0; i < len; i++) { - payload[i] = buffer[(head + 6 + i) % size]; - } - - const bool valid = verifyCRC(payload, len, crc); - -#if MESH_PACKET_LOGGING - Serial.printf("BRIDGE: Read from serial len=%d crc=0x%04x\n", len, crc); -#endif - - if (verifyCRC(payload, len, crc)) { -#if MESH_PACKET_LOGGING - Serial.printf("BRIDGE: Received packet was validated\n"); -#endif - rx_queue.enqueue(payload, len); - } - } - } -} - -void SerialBridge::writeToSerial() { - bridge::Packet pkt; - if (!tx_queue.available()) return; - pkt.len = tx_queue.dequeue(pkt.payload); - - if (pkt.len > 0) { - pkt.crc = SerialBridge::calculateCRC(pkt.payload, pkt.len); - BRIDGE_OVER_SERIAL.write((uint8_t *)&pkt, sizeof(bridge::Packet)); -#if MESH_PACKET_LOGGING - Serial.printf("BRIDGE: Write to serial len=%d crc=0x%04x\n", pkt.len, pkt.crc); -#endif - } -} - -#endif -} // namespace bridge diff --git a/src/bridge/serial/SerialBridge.h b/src/bridge/serial/SerialBridge.h deleted file mode 100644 index 80bb236..0000000 --- a/src/bridge/serial/SerialBridge.h +++ /dev/null @@ -1,73 +0,0 @@ -/** - * MeshCore - A new lightweight, hybrid routing mesh protocol for packet radios - * Copyright (c) 2025 Scott Powell / rippleradios.com - * - * This project is maintained by the contributors listed in - * https://github.com/ripplebiz/MeshCore/graphs/contributors - * - * MIT License - * - * 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. - * - */ -#pragma once - -#include "Packet.h" -#include "PacketQueue.h" - -#include - -namespace bridge { - -class SerialBridge { -private: - PacketQueue rx_queue, tx_queue; - -protected: - bool shouldRetransmit(const mesh::Packet *); - -public: - void loop(); - void setup(); - void readFromSerial(); - void writeToSerial(); - - size_t getPacket(uint8_t *); - size_t sendPacket(const mesh::Packet *); - - static uint16_t calculateCRC(const uint8_t *bytes, size_t len) { - // Fletcher-16 - // https://en.wikipedia.org/wiki/Fletcher%27s_checksum - uint8_t sum1 = 0, sum2 = 0; - - for (size_t i = 0; i < len; i++) { - sum1 = (sum1 + bytes[i]) % 255; - sum2 = (sum2 + sum1) % 255; - } - - return (sum2 << 8) | sum1; - }; - - static bool verifyCRC(const uint8_t *bytes, size_t len, uint16_t crc) { - uint16_t computedChecksum = calculateCRC(bytes, len); - return (computedChecksum == crc); - } -}; - -} // namespace bridge From 92ee1820c42041dce922b8e5917eb46533f9e217 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Tue, 8 Jul 2025 16:02:10 +0100 Subject: [PATCH 04/50] Add null check for packet allocation and clean up Dispatcher --- examples/simple_repeater/main.cpp | 13 ++++++++++--- src/Dispatcher.cpp | 9 ++++----- 2 files changed, 14 insertions(+), 8 deletions(-) diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 96969f9..428e932 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -774,9 +774,16 @@ public: #endif if (f16 == crc) { - mesh::Packet *pkt = _mgr->allocNew(); - pkt->readFrom(bytes, len); - _mgr->queueInbound(pkt, millis()); + Packet *pkt = _mgr->allocNew(); + + if (pkt != NULL) { + pkt->readFrom(bytes, len); + _mgr->queueInbound(pkt, millis()); + } else { +#if MESH_PACKET_LOGGING + Serial.printf("BRIDGE: Unable to allocate new Packet *pkt"); +#endif + } } } } diff --git a/src/Dispatcher.cpp b/src/Dispatcher.cpp index 1a6e833..7f39dc4 100644 --- a/src/Dispatcher.cpp +++ b/src/Dispatcher.cpp @@ -1,7 +1,7 @@ #include "Dispatcher.h" #if MESH_PACKET_LOGGING -#include + #include #endif #include @@ -104,7 +104,6 @@ void Dispatcher::loop() { processRecvPacket(pkt); } } - checkRecv(); checkSend(); } @@ -116,7 +115,6 @@ void Dispatcher::checkRecv() { { uint8_t raw[MAX_TRANS_UNIT+1]; int len = _radio->recvRaw(raw, MAX_TRANS_UNIT); - if (len > 0) { logRxRaw(_radio->getLastSNR(), _radio->getLastRSSI(), raw, len); @@ -282,7 +280,7 @@ void Dispatcher::checkSend() { } outbound_expiry = futureMillis(max_airtime); -#if MESH_PACKET_LOGGING + #if MESH_PACKET_LOGGING Serial.print(getLogDateTime()); Serial.printf(": TX, len=%d (type=%d, route=%s, payload_len=%d)", len, outbound->getPayloadType(), outbound->isRouteDirect() ? "D" : "F", outbound->payload_len); @@ -292,7 +290,7 @@ void Dispatcher::checkSend() { } else { Serial.printf("\n"); } -#endif + #endif } } } @@ -330,4 +328,5 @@ bool Dispatcher::millisHasNowPassed(unsigned long timestamp) const { unsigned long Dispatcher::futureMillis(int millis_from_now) const { return _ms->getMillis() + millis_from_now; } + } \ No newline at end of file From 97b51900f8667515f4f1a6f9064f5d280a0b480f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Tue, 8 Jul 2025 21:45:49 +0100 Subject: [PATCH 05/50] More robust handling of pkt len --- examples/simple_repeater/main.cpp | 45 ++++++++++++++++++------------- 1 file changed, 26 insertions(+), 19 deletions(-) diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 428e932..fe065a3 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -79,7 +79,7 @@ /* ------------------------------ Code -------------------------------- */ #ifdef BRIDGE_OVER_SERIAL -#define SERIAL_PKT_MAGIC 0xbeef +#define SERIAL_PKT_MAGIC 0xcafe struct SerialPacket { uint16_t magic, len, crc; @@ -316,15 +316,17 @@ protected: } void logTx(mesh::Packet* pkt, int len) override { #ifdef BRIDGE_OVER_SERIAL - SerialPacket spkt; - spkt.len = pkt->writeTo(spkt.payload); + SerialPacket serialpkt; + size_t seriallen = pkt->writeTo(serialpkt.payload); - if (spkt.len > 0) { - spkt.crc = fletcher16(spkt.payload, spkt.len); - BRIDGE_OVER_SERIAL.write((uint8_t *)&spkt, sizeof(SerialPacket)); + if (seriallen - 1 < MAX_TRANS_UNIT - 1) { + serialpkt.len = seriallen; + serialpkt.crc = fletcher16(serialpkt.payload, serialpkt.len); + BRIDGE_OVER_SERIAL.write((uint8_t *)&serialpkt, sizeof(SerialPacket)); #if MESH_PACKET_LOGGING - Serial.printf("BRIDGE: Write to serial len=%d crc=0x%04x\n", spkt.len, spkt.crc); + Serial.print(getLogDateTime()); + Serial.printf(": BRIDGE: Write to serial len=%d crc=0x%04x\n", serialpkt.len, serialpkt.crc); #endif } #endif @@ -763,26 +765,31 @@ public: const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); - for (size_t i = 0; i < len; i++) { - bytes[i] = buffer[(head + 6 + i) % size]; - } + if (len - 1 < MAX_TRANS_UNIT - 1) { + for (size_t i = 0; i < len; i++) { + bytes[i] = buffer[(head + 6 + i) % size]; + } - uint16_t f16 = fletcher16(bytes, len); + uint16_t f16 = fletcher16(bytes, len); #if MESH_PACKET_LOGGING - Serial.printf("BRIDGE: Read from serial len=%d crc=0x%04x valid=%s\n", len, crc, (f16 == crc) ? "true" : "false"); + Serial.print(getLogDateTime()); + Serial.printf(": BRIDGE: Read from serial len=%d crc=0x%04x valid=%s\n", len, crc, + (f16 == crc) ? "true" : "false"); #endif - if (f16 == crc) { - Packet *pkt = _mgr->allocNew(); + if (f16 == crc) { + mesh::Packet *pkt = _mgr->allocNew(); - if (pkt != NULL) { - pkt->readFrom(bytes, len); - _mgr->queueInbound(pkt, millis()); - } else { + if (pkt == NULL) { #if MESH_PACKET_LOGGING - Serial.printf("BRIDGE: Unable to allocate new Packet *pkt"); + Serial.print(getLogDateTime()); + Serial.printf(": BRIDGE: Unable to allocate new Packet *pkt\n"); #endif + } else { + pkt->readFrom(bytes, len); + _mgr->queueInbound(pkt, millis()); + } } } } From 04042e3ca0c1f0c52ddd110d589bdb446d5de4eb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Wed, 9 Jul 2025 11:03:35 +0100 Subject: [PATCH 06/50] Refactor serial bridge handling --- examples/simple_repeater/main.cpp | 170 +++++++++--------- platformio.ini | 1 - variants/heltec_v3/platformio.ini | 25 ++- variants/lilygo_tlora_v2_1/platformio.ini | 25 ++- variants/waveshare_rp2040_lora/platformio.ini | 19 +- 5 files changed, 147 insertions(+), 93 deletions(-) diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index fe065a3..e9683fd 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -80,25 +80,6 @@ #ifdef BRIDGE_OVER_SERIAL #define SERIAL_PKT_MAGIC 0xcafe - -struct SerialPacket { - uint16_t magic, len, crc; - uint8_t payload[MAX_TRANS_UNIT]; - SerialPacket() : magic(SERIAL_PKT_MAGIC), len(0), crc(0) {} -}; - -// Fletcher-16 -// https://en.wikipedia.org/wiki/Fletcher%27s_checksum -static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { - uint8_t sum1 = 0, sum2 = 0; - - for (size_t i = 0; i < len; i++) { - sum1 = (sum1 + bytes[i]) % 255; - sum2 = (sum2 + sum1) % 255; - } - - return (sum2 << 8) | sum1; -}; #endif #define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS @@ -267,6 +248,89 @@ class MyMesh : public mesh::Mesh, public CommonCLICallbacks { #endif } +#ifdef BRIDGE_OVER_SERIAL + struct SerialPacket { + uint16_t magic, len, crc; + uint8_t payload[MAX_TRANS_UNIT]; + SerialPacket() : magic(SERIAL_PKT_MAGIC), len(0), crc(0) {} + }; + + // Fletcher-16 + // https://en.wikipedia.org/wiki/Fletcher%27s_checksum + inline static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { + uint8_t sum1 = 0, sum2 = 0; + + for (size_t i = 0; i < len; i++) { + sum1 = (sum1 + bytes[i]) % 255; + sum2 = (sum2 + sum1) % 255; + } + + return (sum2 << 8) | sum1; + }; + + inline void serialBridgeSendPkt(const mesh::Packet *pkt) { + SerialPacket spkt; + spkt.len = pkt->writeTo(spkt.payload); + spkt.crc = fletcher16(spkt.payload, spkt.len); + BRIDGE_OVER_SERIAL.write((uint8_t *)&spkt, sizeof(SerialPacket)); + +#if MESH_PACKET_LOGGING + Serial.printf("%s: BRIDGE: TX, len=%d crc=0x%04x\n", getLogDateTime(), spkt.len, spkt.crc); +#endif + } + + inline void serialBridgeReceivePkt() { + static constexpr uint16_t size = sizeof(SerialPacket) + 1; + static uint8_t buffer[size]; + static uint16_t tail = 0; + + while (BRIDGE_OVER_SERIAL.available()) { + buffer[tail] = (uint8_t)BRIDGE_OVER_SERIAL.read(); + MESH_DEBUG_PRINT("%02x ", buffer[tail]); + tail = (tail + 1) % size; + + // Check for complete packet by looking back to where the magic number should be + const uint16_t head = (tail - sizeof(SerialPacket) + size) % size; + if ((buffer[head] | (buffer[(head + 1) % size] << 8)) != SERIAL_PKT_MAGIC) { + return; + } + + uint8_t bytes[MAX_TRANS_UNIT]; + const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); + + if (len == 0 || len > sizeof(bytes)) { + MESH_DEBUG_PRINTLN("%s: BRIDGE: RX, invalid packet len", getLogDateTime()); + return; + } + + for (size_t i = 0; i < len; i++) { + bytes[i] = buffer[(head + 6 + i) % size]; + } + + const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); + const uint16_t f16 = fletcher16(bytes, len); + +#if MESH_PACKET_LOGGING + Serial.printf("%s: BRIDGE: RX, len=%d crc=0x%04x\n", getLogDateTime(), len, crc); +#endif + + if ((f16 != crc)) { + MESH_DEBUG_PRINTLN("%s: BRIDGE: RX, invalid packet checksum", getLogDateTime()); + return; + } + + mesh::Packet *pkt = _mgr->allocNew(); + if (pkt == NULL) { + MESH_DEBUG_PRINTLN("%s: BRIDGE: RX, no unused packets available", getLogDateTime()); + return; + } + + pkt->readFrom(bytes, len); + _mgr->queueInbound(pkt, futureMillis(0)); + } + } +#endif + protected: float getAirtimeBudgetFactor() const override { return _prefs.airtime_factor; @@ -316,21 +380,10 @@ protected: } void logTx(mesh::Packet* pkt, int len) override { #ifdef BRIDGE_OVER_SERIAL - SerialPacket serialpkt; - size_t seriallen = pkt->writeTo(serialpkt.payload); - - if (seriallen - 1 < MAX_TRANS_UNIT - 1) { - serialpkt.len = seriallen; - serialpkt.crc = fletcher16(serialpkt.payload, serialpkt.len); - BRIDGE_OVER_SERIAL.write((uint8_t *)&serialpkt, sizeof(SerialPacket)); - -#if MESH_PACKET_LOGGING - Serial.print(getLogDateTime()); - Serial.printf(": BRIDGE: Write to serial len=%d crc=0x%04x\n", serialpkt.len, serialpkt.crc); -#endif + if (!pkt->isMarkedDoNotRetransmit()) { + serialBridgeSendPkt(pkt); } #endif - if (_logging) { File f = openAppend(PACKET_LOG_FILE); if (f) { @@ -747,53 +800,7 @@ public: void loop() { #ifdef BRIDGE_OVER_SERIAL - static constexpr uint16_t size = sizeof(SerialPacket) + 1; - static uint8_t buffer[size]; - static uint16_t tail = 0; - - while (BRIDGE_OVER_SERIAL.available()) { - buffer[tail] = (uint8_t)BRIDGE_OVER_SERIAL.read(); - MESH_DEBUG_PRINT("%02x ", buffer[tail]); - tail = (tail + 1) % size; - - // Check for complete packet by looking back to where the magic number should be - uint16_t head = (tail - sizeof(SerialPacket) + size) % size; - const uint16_t magic = buffer[head] | (buffer[(head + 1) % size] << 8); - - if (magic == SERIAL_PKT_MAGIC) { - uint8_t bytes[MAX_TRANS_UNIT]; - const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); - const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); - - if (len - 1 < MAX_TRANS_UNIT - 1) { - for (size_t i = 0; i < len; i++) { - bytes[i] = buffer[(head + 6 + i) % size]; - } - - uint16_t f16 = fletcher16(bytes, len); - -#if MESH_PACKET_LOGGING - Serial.print(getLogDateTime()); - Serial.printf(": BRIDGE: Read from serial len=%d crc=0x%04x valid=%s\n", len, crc, - (f16 == crc) ? "true" : "false"); -#endif - - if (f16 == crc) { - mesh::Packet *pkt = _mgr->allocNew(); - - if (pkt == NULL) { -#if MESH_PACKET_LOGGING - Serial.print(getLogDateTime()); - Serial.printf(": BRIDGE: Unable to allocate new Packet *pkt\n"); -#endif - } else { - pkt->readFrom(bytes, len); - _mgr->queueInbound(pkt, millis()); - } - } - } - } - } + serialBridgeReceivePkt(); #endif mesh::Mesh::loop(); @@ -829,6 +836,7 @@ static char command[80]; void setup() { Serial.begin(115200); + delay(1000); #ifdef BRIDGE_OVER_SERIAL #if defined(ESP32) @@ -842,13 +850,9 @@ void setup() { #else #error SerialBridge was not tested on the current platform #endif - BRIDGE_OVER_SERIAL.begin(115200); - MESH_DEBUG_PRINTLN("Bridge over serial: enabled"); #endif - delay(1000); - board.begin(); #ifdef DISPLAY_CLASS diff --git a/platformio.ini b/platformio.ini index 36cdf76..90e7cfb 100644 --- a/platformio.ini +++ b/platformio.ini @@ -32,7 +32,6 @@ build_flags = -w -DNDEBUG -DRADIOLIB_STATIC_ONLY=1 -DRADIOLIB_GODMODE=1 build_src_filter = +<*.cpp> + - + ; ----------------- ESP32 --------------------- diff --git a/variants/heltec_v3/platformio.ini b/variants/heltec_v3/platformio.ini index 704958d..16e65bf 100644 --- a/variants/heltec_v3/platformio.ini +++ b/variants/heltec_v3/platformio.ini @@ -49,9 +49,6 @@ build_flags = -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 -; -D BRIDGE_OVER_SERIAL=Serial2 -; -D BRIDGE_OVER_SERIAL_RX=5 -; -D BRIDGE_OVER_SERIAL_TX=6 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${Heltec_lora32_v3.build_src_filter} @@ -61,6 +58,28 @@ lib_deps = ${Heltec_lora32_v3.lib_deps} ${esp32_ota.lib_deps} +[env:Heltec_v3_Bridge] +extends = Heltec_lora32_v3 +build_flags = + ${Heltec_lora32_v3.build_flags} + -D DISPLAY_CLASS=SSD1306Display + -D ADVERT_NAME='"Heltec Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D BRIDGE_OVER_SERIAL=Serial2 + -D BRIDGE_OVER_SERIAL_RX=5 + -D BRIDGE_OVER_SERIAL_TX=6 + -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_lora32_v3.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_lora32_v3.lib_deps} + ${esp32_ota.lib_deps} + [env:Heltec_v3_room_server] extends = Heltec_lora32_v3 build_flags = diff --git a/variants/lilygo_tlora_v2_1/platformio.ini b/variants/lilygo_tlora_v2_1/platformio.ini index a2169f1..adf4a7e 100644 --- a/variants/lilygo_tlora_v2_1/platformio.ini +++ b/variants/lilygo_tlora_v2_1/platformio.ini @@ -57,9 +57,6 @@ build_flags = -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 -; -D BRIDGE_OVER_SERIAL=Serial2 -; -D BRIDGE_OVER_SERIAL_RX=34 -; -D BRIDGE_OVER_SERIAL_TX=25 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 ; -D CORE_DEBUG_LEVEL=3 @@ -67,6 +64,28 @@ lib_deps = ${LilyGo_TLora_V2_1_1_6.lib_deps} ${esp32_ota.lib_deps} +[env:LilyGo_TLora_V2_1_1_6_Bridge] +extends = LilyGo_TLora_V2_1_1_6 +build_src_filter = ${LilyGo_TLora_V2_1_1_6.build_src_filter} + + + +<../examples/simple_repeater> +build_flags = + ${LilyGo_TLora_V2_1_1_6.build_flags} + -D ADVERT_NAME='"TLora-V2.1-1.6 Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D BRIDGE_OVER_SERIAL=Serial2 + -D BRIDGE_OVER_SERIAL_RX=34 + -D BRIDGE_OVER_SERIAL_TX=25 + -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +; -D CORE_DEBUG_LEVEL=3 +lib_deps = + ${LilyGo_TLora_V2_1_1_6.lib_deps} + ${esp32_ota.lib_deps} + [env:LilyGo_TLora_V2_1_1_6_terminal_chat] extends = LilyGo_TLora_V2_1_1_6 build_flags = diff --git a/variants/waveshare_rp2040_lora/platformio.ini b/variants/waveshare_rp2040_lora/platformio.ini index b1e4714..515f702 100644 --- a/variants/waveshare_rp2040_lora/platformio.ini +++ b/variants/waveshare_rp2040_lora/platformio.ini @@ -35,14 +35,27 @@ build_flags = ${waveshare_rp2040_lora.build_flags} -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 -; -D BRIDGE_OVER_SERIAL=Serial2 -; -D BRIDGE_OVER_SERIAL_RX=9 -; -D BRIDGE_OVER_SERIAL_TX=8 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${waveshare_rp2040_lora.build_src_filter} +<../examples/simple_repeater> +[env:waveshare_rp2040_lora_Bridge] +extends = waveshare_rp2040_lora +build_flags = ${waveshare_rp2040_lora.build_flags} + -D ADVERT_NAME='"RP2040-LoRa Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D BRIDGE_OVER_SERIAL=Serial2 + -D BRIDGE_OVER_SERIAL_RX=9 + -D BRIDGE_OVER_SERIAL_TX=8 + -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${waveshare_rp2040_lora.build_src_filter} + +<../examples/simple_repeater> + [env:waveshare_rp2040_lora_room_server] extends = waveshare_rp2040_lora build_flags = ${waveshare_rp2040_lora.build_flags} From 9fd7e9427a528db1cca00cbad1b1d854f2dea6de Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Mon, 1 Sep 2025 10:53:51 +0100 Subject: [PATCH 07/50] Add bridge support for WSL3 board --- variants/heltec_v3/platformio.ini | 23 ++++++++++++++++++- variants/lilygo_tlora_v2_1/platformio.ini | 2 +- variants/waveshare_rp2040_lora/platformio.ini | 2 +- 3 files changed, 24 insertions(+), 3 deletions(-) diff --git a/variants/heltec_v3/platformio.ini b/variants/heltec_v3/platformio.ini index 1d2baa2..3e7524c 100644 --- a/variants/heltec_v3/platformio.ini +++ b/variants/heltec_v3/platformio.ini @@ -49,7 +49,7 @@ lib_deps = ${esp32_ota.lib_deps} bakercp/CRC32 @ ^2.0.0 -[env:Heltec_v3_Bridge] +[env:Heltec_v3_repeater_bridge] extends = Heltec_lora32_v3 build_flags = ${Heltec_lora32_v3.build_flags} @@ -208,6 +208,27 @@ lib_deps = ${esp32_ota.lib_deps} bakercp/CRC32 @ ^2.0.0 +[env:Heltec_WSL3_repeater_bridge] +extends = Heltec_lora32_v3 +build_flags = + ${Heltec_lora32_v3.build_flags} + -D ADVERT_NAME='"Heltec WSL3 Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D BRIDGE_OVER_SERIAL=Serial2 + -D BRIDGE_OVER_SERIAL_RX=5 + -D BRIDGE_OVER_SERIAL_TX=6 +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_lora32_v3.build_src_filter} + +<../examples/simple_repeater> +lib_deps = + ${Heltec_lora32_v3.lib_deps} + ${esp32_ota.lib_deps} + bakercp/CRC32 @ ^2.0.0 + [env:Heltec_WSL3_room_server] extends = Heltec_lora32_v3 build_src_filter = ${Heltec_lora32_v3.build_src_filter} diff --git a/variants/lilygo_tlora_v2_1/platformio.ini b/variants/lilygo_tlora_v2_1/platformio.ini index 4e2078c..4e146cf 100644 --- a/variants/lilygo_tlora_v2_1/platformio.ini +++ b/variants/lilygo_tlora_v2_1/platformio.ini @@ -64,7 +64,7 @@ lib_deps = ${LilyGo_TLora_V2_1_1_6.lib_deps} ${esp32_ota.lib_deps} -[env:LilyGo_TLora_V2_1_1_6_Bridge] +[env:LilyGo_TLora_V2_1_1_6_repeater_bridge] extends = LilyGo_TLora_V2_1_1_6 build_src_filter = ${LilyGo_TLora_V2_1_1_6.build_src_filter} + diff --git a/variants/waveshare_rp2040_lora/platformio.ini b/variants/waveshare_rp2040_lora/platformio.ini index 60b39ad..0ec745f 100644 --- a/variants/waveshare_rp2040_lora/platformio.ini +++ b/variants/waveshare_rp2040_lora/platformio.ini @@ -40,7 +40,7 @@ build_flags = ${waveshare_rp2040_lora.build_flags} build_src_filter = ${waveshare_rp2040_lora.build_src_filter} +<../examples/simple_repeater> -[env:waveshare_rp2040_lora_Bridge] +[env:waveshare_rp2040_lora_repeater_bridge] extends = waveshare_rp2040_lora build_flags = ${waveshare_rp2040_lora.build_flags} -D ADVERT_NAME='"RP2040-LoRa Bridge"' From 1948d284a022b3951e5b6b607b13ca0eed71bc1d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Thu, 4 Sep 2025 23:43:05 +0100 Subject: [PATCH 08/50] Extract serial bridge into dedicated classes This commit refactors the serial bridge functionality out of the `simple_repeater` example and into a more reusable, object-oriented structure. An `AbstractBridge` interface has been introduced, along with a concrete `SerialBridge` implementation. This encapsulates all the logic for packet framing, checksum calculation, and serial communication, cleaning up the main example file significantly. The `simple_repeater` example now instantiates and uses the `SerialBridge` class, resulting in better separation of concerns and improved code organization. --- examples/simple_repeater/main.cpp | 109 +++--------------------------- src/helpers/AbstractBridge.h | 32 +++++++++ src/helpers/SerialBridge.cpp | 98 +++++++++++++++++++++++++++ src/helpers/SerialBridge.h | 30 ++++++++ 4 files changed, 171 insertions(+), 98 deletions(-) create mode 100644 src/helpers/AbstractBridge.h create mode 100644 src/helpers/SerialBridge.cpp create mode 100644 src/helpers/SerialBridge.h diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 7e44d40..7150f0b 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -79,7 +79,7 @@ /* ------------------------------ Code -------------------------------- */ #ifdef BRIDGE_OVER_SERIAL -#define SERIAL_PKT_MAGIC 0xcafe +#include "helpers/SerialBridge.h" #endif #define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS @@ -118,6 +118,10 @@ struct ClientInfo { #define MAX_CLIENTS 32 #endif +#ifdef BRIDGE_OVER_SERIAL +AbstractBridge* bridge; +#endif + struct NeighbourInfo { mesh::Identity id; uint32_t advert_timestamp; @@ -256,89 +260,6 @@ class MyMesh : public mesh::Mesh, public CommonCLICallbacks { #endif } -#ifdef BRIDGE_OVER_SERIAL - struct SerialPacket { - uint16_t magic, len, crc; - uint8_t payload[MAX_TRANS_UNIT]; - SerialPacket() : magic(SERIAL_PKT_MAGIC), len(0), crc(0) {} - }; - - // Fletcher-16 - // https://en.wikipedia.org/wiki/Fletcher%27s_checksum - inline static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { - uint8_t sum1 = 0, sum2 = 0; - - for (size_t i = 0; i < len; i++) { - sum1 = (sum1 + bytes[i]) % 255; - sum2 = (sum2 + sum1) % 255; - } - - return (sum2 << 8) | sum1; - }; - - inline void serialBridgeSendPkt(const mesh::Packet *pkt) { - SerialPacket spkt; - spkt.len = pkt->writeTo(spkt.payload); - spkt.crc = fletcher16(spkt.payload, spkt.len); - BRIDGE_OVER_SERIAL.write((uint8_t *)&spkt, sizeof(SerialPacket)); - -#if MESH_PACKET_LOGGING - Serial.printf("%s: BRIDGE: TX, len=%d crc=0x%04x\n", getLogDateTime(), spkt.len, spkt.crc); -#endif - } - - inline void serialBridgeReceivePkt() { - static constexpr uint16_t size = sizeof(SerialPacket) + 1; - static uint8_t buffer[size]; - static uint16_t tail = 0; - - while (BRIDGE_OVER_SERIAL.available()) { - buffer[tail] = (uint8_t)BRIDGE_OVER_SERIAL.read(); - MESH_DEBUG_PRINT("%02x ", buffer[tail]); - tail = (tail + 1) % size; - - // Check for complete packet by looking back to where the magic number should be - const uint16_t head = (tail - sizeof(SerialPacket) + size) % size; - if ((buffer[head] | (buffer[(head + 1) % size] << 8)) != SERIAL_PKT_MAGIC) { - return; - } - - uint8_t bytes[MAX_TRANS_UNIT]; - const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); - - if (len == 0 || len > sizeof(bytes)) { - MESH_DEBUG_PRINTLN("%s: BRIDGE: RX, invalid packet len", getLogDateTime()); - return; - } - - for (size_t i = 0; i < len; i++) { - bytes[i] = buffer[(head + 6 + i) % size]; - } - - const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); - const uint16_t f16 = fletcher16(bytes, len); - -#if MESH_PACKET_LOGGING - Serial.printf("%s: BRIDGE: RX, len=%d crc=0x%04x\n", getLogDateTime(), len, crc); -#endif - - if ((f16 != crc)) { - MESH_DEBUG_PRINTLN("%s: BRIDGE: RX, invalid packet checksum", getLogDateTime()); - return; - } - - mesh::Packet *pkt = _mgr->allocNew(); - if (pkt == NULL) { - MESH_DEBUG_PRINTLN("%s: BRIDGE: RX, no unused packets available", getLogDateTime()); - return; - } - - pkt->readFrom(bytes, len); - _mgr->queueInbound(pkt, futureMillis(0)); - } - } -#endif - protected: float getAirtimeBudgetFactor() const override { return _prefs.airtime_factor; @@ -389,7 +310,7 @@ protected: void logTx(mesh::Packet* pkt, int len) override { #ifdef BRIDGE_OVER_SERIAL if (!pkt->isMarkedDoNotRetransmit()) { - serialBridgeSendPkt(pkt); + bridge->onPacketTransmitted(pkt); } #endif if (_logging) { @@ -657,6 +578,9 @@ public: : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) { +#ifdef BRIDGE_OVER_SERIAL + bridge = new SerialBridge(BRIDGE_OVER_SERIAL, _mgr); +#endif memset(known_clients, 0, sizeof(known_clients)); next_local_advert = next_flood_advert = 0; set_radio_at = revert_radio_at = 0; @@ -858,7 +782,7 @@ public: void loop() { #ifdef BRIDGE_OVER_SERIAL - serialBridgeReceivePkt(); + bridge->loop(); #endif mesh::Mesh::loop(); @@ -910,18 +834,7 @@ void setup() { delay(1000); #ifdef BRIDGE_OVER_SERIAL -#if defined(ESP32) - BRIDGE_OVER_SERIAL.setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); -#elif defined(RP2040_PLATFORM) - BRIDGE_OVER_SERIAL.setRX(BRIDGE_OVER_SERIAL_RX); - BRIDGE_OVER_SERIAL.setTX(BRIDGE_OVER_SERIAL_TX); -#elif defined(STM32_PLATFORM) - BRIDGE_OVER_SERIAL.setRx(BRIDGE_OVER_SERIAL_RX); - BRIDGE_OVER_SERIAL.setTx(BRIDGE_OVER_SERIAL_TX); -#else -#error SerialBridge was not tested on the current platform -#endif - BRIDGE_OVER_SERIAL.begin(115200); + bridge->begin(); #endif board.begin(); diff --git a/src/helpers/AbstractBridge.h b/src/helpers/AbstractBridge.h new file mode 100644 index 0000000..930eea6 --- /dev/null +++ b/src/helpers/AbstractBridge.h @@ -0,0 +1,32 @@ +#pragma once + +#include + +class AbstractBridge { +public: + virtual ~AbstractBridge() {} + + /** + * @brief Initializes the bridge. + */ + virtual void begin() = 0; + + /** + * @brief A method to be called on every main loop iteration. + * Used for tasks like checking for incoming data. + */ + virtual void loop() = 0; + + /** + * @brief A callback that is triggered when the mesh transmits a packet. + * The bridge can use this to forward the packet. + * + * @param packet The packet that was transmitted. + */ + virtual void onPacketTransmitted(mesh::Packet* packet) = 0; + + /** + * @brief Processes a received packet from the bridge's medium. + */ + virtual void onPacketReceived() = 0; +}; diff --git a/src/helpers/SerialBridge.cpp b/src/helpers/SerialBridge.cpp new file mode 100644 index 0000000..235661a --- /dev/null +++ b/src/helpers/SerialBridge.cpp @@ -0,0 +1,98 @@ +#include "SerialBridge.h" +#include + +#ifdef BRIDGE_OVER_SERIAL + +#define SERIAL_PKT_MAGIC 0xcafe + +struct SerialPacket { + uint16_t magic, len, crc; + uint8_t payload[MAX_TRANS_UNIT]; + SerialPacket() : magic(SERIAL_PKT_MAGIC), len(0), crc(0) {} +}; + +// Fletcher-16 +// https://en.wikipedia.org/wiki/Fletcher%27s_checksum +inline static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { + uint8_t sum1 = 0, sum2 = 0; + + for (size_t i = 0; i < len; i++) { + sum1 = (sum1 + bytes[i]) % 255; + sum2 = (sum2 + sum1) % 255; + } + + return (sum2 << 8) | sum1; +}; + +SerialBridge::SerialBridge(Stream& serial, mesh::PacketManager* mgr) : _serial(&serial), _mgr(mgr) {} + +void SerialBridge::begin() { +#if defined(ESP32) + ((HardwareSerial*)_serial)->setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); +#elif defined(RP2040_PLATFORM) + ((HardwareSerial*)_serial)->setRX(BRIDGE_OVER_SERIAL_RX); + ((HardwareSerial*)_serial)->setTX(BRIDGE_OVER_SERIAL_TX); +#elif defined(STM32_PLATFORM) + ((HardwareSerial*)_serial)->setRx(BRIDGE_OVER_SERIAL_RX); + ((HardwareSerial*)_serial)->setTx(BRIDGE_OVER_SERIAL_TX); +#else +#error SerialBridge was not tested on the current platform +#endif + ((HardwareSerial*)_serial)->begin(115200); +} + +void SerialBridge::onPacketTransmitted(mesh::Packet* packet) { + SerialPacket spkt; + spkt.len = packet->writeTo(spkt.payload); + spkt.crc = fletcher16(spkt.payload, spkt.len); + _serial->write((uint8_t *)&spkt, sizeof(SerialPacket)); +} + +void SerialBridge::loop() { + while (_serial->available()) { + onPacketReceived(); + } +} + +void SerialBridge::onPacketReceived() { + static constexpr uint16_t size = sizeof(SerialPacket) + 1; + static uint8_t buffer[size]; + static uint16_t tail = 0; + + buffer[tail] = (uint8_t)_serial->read(); + tail = (tail + 1) % size; + + // Check for complete packet by looking back to where the magic number should be + const uint16_t head = (tail - sizeof(SerialPacket) + size) % size; + if ((buffer[head] | (buffer[(head + 1) % size] << 8)) != SERIAL_PKT_MAGIC) { + return; + } + + uint8_t bytes[MAX_TRANS_UNIT]; + const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); + + if (len == 0 || len > sizeof(bytes)) { + return; + } + + for (size_t i = 0; i < len; i++) { + bytes[i] = buffer[(head + 6 + i) % size]; + } + + const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); + const uint16_t f16 = fletcher16(bytes, len); + + if ((f16 != crc)) { + return; + } + + mesh::Packet *new_pkt = _mgr->allocNew(); + if (new_pkt == NULL) { + return; + } + + new_pkt->readFrom(bytes, len); + _mgr->queueInbound(new_pkt, 0); +} + +#endif diff --git a/src/helpers/SerialBridge.h b/src/helpers/SerialBridge.h new file mode 100644 index 0000000..3a4f077 --- /dev/null +++ b/src/helpers/SerialBridge.h @@ -0,0 +1,30 @@ +#pragma once + +#include "helpers/AbstractBridge.h" +#include + +#ifdef BRIDGE_OVER_SERIAL + +/** + * @brief A bridge implementation that uses a serial port to connect two mesh networks. + */ +class SerialBridge : public AbstractBridge { +public: + /** + * @brief Construct a new Serial Bridge object + * + * @param serial The serial port to use for the bridge. + * @param mgr A pointer to the packet manager. + */ + SerialBridge(Stream& serial, mesh::PacketManager* mgr); + void begin() override; + void loop() override; + void onPacketTransmitted(mesh::Packet* packet) override; + void onPacketReceived() override; + +private: + Stream* _serial; + mesh::PacketManager* _mgr; +}; + +#endif From ee3c4baea5e420f8798ad313861fb1ed5bb2f730 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Thu, 4 Sep 2025 23:50:13 +0100 Subject: [PATCH 09/50] Prevent packet loops and duplicates Implement a "seen packets" table to track packets that have already been processed by the serial bridge. This prevents packets from being re-transmitted over the serial link if they have already been seen, and it stops inbound packets from serial from being re-injected into the mesh if they are duplicates. Duplicate inbound packets are now freed to prevent memory leaks. --- src/helpers/SerialBridge.cpp | 16 +++++++++++----- src/helpers/SerialBridge.h | 2 ++ 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/src/helpers/SerialBridge.cpp b/src/helpers/SerialBridge.cpp index 235661a..bbd2e0d 100644 --- a/src/helpers/SerialBridge.cpp +++ b/src/helpers/SerialBridge.cpp @@ -42,10 +42,12 @@ void SerialBridge::begin() { } void SerialBridge::onPacketTransmitted(mesh::Packet* packet) { - SerialPacket spkt; - spkt.len = packet->writeTo(spkt.payload); - spkt.crc = fletcher16(spkt.payload, spkt.len); - _serial->write((uint8_t *)&spkt, sizeof(SerialPacket)); + if (!_seen_packets.hasSeen(packet)) { + SerialPacket spkt; + spkt.len = packet->writeTo(spkt.payload); + spkt.crc = fletcher16(spkt.payload, spkt.len); + _serial->write((uint8_t *)&spkt, sizeof(SerialPacket)); + } } void SerialBridge::loop() { @@ -92,7 +94,11 @@ void SerialBridge::onPacketReceived() { } new_pkt->readFrom(bytes, len); - _mgr->queueInbound(new_pkt, 0); + if (!_seen_packets.hasSeen(new_pkt)) { + _mgr->queueInbound(new_pkt, 0); + } else { + _mgr->free(new_pkt); + } } #endif diff --git a/src/helpers/SerialBridge.h b/src/helpers/SerialBridge.h index 3a4f077..fe3c176 100644 --- a/src/helpers/SerialBridge.h +++ b/src/helpers/SerialBridge.h @@ -1,6 +1,7 @@ #pragma once #include "helpers/AbstractBridge.h" +#include "helpers/SimpleMeshTables.h" #include #ifdef BRIDGE_OVER_SERIAL @@ -25,6 +26,7 @@ public: private: Stream* _serial; mesh::PacketManager* _mgr; + SimpleMeshTables _seen_packets; }; #endif From 2b920dfed32ae548812bba1383d3b2a734bfc8d0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Fri, 5 Sep 2025 01:50:50 +0100 Subject: [PATCH 10/50] Rework packet serialization and parsing --- src/helpers/AbstractBridge.h | 4 +- src/helpers/SerialBridge.cpp | 106 +++++++++++++++++------------------ src/helpers/SerialBridge.h | 28 ++++++++- 3 files changed, 82 insertions(+), 56 deletions(-) diff --git a/src/helpers/AbstractBridge.h b/src/helpers/AbstractBridge.h index 930eea6..a348e93 100644 --- a/src/helpers/AbstractBridge.h +++ b/src/helpers/AbstractBridge.h @@ -27,6 +27,8 @@ public: /** * @brief Processes a received packet from the bridge's medium. + * + * @param packet The packet that was received. */ - virtual void onPacketReceived() = 0; + virtual void onPacketReceived(mesh::Packet* packet) = 0; }; diff --git a/src/helpers/SerialBridge.cpp b/src/helpers/SerialBridge.cpp index bbd2e0d..c56645b 100644 --- a/src/helpers/SerialBridge.cpp +++ b/src/helpers/SerialBridge.cpp @@ -3,14 +3,6 @@ #ifdef BRIDGE_OVER_SERIAL -#define SERIAL_PKT_MAGIC 0xcafe - -struct SerialPacket { - uint16_t magic, len, crc; - uint8_t payload[MAX_TRANS_UNIT]; - SerialPacket() : magic(SERIAL_PKT_MAGIC), len(0), crc(0) {} -}; - // Fletcher-16 // https://en.wikipedia.org/wiki/Fletcher%27s_checksum inline static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { @@ -43,61 +35,67 @@ void SerialBridge::begin() { void SerialBridge::onPacketTransmitted(mesh::Packet* packet) { if (!_seen_packets.hasSeen(packet)) { - SerialPacket spkt; - spkt.len = packet->writeTo(spkt.payload); - spkt.crc = fletcher16(spkt.payload, spkt.len); - _serial->write((uint8_t *)&spkt, sizeof(SerialPacket)); + uint8_t buffer[MAX_SERIAL_PACKET_SIZE]; + uint16_t len = packet->writeTo(buffer + 4); + + buffer[0] = (SERIAL_PKT_MAGIC >> 8) & 0xFF; + buffer[1] = SERIAL_PKT_MAGIC & 0xFF; + buffer[2] = (len >> 8) & 0xFF; + buffer[3] = len & 0xFF; + + uint16_t checksum = fletcher16(buffer + 4, len); + buffer[4 + len] = (checksum >> 8) & 0xFF; + buffer[5 + len] = checksum & 0xFF; + + _serial->write(buffer, len + SERIAL_OVERHEAD); } } void SerialBridge::loop() { while (_serial->available()) { - onPacketReceived(); + uint8_t b = _serial->read(); + + if (_rx_buffer_pos < 2) { + // Waiting for magic word + if ((_rx_buffer_pos == 0 && b == ((SERIAL_PKT_MAGIC >> 8) & 0xFF)) || + (_rx_buffer_pos == 1 && b == (SERIAL_PKT_MAGIC & 0xFF))) { + _rx_buffer[_rx_buffer_pos++] = b; + } else { + _rx_buffer_pos = 0; + } + } else { + // Reading length, payload, and checksum + _rx_buffer[_rx_buffer_pos++] = b; + + if (_rx_buffer_pos >= 4) { + uint16_t len = (_rx_buffer[2] << 8) | _rx_buffer[3]; + if (len > MAX_PACKET_PAYLOAD) { + _rx_buffer_pos = 0; // Invalid length, reset + return; + } + + if (_rx_buffer_pos == len + SERIAL_OVERHEAD) { // Full packet received + uint16_t checksum = (_rx_buffer[4 + len] << 8) | _rx_buffer[5 + len]; + if (checksum == fletcher16(_rx_buffer + 4, len)) { + mesh::Packet *pkt = _mgr->allocNew(); + if (pkt) { + memcpy(pkt->payload, _rx_buffer + 4, len); + pkt->payload_len = len; + onPacketReceived(pkt); + } + } + _rx_buffer_pos = 0; // Reset for next packet + } + } + } } } -void SerialBridge::onPacketReceived() { - static constexpr uint16_t size = sizeof(SerialPacket) + 1; - static uint8_t buffer[size]; - static uint16_t tail = 0; - - buffer[tail] = (uint8_t)_serial->read(); - tail = (tail + 1) % size; - - // Check for complete packet by looking back to where the magic number should be - const uint16_t head = (tail - sizeof(SerialPacket) + size) % size; - if ((buffer[head] | (buffer[(head + 1) % size] << 8)) != SERIAL_PKT_MAGIC) { - return; - } - - uint8_t bytes[MAX_TRANS_UNIT]; - const uint16_t len = buffer[(head + 2) % size] | (buffer[(head + 3) % size] << 8); - - if (len == 0 || len > sizeof(bytes)) { - return; - } - - for (size_t i = 0; i < len; i++) { - bytes[i] = buffer[(head + 6 + i) % size]; - } - - const uint16_t crc = buffer[(head + 4) % size] | (buffer[(head + 5) % size] << 8); - const uint16_t f16 = fletcher16(bytes, len); - - if ((f16 != crc)) { - return; - } - - mesh::Packet *new_pkt = _mgr->allocNew(); - if (new_pkt == NULL) { - return; - } - - new_pkt->readFrom(bytes, len); - if (!_seen_packets.hasSeen(new_pkt)) { - _mgr->queueInbound(new_pkt, 0); +void SerialBridge::onPacketReceived(mesh::Packet* packet) { + if (!_seen_packets.hasSeen(packet)) { + _mgr->queueInbound(packet, 0); } else { - _mgr->free(new_pkt); + _mgr->free(packet); } } diff --git a/src/helpers/SerialBridge.h b/src/helpers/SerialBridge.h index fe3c176..7b72987 100644 --- a/src/helpers/SerialBridge.h +++ b/src/helpers/SerialBridge.h @@ -21,12 +21,38 @@ public: void begin() override; void loop() override; void onPacketTransmitted(mesh::Packet* packet) override; - void onPacketReceived() override; + void onPacketReceived(mesh::Packet* packet) override; private: + /** + * @brief The 2-byte magic word used to signify the start of a packet. + */ + static constexpr uint16_t SERIAL_PKT_MAGIC = 0xCAFE; + + /** + * @brief The total overhead of the serial protocol in bytes. + * [MAGIC_WORD (2 bytes)] [LENGTH (2 bytes)] [PAYLOAD (variable)] [CHECKSUM (2 bytes)] + */ + static constexpr uint16_t SERIAL_OVERHEAD = 6; + + /** + * @brief The maximum size of a packet on the serial line. + * + * This is calculated as the sum of: + * - 1 byte for the packet header (from mesh::Packet) + * - 4 bytes for transport codes (from mesh::Packet) + * - 1 byte for the path length (from mesh::Packet) + * - MAX_PATH_SIZE for the path itself (from MeshCore.h) + * - MAX_PACKET_PAYLOAD for the payload (from MeshCore.h) + * - SERIAL_OVERHEAD for the serial framing + */ + static constexpr uint16_t MAX_SERIAL_PACKET_SIZE = (MAX_TRANS_UNIT + 1) + SERIAL_OVERHEAD; + Stream* _serial; mesh::PacketManager* _mgr; SimpleMeshTables _seen_packets; + uint8_t _rx_buffer[MAX_SERIAL_PACKET_SIZE]; // Buffer for serial data + uint16_t _rx_buffer_pos = 0; }; #endif From 77ab19153e9c36eddf7f4c3546e1c5c6f0ec7396 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Fri, 5 Sep 2025 02:07:26 +0100 Subject: [PATCH 11/50] Add serial logging for TX/RX packets --- examples/simple_repeater/main.cpp | 2 +- src/helpers/SerialBridge.cpp | 18 +++++++++++++++++- src/helpers/SerialBridge.h | 5 ++++- 3 files changed, 22 insertions(+), 3 deletions(-) diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 7150f0b..93d3656 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -579,7 +579,7 @@ public: _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) { #ifdef BRIDGE_OVER_SERIAL - bridge = new SerialBridge(BRIDGE_OVER_SERIAL, _mgr); + bridge = new SerialBridge(BRIDGE_OVER_SERIAL, _mgr, &rtc); #endif memset(known_clients, 0, sizeof(known_clients)); next_local_advert = next_flood_advert = 0; diff --git a/src/helpers/SerialBridge.cpp b/src/helpers/SerialBridge.cpp index c56645b..f971e39 100644 --- a/src/helpers/SerialBridge.cpp +++ b/src/helpers/SerialBridge.cpp @@ -1,5 +1,6 @@ #include "SerialBridge.h" #include +#include #ifdef BRIDGE_OVER_SERIAL @@ -16,7 +17,15 @@ inline static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { return (sum2 << 8) | sum1; }; -SerialBridge::SerialBridge(Stream& serial, mesh::PacketManager* mgr) : _serial(&serial), _mgr(mgr) {} +const char* SerialBridge::getLogDateTime() { + static char tmp[32]; + uint32_t now = _rtc->getCurrentTime(); + DateTime dt = DateTime(now); + sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), dt.year()); + return tmp; +} + +SerialBridge::SerialBridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc) : _serial(&serial), _mgr(mgr), _rtc(rtc) {} void SerialBridge::begin() { #if defined(ESP32) @@ -48,6 +57,10 @@ void SerialBridge::onPacketTransmitted(mesh::Packet* packet) { buffer[5 + len] = checksum & 0xFF; _serial->write(buffer, len + SERIAL_OVERHEAD); + +#if MESH_PACKET_LOGGING + Serial.printf("%s: BRIDGE: TX, len=%d crc=0x%04x\n", getLogDateTime(), len, checksum); +#endif } } @@ -77,6 +90,9 @@ void SerialBridge::loop() { if (_rx_buffer_pos == len + SERIAL_OVERHEAD) { // Full packet received uint16_t checksum = (_rx_buffer[4 + len] << 8) | _rx_buffer[5 + len]; if (checksum == fletcher16(_rx_buffer + 4, len)) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: BRIDGE: RX, len=%d crc=0x%04x\n", getLogDateTime(), len, checksum); +#endif mesh::Packet *pkt = _mgr->allocNew(); if (pkt) { memcpy(pkt->payload, _rx_buffer + 4, len); diff --git a/src/helpers/SerialBridge.h b/src/helpers/SerialBridge.h index 7b72987..cc837d5 100644 --- a/src/helpers/SerialBridge.h +++ b/src/helpers/SerialBridge.h @@ -16,14 +16,16 @@ public: * * @param serial The serial port to use for the bridge. * @param mgr A pointer to the packet manager. + * @param rtc A pointer to the RTC clock. */ - SerialBridge(Stream& serial, mesh::PacketManager* mgr); + SerialBridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc); void begin() override; void loop() override; void onPacketTransmitted(mesh::Packet* packet) override; void onPacketReceived(mesh::Packet* packet) override; private: + const char* getLogDateTime(); /** * @brief The 2-byte magic word used to signify the start of a packet. */ @@ -50,6 +52,7 @@ private: Stream* _serial; mesh::PacketManager* _mgr; + mesh::RTCClock* _rtc; SimpleMeshTables _seen_packets; uint8_t _rx_buffer[MAX_SERIAL_PACKET_SIZE]; // Buffer for serial data uint16_t _rx_buffer_pos = 0; From 375093f78df41e1632afb5f3362d71441442f2fd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Fri, 5 Sep 2025 09:22:06 +0100 Subject: [PATCH 12/50] Add nRF52 support and refactor packet handling This commit introduces several improvements to the SerialBridge helper: - Adds support for the nRF52 platform by implementing the `setPins` configuration. - Corrects the type cast for the RP2040 platform from `HardwareSerial` to `SerialUART`. - Refactors packet deserialization to use a new `Packet::readFrom()` method instead of a direct `memcpy`, improving encapsulation. - Updates the packet length validation to use the more appropriate `MAX_TRANS_UNIT` constant. --- src/helpers/SerialBridge.cpp | 27 ++++++++++++++------------- 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/src/helpers/SerialBridge.cpp b/src/helpers/SerialBridge.cpp index f971e39..eefd751 100644 --- a/src/helpers/SerialBridge.cpp +++ b/src/helpers/SerialBridge.cpp @@ -29,13 +29,15 @@ SerialBridge::SerialBridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCCl void SerialBridge::begin() { #if defined(ESP32) - ((HardwareSerial*)_serial)->setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); + ((HardwareSerial *)_serial)->setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); +#elif defined(NRF52_PLATFORM) + ((HardwareSerial *)_serial)->setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); #elif defined(RP2040_PLATFORM) - ((HardwareSerial*)_serial)->setRX(BRIDGE_OVER_SERIAL_RX); - ((HardwareSerial*)_serial)->setTX(BRIDGE_OVER_SERIAL_TX); + ((SerialUART *)_serial)->setRX(BRIDGE_OVER_SERIAL_RX); + ((SerialUART *)_serial)->setTX(BRIDGE_OVER_SERIAL_TX); #elif defined(STM32_PLATFORM) - ((HardwareSerial*)_serial)->setRx(BRIDGE_OVER_SERIAL_RX); - ((HardwareSerial*)_serial)->setTx(BRIDGE_OVER_SERIAL_TX); + ((HardwareSerial *)_serial)->setRx(BRIDGE_OVER_SERIAL_RX); + ((HardwareSerial *)_serial)->setTx(BRIDGE_OVER_SERIAL_TX); #else #error SerialBridge was not tested on the current platform #endif @@ -82,21 +84,20 @@ void SerialBridge::loop() { if (_rx_buffer_pos >= 4) { uint16_t len = (_rx_buffer[2] << 8) | _rx_buffer[3]; - if (len > MAX_PACKET_PAYLOAD) { + if (len > (MAX_TRANS_UNIT + 1)) { _rx_buffer_pos = 0; // Invalid length, reset return; } - if (_rx_buffer_pos == len + SERIAL_OVERHEAD) { // Full packet received - uint16_t checksum = (_rx_buffer[4 + len] << 8) | _rx_buffer[5 + len]; - if (checksum == fletcher16(_rx_buffer + 4, len)) { + if (_rx_buffer_pos == len + SERIAL_OVERHEAD) { // Full packet received + uint16_t checksum = (_rx_buffer[4 + len] << 8) | _rx_buffer[5 + len]; + if (checksum == fletcher16(_rx_buffer + 4, len)) { #if MESH_PACKET_LOGGING - Serial.printf("%s: BRIDGE: RX, len=%d crc=0x%04x\n", getLogDateTime(), len, checksum); + Serial.printf("%s: BRIDGE: RX, len=%d crc=0x%04x\n", getLogDateTime(), len, checksum); #endif - mesh::Packet *pkt = _mgr->allocNew(); + mesh::Packet* pkt = _mgr->allocNew(); if (pkt) { - memcpy(pkt->payload, _rx_buffer + 4, len); - pkt->payload_len = len; + pkt->readFrom(_rx_buffer + 4, len); onPacketReceived(pkt); } } From 963556f9ba85c7334ffd4e489ff44ed7479f43b9 Mon Sep 17 00:00:00 2001 From: ViezeVingertjes Date: Fri, 5 Sep 2025 10:46:51 +0200 Subject: [PATCH 13/50] Updated BLE functionality for low power mode in SerialBLEInterface. Updated platformio.ini to enable low power mode and added DC/DC converter support in T1000eBoard for improved power efficiency. --- src/helpers/nrf52/SerialBLEInterface.cpp | 32 +++++++++++++++++++++--- variants/t1000-e/T1000eBoard.cpp | 3 +++ variants/t1000-e/platformio.ini | 1 + 3 files changed, 32 insertions(+), 4 deletions(-) diff --git a/src/helpers/nrf52/SerialBLEInterface.cpp b/src/helpers/nrf52/SerialBLEInterface.cpp index 170a733..283fe40 100644 --- a/src/helpers/nrf52/SerialBLEInterface.cpp +++ b/src/helpers/nrf52/SerialBLEInterface.cpp @@ -25,10 +25,28 @@ void SerialBLEInterface::begin(const char* device_name, uint32_t pin_code) { char charpin[20]; sprintf(charpin, "%d", pin_code); - Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); - Bluefruit.configPrphConn(250, BLE_GAP_EVENT_LENGTH_MIN, 16, 16); // increase MTU + Bluefruit.configPrphBandwidth( +#ifdef BLE_LOW_POWER + BANDWIDTH_NORMAL +#else + BANDWIDTH_MAX +#endif + ); + Bluefruit.configPrphConn( +#ifdef BLE_LOW_POWER + 400, BLE_GAP_EVENT_LENGTH_MIN, 8, 8 +#else + 250, BLE_GAP_EVENT_LENGTH_MIN, 16, 16 // increase MTU +#endif + ); Bluefruit.begin(); - Bluefruit.setTxPower(4); // Check bluefruit.h for supported values + Bluefruit.setTxPower( +#ifdef BLE_LOW_POWER + 0 +#else + 4 +#endif + ); // Check bluefruit.h for supported values Bluefruit.setName(device_name); Bluefruit.Security.setMITM(true); @@ -80,7 +98,13 @@ void SerialBLEInterface::startAdv() { * https://developer.apple.com/library/content/qa/qa1931/_index.html */ Bluefruit.Advertising.restartOnDisconnect(false); // don't restart automatically as we handle it in onDisconnect - Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setInterval( +#ifdef BLE_LOW_POWER + 160, 1600 +#else + 32, 244 +#endif + ); // in unit of 0.625 ms Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds diff --git a/variants/t1000-e/T1000eBoard.cpp b/variants/t1000-e/T1000eBoard.cpp index a17711d..4bcdf98 100644 --- a/variants/t1000-e/T1000eBoard.cpp +++ b/variants/t1000-e/T1000eBoard.cpp @@ -11,6 +11,9 @@ void T1000eBoard::begin() { sd_power_mode_set(NRF_POWER_MODE_LOWPWR); + // Enable DC/DC converter for improved power efficiency + NRF_POWER->DCDCEN = 1; + #ifdef BUTTON_PIN pinMode(BATTERY_PIN, INPUT); pinMode(BUTTON_PIN, INPUT); diff --git a/variants/t1000-e/platformio.ini b/variants/t1000-e/platformio.ini index b182613..88c0b45 100644 --- a/variants/t1000-e/platformio.ini +++ b/variants/t1000-e/platformio.ini @@ -100,6 +100,7 @@ build_flags = ${t1000-e.build_flags} -D MAX_CONTACTS=100 -D MAX_GROUP_CHANNELS=8 -D BLE_PIN_CODE=123456 + -D BLE_LOW_POWER=1 ; -D BLE_DEBUG_LOGGING=1 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 From 5843a12c71c094ef6e928ab714e253c8593c9c33 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Fri, 5 Sep 2025 11:28:40 +0100 Subject: [PATCH 14/50] Rename `SerialBridge` to `RS232Bridge` --- examples/simple_repeater/main.cpp | 16 ++++----- .../RS232Bridge.cpp} | 34 +++++++++++-------- .../{SerialBridge.h => bridges/RS232Bridge.h} | 6 ++-- variants/heltec_v3/platformio.ini | 14 ++++---- variants/lilygo_tlora_v2_1/platformio.ini | 7 ++-- variants/waveshare_rp2040_lora/platformio.ini | 7 ++-- 6 files changed, 46 insertions(+), 38 deletions(-) rename src/helpers/{SerialBridge.cpp => bridges/RS232Bridge.cpp} (73%) rename src/helpers/{SerialBridge.h => bridges/RS232Bridge.h} (92%) diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 93d3656..7b16ab2 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -78,8 +78,8 @@ /* ------------------------------ Code -------------------------------- */ -#ifdef BRIDGE_OVER_SERIAL -#include "helpers/SerialBridge.h" +#ifdef WITH_RS232_BRIDGE +#include "helpers/bridges/RS232Bridge.h" #endif #define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS @@ -118,7 +118,7 @@ struct ClientInfo { #define MAX_CLIENTS 32 #endif -#ifdef BRIDGE_OVER_SERIAL +#ifdef WITH_RS232_BRIDGE AbstractBridge* bridge; #endif @@ -308,7 +308,7 @@ protected: } } void logTx(mesh::Packet* pkt, int len) override { -#ifdef BRIDGE_OVER_SERIAL +#ifdef WITH_RS232_BRIDGE if (!pkt->isMarkedDoNotRetransmit()) { bridge->onPacketTransmitted(pkt); } @@ -578,8 +578,8 @@ public: : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) { -#ifdef BRIDGE_OVER_SERIAL - bridge = new SerialBridge(BRIDGE_OVER_SERIAL, _mgr, &rtc); +#ifdef WITH_RS232_BRIDGE + bridge = new RS232Bridge(WITH_RS232_BRIDGE, _mgr, &rtc); #endif memset(known_clients, 0, sizeof(known_clients)); next_local_advert = next_flood_advert = 0; @@ -781,7 +781,7 @@ public: } void loop() { -#ifdef BRIDGE_OVER_SERIAL +#ifdef WITH_RS232_BRIDGE bridge->loop(); #endif @@ -833,7 +833,7 @@ void setup() { Serial.begin(115200); delay(1000); -#ifdef BRIDGE_OVER_SERIAL +#ifdef WITH_RS232_BRIDGE bridge->begin(); #endif diff --git a/src/helpers/SerialBridge.cpp b/src/helpers/bridges/RS232Bridge.cpp similarity index 73% rename from src/helpers/SerialBridge.cpp rename to src/helpers/bridges/RS232Bridge.cpp index eefd751..801bcc5 100644 --- a/src/helpers/SerialBridge.cpp +++ b/src/helpers/bridges/RS232Bridge.cpp @@ -1,8 +1,8 @@ -#include "SerialBridge.h" +#include "RS232Bridge.h" #include #include -#ifdef BRIDGE_OVER_SERIAL +#ifdef WITH_RS232_BRIDGE // Fletcher-16 // https://en.wikipedia.org/wiki/Fletcher%27s_checksum @@ -17,7 +17,7 @@ inline static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { return (sum2 << 8) | sum1; }; -const char* SerialBridge::getLogDateTime() { +const char* RS232Bridge::getLogDateTime() { static char tmp[32]; uint32_t now = _rtc->getCurrentTime(); DateTime dt = DateTime(now); @@ -25,26 +25,30 @@ const char* SerialBridge::getLogDateTime() { return tmp; } -SerialBridge::SerialBridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc) : _serial(&serial), _mgr(mgr), _rtc(rtc) {} +RS232Bridge::RS232Bridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc) : _serial(&serial), _mgr(mgr), _rtc(rtc) {} + +void RS232Bridge::begin() { +#if !defined(WITH_RS232_BRIDGE_RX) || !defined(WITH_RS232_BRIDGE_TX) +#error "WITH_RS232_BRIDGE_RX and WITH_RS232_BRIDGE_TX must be defined" +#endif -void SerialBridge::begin() { #if defined(ESP32) - ((HardwareSerial *)_serial)->setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); + ((HardwareSerial *)_serial)->setPins(WITH_RS232_BRIDGE_RX, WITH_RS232_BRIDGE_TX); #elif defined(NRF52_PLATFORM) - ((HardwareSerial *)_serial)->setPins(BRIDGE_OVER_SERIAL_RX, BRIDGE_OVER_SERIAL_TX); + ((HardwareSerial *)_serial)->setPins(WITH_RS232_BRIDGE_RX, WITH_RS232_BRIDGE_TX); #elif defined(RP2040_PLATFORM) - ((SerialUART *)_serial)->setRX(BRIDGE_OVER_SERIAL_RX); - ((SerialUART *)_serial)->setTX(BRIDGE_OVER_SERIAL_TX); + ((SerialUART *)_serial)->setRX(WITH_RS232_BRIDGE_RX); + ((SerialUART *)_serial)->setTX(WITH_RS232_BRIDGE_TX); #elif defined(STM32_PLATFORM) - ((HardwareSerial *)_serial)->setRx(BRIDGE_OVER_SERIAL_RX); - ((HardwareSerial *)_serial)->setTx(BRIDGE_OVER_SERIAL_TX); + ((HardwareSerial *)_serial)->setRx(WITH_RS232_BRIDGE_RX); + ((HardwareSerial *)_serial)->setTx(WITH_RS232_BRIDGE_TX); #else -#error SerialBridge was not tested on the current platform +#error RS232Bridge was not tested on the current platform #endif ((HardwareSerial*)_serial)->begin(115200); } -void SerialBridge::onPacketTransmitted(mesh::Packet* packet) { +void RS232Bridge::onPacketTransmitted(mesh::Packet* packet) { if (!_seen_packets.hasSeen(packet)) { uint8_t buffer[MAX_SERIAL_PACKET_SIZE]; uint16_t len = packet->writeTo(buffer + 4); @@ -66,7 +70,7 @@ void SerialBridge::onPacketTransmitted(mesh::Packet* packet) { } } -void SerialBridge::loop() { +void RS232Bridge::loop() { while (_serial->available()) { uint8_t b = _serial->read(); @@ -108,7 +112,7 @@ void SerialBridge::loop() { } } -void SerialBridge::onPacketReceived(mesh::Packet* packet) { +void RS232Bridge::onPacketReceived(mesh::Packet* packet) { if (!_seen_packets.hasSeen(packet)) { _mgr->queueInbound(packet, 0); } else { diff --git a/src/helpers/SerialBridge.h b/src/helpers/bridges/RS232Bridge.h similarity index 92% rename from src/helpers/SerialBridge.h rename to src/helpers/bridges/RS232Bridge.h index cc837d5..0e99040 100644 --- a/src/helpers/SerialBridge.h +++ b/src/helpers/bridges/RS232Bridge.h @@ -4,12 +4,12 @@ #include "helpers/SimpleMeshTables.h" #include -#ifdef BRIDGE_OVER_SERIAL +#ifdef WITH_RS232_BRIDGE /** * @brief A bridge implementation that uses a serial port to connect two mesh networks. */ -class SerialBridge : public AbstractBridge { +class RS232Bridge : public AbstractBridge { public: /** * @brief Construct a new Serial Bridge object @@ -18,7 +18,7 @@ public: * @param mgr A pointer to the packet manager. * @param rtc A pointer to the RTC clock. */ - SerialBridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc); + RS232Bridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc); void begin() override; void loop() override; void onPacketTransmitted(mesh::Packet* packet) override; diff --git a/variants/heltec_v3/platformio.ini b/variants/heltec_v3/platformio.ini index 3e7524c..4ffb11b 100644 --- a/variants/heltec_v3/platformio.ini +++ b/variants/heltec_v3/platformio.ini @@ -59,13 +59,14 @@ build_flags = -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 - -D BRIDGE_OVER_SERIAL=Serial2 - -D BRIDGE_OVER_SERIAL_RX=5 - -D BRIDGE_OVER_SERIAL_TX=6 + -D WITH_RS232_BRIDGE=Serial2 + -D WITH_RS232_BRIDGE_RX=5 + -D WITH_RS232_BRIDGE_TX=6 -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${Heltec_lora32_v3.build_src_filter} + + + +<../examples/simple_repeater> lib_deps = ${Heltec_lora32_v3.lib_deps} @@ -217,12 +218,13 @@ build_flags = -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 - -D BRIDGE_OVER_SERIAL=Serial2 - -D BRIDGE_OVER_SERIAL_RX=5 - -D BRIDGE_OVER_SERIAL_TX=6 + -D WITH_RS232_BRIDGE=Serial2 + -D WITH_RS232_BRIDGE_RX=5 + -D WITH_RS232_BRIDGE_TX=6 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${Heltec_lora32_v3.build_src_filter} + + +<../examples/simple_repeater> lib_deps = ${Heltec_lora32_v3.lib_deps} diff --git a/variants/lilygo_tlora_v2_1/platformio.ini b/variants/lilygo_tlora_v2_1/platformio.ini index 4e146cf..313b984 100644 --- a/variants/lilygo_tlora_v2_1/platformio.ini +++ b/variants/lilygo_tlora_v2_1/platformio.ini @@ -68,6 +68,7 @@ lib_deps = extends = LilyGo_TLora_V2_1_1_6 build_src_filter = ${LilyGo_TLora_V2_1_1_6.build_src_filter} + + + +<../examples/simple_repeater> build_flags = ${LilyGo_TLora_V2_1_1_6.build_flags} @@ -76,9 +77,9 @@ build_flags = -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 - -D BRIDGE_OVER_SERIAL=Serial2 - -D BRIDGE_OVER_SERIAL_RX=34 - -D BRIDGE_OVER_SERIAL_TX=25 + -D WITH_RS232_BRIDGE=Serial2 + -D WITH_RS232_BRIDGE_RX=34 + -D WITH_RS232_BRIDGE_TX=25 -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 ; -D CORE_DEBUG_LEVEL=3 diff --git a/variants/waveshare_rp2040_lora/platformio.ini b/variants/waveshare_rp2040_lora/platformio.ini index 0ec745f..8824ddb 100644 --- a/variants/waveshare_rp2040_lora/platformio.ini +++ b/variants/waveshare_rp2040_lora/platformio.ini @@ -48,12 +48,13 @@ build_flags = ${waveshare_rp2040_lora.build_flags} -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 - -D BRIDGE_OVER_SERIAL=Serial2 - -D BRIDGE_OVER_SERIAL_RX=9 - -D BRIDGE_OVER_SERIAL_TX=8 + -D WITH_RS232_BRIDGE=Serial2 + -D WITH_RS232_BRIDGE_RX=9 + -D WITH_RS232_BRIDGE_TX=8 -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${waveshare_rp2040_lora.build_src_filter} + + +<../examples/simple_repeater> [env:waveshare_rp2040_lora_room_server] From 2d651221c471dfb8b98b2e6de54759d5a723ccb1 Mon Sep 17 00:00:00 2001 From: Florent de Lamotte Date: Fri, 5 Sep 2025 15:20:52 +0200 Subject: [PATCH 15/50] ui: sensors page --- examples/companion_radio/ui-new/UITask.cpp | 54 +++++++++++++++++++++- 1 file changed, 53 insertions(+), 1 deletion(-) diff --git a/examples/companion_radio/ui-new/UITask.cpp b/examples/companion_radio/ui-new/UITask.cpp index 34ba60e..efa3133 100644 --- a/examples/companion_radio/ui-new/UITask.cpp +++ b/examples/companion_radio/ui-new/UITask.cpp @@ -75,6 +75,7 @@ class HomeScreen : public UIScreen { RADIO, BLUETOOTH, ADVERT, + SENSORS, SHUTDOWN, Count // keep as last }; @@ -113,9 +114,32 @@ class HomeScreen : public UIScreen { display.fillRect(iconX + 2, iconY + 2, fillWidth, iconHeight - 4); } + DynamicJsonDocument _sensors_doc; + JsonArray _sensors_arr; + bool scroll = false; + int scroll_offset = 0; + int next_sensors_refresh = 0; + + void refresh_sensors() { + CayenneLPP lpp(200); + if (millis() > next_sensors_refresh) { + lpp.addVoltage(TELEM_CHANNEL_SELF, (float)board.getBattMilliVolts() / 1000.0f); + sensors.querySensors(0xFF, lpp); + _sensors_arr.clear(); + lpp.decode(lpp.getBuffer(), lpp.getSize(), _sensors_arr); + scroll = _sensors_arr.size() > UI_RECENT_LIST_SIZE; // there is a status line +#if AUTO_OFF_MILLIS > 0 + next_sensors_refresh = millis() + 5000; // refresh sensor values every 5 sec +#else + next_sensors_refresh = millis() + 60000; // refresh sensor values every 1 min +#endif + } + } + public: HomeScreen(UITask* task, mesh::RTCClock* rtc, SensorManager* sensors, NodePrefs* node_prefs) - : _task(task), _rtc(rtc), _sensors(sensors), _node_prefs(node_prefs), _page(0), _shutdown_init(false) { } + : _task(task), _rtc(rtc), _sensors(sensors), _node_prefs(node_prefs), _page(0), + _shutdown_init(false), _sensors_doc(2048) { _sensors_arr=_sensors_doc.to(); } void poll() override { if (_shutdown_init && !_task->isButtonPressed()) { // must wait for USR button to be released @@ -211,6 +235,34 @@ public: display.setColor(DisplayDriver::GREEN); display.drawXbm((display.width() - 32) / 2, 18, advert_icon, 32, 32); display.drawTextCentered(display.width() / 2, 64 - 11, "advert: " PRESS_LABEL); + } else if (_page == HomePage::SENSORS) { + int y = 18; + refresh_sensors(); + char buf[100]; + int s_size = _sensors_arr.size(); + for (int i = 0; i < (scroll?UI_RECENT_LIST_SIZE:s_size); i++) { + JsonObject v = _sensors_arr[(i+scroll_offset)%s_size]; + display.setCursor(0, y); + switch (v["type"].as()) { + case 136: // GPS + sprintf(buf, "%.4f %.4f", + v["value"]["latitude"].as(), + v["value"]["longitude"].as()); + break; + default: // will be a float for now + sprintf(buf, "%.02f", + v["value"].as()); + } + display.setCursor(0, y); + display.print(v["name"].as().c_str()); + display.setCursor( + display.width()-display.getTextWidth(buf)-1, y + ); + display.print(buf); + y = y + 12; + } + if (scroll) scroll_offset = (scroll_offset+1)%s_size; + else scroll_offset = 0; } else if (_page == HomePage::SHUTDOWN) { display.setColor(DisplayDriver::GREEN); display.setTextSize(1); From f974cb2a4fbe2a93607a4737c3e08a6807f386e0 Mon Sep 17 00:00:00 2001 From: Florent de Lamotte Date: Fri, 5 Sep 2025 15:32:02 +0200 Subject: [PATCH 16/50] ui: ENTER on SENSORS page toggles gps --- examples/companion_radio/ui-new/UITask.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/examples/companion_radio/ui-new/UITask.cpp b/examples/companion_radio/ui-new/UITask.cpp index efa3133..93a7da1 100644 --- a/examples/companion_radio/ui-new/UITask.cpp +++ b/examples/companion_radio/ui-new/UITask.cpp @@ -307,6 +307,10 @@ public: } return true; } + if (c == KEY_ENTER && _page == HomePage::SENSORS) { + _task->toggleGPS(); + return true; + } if (c == KEY_ENTER && _page == HomePage::SHUTDOWN) { _shutdown_init = true; // need to wait for button to be released return true; From 8fdaaceb1c4586bfe4477d608f50d23808c8f415 Mon Sep 17 00:00:00 2001 From: Florent de Lamotte Date: Fri, 5 Sep 2025 15:35:04 +0200 Subject: [PATCH 17/50] ui: refresh sensors on gps toggle --- examples/companion_radio/ui-new/UITask.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/examples/companion_radio/ui-new/UITask.cpp b/examples/companion_radio/ui-new/UITask.cpp index 93a7da1..1adabff 100644 --- a/examples/companion_radio/ui-new/UITask.cpp +++ b/examples/companion_radio/ui-new/UITask.cpp @@ -309,6 +309,7 @@ public: } if (c == KEY_ENTER && _page == HomePage::SENSORS) { _task->toggleGPS(); + next_sensors_refresh=0; return true; } if (c == KEY_ENTER && _page == HomePage::SHUTDOWN) { From cb99eb4ae8db2a243b56d27e8e679fd222d09859 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Fri, 5 Sep 2025 14:49:06 +0100 Subject: [PATCH 18/50] Remove retransmit check for RS232 bridge in logTx Since the flag is preserved and respected by the mesh processing on the receiving end, there's no risk of these packets being retransmitted endlessly. --- examples/simple_repeater/main.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 7b16ab2..3e2795d 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -309,9 +309,7 @@ protected: } void logTx(mesh::Packet* pkt, int len) override { #ifdef WITH_RS232_BRIDGE - if (!pkt->isMarkedDoNotRetransmit()) { - bridge->onPacketTransmitted(pkt); - } + bridge->onPacketTransmitted(pkt); #endif if (_logging) { File f = openAppend(PACKET_LOG_FILE); From d59724acd05bbcad41cbfb1abfdf7c5678053af5 Mon Sep 17 00:00:00 2001 From: recrof Date: Fri, 5 Sep 2025 16:21:19 +0200 Subject: [PATCH 19/50] new variant: RAK WisMesh Tag --- .../sensors/EnvironmentSensorManager.cpp | 34 ++--- .../rak_wismesh_tag/RAKWismeshTagBoard.cpp | 81 ++++++++++++ variants/rak_wismesh_tag/RAKWismeshTagBoard.h | 80 ++++++++++++ variants/rak_wismesh_tag/platformio.ini | 116 +++++++++++++++++ variants/rak_wismesh_tag/target.cpp | 54 ++++++++ variants/rak_wismesh_tag/target.h | 27 ++++ variants/rak_wismesh_tag/variant.cpp | 21 +++ variants/rak_wismesh_tag/variant.h | 121 ++++++++++++++++++ 8 files changed, 518 insertions(+), 16 deletions(-) create mode 100644 variants/rak_wismesh_tag/RAKWismeshTagBoard.cpp create mode 100644 variants/rak_wismesh_tag/RAKWismeshTagBoard.h create mode 100644 variants/rak_wismesh_tag/platformio.ini create mode 100644 variants/rak_wismesh_tag/target.cpp create mode 100644 variants/rak_wismesh_tag/target.h create mode 100644 variants/rak_wismesh_tag/variant.cpp create mode 100644 variants/rak_wismesh_tag/variant.h diff --git a/src/helpers/sensors/EnvironmentSensorManager.cpp b/src/helpers/sensors/EnvironmentSensorManager.cpp index f444b67..df08ed7 100644 --- a/src/helpers/sensors/EnvironmentSensorManager.cpp +++ b/src/helpers/sensors/EnvironmentSensorManager.cpp @@ -66,8 +66,8 @@ static Adafruit_INA260 INA260; #endif #if ENV_INCLUDE_INA226 -#define TELEM_INA226_ADDRESS 0x44 -#define TELEM_INA226_SHUNT_VALUE 0.100 +#define TELEM_INA226_ADDRESS 0x44 +#define TELEM_INA226_SHUNT_VALUE 0.100 #define TELEM_INA226_MAX_AMP 0.8 #include static INA226 INA226(TELEM_INA226_ADDRESS); @@ -85,7 +85,11 @@ static Adafruit_MLX90614 MLX90614; static Adafruit_VL53L0X VL53L0X; #endif -#if ENV_INCLUDE_GPS && RAK_BOARD +#if ENV_INCLUDE_GPS && defined(RAK_BOARD) && !defined(RAK_WISMESH_TAG) +#define RAK_WISBLOCK_GPS +#endif + +#ifdef RAK_WISBLOCK_GPS static uint32_t gpsResetPin = 0; static bool i2cGPSFlag = false; static bool serialGPSFlag = false; @@ -96,7 +100,7 @@ static SFE_UBLOX_GNSS ublox_GNSS; bool EnvironmentSensorManager::begin() { #if ENV_INCLUDE_GPS - #if RAK_BOARD + #ifdef RAK_WISBLOCK_GPS rakGPSInit(); //probe base board/sockets for GPS #else initBasicGPS(); @@ -457,7 +461,7 @@ void EnvironmentSensorManager::initBasicGPS() { gps_active = false; //Set GPS visibility off until setting is changed } -#ifdef RAK_BOARD +#ifdef RAK_WISBLOCK_GPS void EnvironmentSensorManager::rakGPSInit(){ Serial1.setPins(PIN_GPS_TX, PIN_GPS_RX); @@ -531,7 +535,7 @@ bool EnvironmentSensorManager::gpsIsAwake(uint8_t ioPin){ void EnvironmentSensorManager::start_gps() { gps_active = true; - #ifdef RAK_BOARD + #ifdef RAK_WISBLOCK_GPS pinMode(gpsResetPin, OUTPUT); digitalWrite(gpsResetPin, HIGH); return; @@ -547,7 +551,7 @@ void EnvironmentSensorManager::start_gps() { void EnvironmentSensorManager::stop_gps() { gps_active = false; - #ifdef RAK_BOARD + #ifdef RAK_WISBLOCK_GPS pinMode(gpsResetPin, OUTPUT); digitalWrite(gpsResetPin, LOW); return; @@ -568,13 +572,7 @@ void EnvironmentSensorManager::loop() { if (millis() > next_gps_update) { if(gps_active){ - #ifndef RAK_BOARD - if (_location->isValid()) { - node_lat = ((double)_location->getLatitude())/1000000.; - node_lon = ((double)_location->getLongitude())/1000000.; - MESH_DEBUG_PRINTLN("lat %f lon %f", node_lat, node_lon); - } - #else + #ifdef RAK_WISBLOCK_GPS if(i2cGPSFlag){ node_lat = ((double)ublox_GNSS.getLatitude())/10000000.; node_lon = ((double)ublox_GNSS.getLongitude())/10000000.; @@ -585,8 +583,12 @@ void EnvironmentSensorManager::loop() { node_lon = ((double)_location->getLongitude())/1000000.; MESH_DEBUG_PRINTLN("lat %f lon %f", node_lat, node_lon); } - //else - //MESH_DEBUG_PRINTLN("No valid GPS data"); + #else + if (_location->isValid()) { + node_lat = ((double)_location->getLatitude())/1000000.; + node_lon = ((double)_location->getLongitude())/1000000.; + MESH_DEBUG_PRINTLN("lat %f lon %f", node_lat, node_lon); + } #endif } next_gps_update = millis() + 1000; diff --git a/variants/rak_wismesh_tag/RAKWismeshTagBoard.cpp b/variants/rak_wismesh_tag/RAKWismeshTagBoard.cpp new file mode 100644 index 0000000..68ce2fd --- /dev/null +++ b/variants/rak_wismesh_tag/RAKWismeshTagBoard.cpp @@ -0,0 +1,81 @@ +#include +#include "RAKWismeshTagBoard.h" + +#include +#include + +static BLEDfu bledfu; + +static void connect_callback(uint16_t conn_handle) { + (void)conn_handle; + MESH_DEBUG_PRINTLN("BLE client connected"); +} + +static void disconnect_callback(uint16_t conn_handle, uint8_t reason) { + (void)conn_handle; + (void)reason; + + MESH_DEBUG_PRINTLN("BLE client disconnected"); +} + +void RAKWismeshTagBoard::begin() { + // for future use, sub-classes SHOULD call this from their begin() + startup_reason = BD_STARTUP_NORMAL; + pinMode(PIN_VBAT_READ, INPUT); + pinMode(PIN_USER_BTN, INPUT_PULLUP); + + Wire.setPins(PIN_BOARD_SDA, PIN_BOARD_SCL); + Wire.begin(); + + pinMode(SX126X_POWER_EN, OUTPUT); + digitalWrite(SX126X_POWER_EN, HIGH); + delay(10); // give sx1262 some time to power up +} + +bool RAKWismeshTagBoard::startOTAUpdate(const char* id, char reply[]) { + // Config the peripheral connection with maximum bandwidth + // more SRAM required by SoftDevice + // Note: All config***() function must be called before begin() + Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); + Bluefruit.configPrphConn(92, BLE_GAP_EVENT_LENGTH_MIN, 16, 16); + + Bluefruit.begin(1, 0); + // Set max power. Accepted values are: -40, -30, -20, -16, -12, -8, -4, 0, 4 + Bluefruit.setTxPower(4); + // Set the BLE device name + Bluefruit.setName("WISMESHTAG_OTA"); + + Bluefruit.Periph.setConnectCallback(connect_callback); + Bluefruit.Periph.setDisconnectCallback(disconnect_callback); + + // To be consistent OTA DFU should be added first if it exists + bledfu.begin(); + + // Set up and start advertising + // Advertising packet + Bluefruit.Advertising.addFlags(BLE_GAP_ADV_FLAGS_LE_ONLY_GENERAL_DISC_MODE); + Bluefruit.Advertising.addTxPower(); + Bluefruit.Advertising.addName(); + + /* Start Advertising + - Enable auto advertising if disconnected + - Interval: fast mode = 20 ms, slow mode = 152.5 ms + - Timeout for fast mode is 30 seconds + - Start(timeout) with timeout = 0 will advertise forever (until connected) + + For recommended advertising interval + https://developer.apple.com/library/content/qa/qa1931/_index.html + */ + Bluefruit.Advertising.restartOnDisconnect(true); + Bluefruit.Advertising.setInterval(32, 244); // in unit of 0.625 ms + Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode + Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds + + uint8_t mac_addr[6]; + memset(mac_addr, 0, sizeof(mac_addr)); + Bluefruit.getAddr(mac_addr); + sprintf(reply, "OK - mac: %02X:%02X:%02X:%02X:%02X:%02X", + mac_addr[5], mac_addr[4], mac_addr[3], mac_addr[2], mac_addr[1], mac_addr[0]); + + return true; +} diff --git a/variants/rak_wismesh_tag/RAKWismeshTagBoard.h b/variants/rak_wismesh_tag/RAKWismeshTagBoard.h new file mode 100644 index 0000000..22af6f7 --- /dev/null +++ b/variants/rak_wismesh_tag/RAKWismeshTagBoard.h @@ -0,0 +1,80 @@ +#pragma once + +#include +#include + +// built-ins +#define PIN_VBAT_READ 5 +#define ADC_MULTIPLIER (3 * 1.73 * 1.187 * 1000) + +class RAKWismeshTagBoard : public mesh::MainBoard { +protected: + uint8_t startup_reason; + +public: + void begin(); + uint8_t getStartupReason() const override { return startup_reason; } + +#if defined(P_LORA_TX_LED) && defined(LED_STATE_ON) + void onBeforeTransmit() override { + digitalWrite(P_LORA_TX_LED, LED_STATE_ON); // turn TX LED on + } + void onAfterTransmit() override { + digitalWrite(P_LORA_TX_LED, !LED_STATE_ON); // turn TX LED off + } +#endif + + #define BATTERY_SAMPLES 8 + + uint16_t getBattMilliVolts() override { + analogReadResolution(12); + + uint32_t raw = 0; + for (int i = 0; i < BATTERY_SAMPLES; i++) { + raw += analogRead(PIN_VBAT_READ); + } + raw = raw / BATTERY_SAMPLES; + + return (ADC_MULTIPLIER * raw) / 4096; + } + + const char* getManufacturerName() const override { + return "RAK WisMesh Tag"; + } + + void reboot() override { + NVIC_SystemReset(); + } + + bool startOTAUpdate(const char* id, char reply[]) override; + + void powerOff() override { + #ifdef BUZZER_EN + digitalWrite(BUZZER_EN, LOW); + #endif + + #ifdef PIN_GPS_EN + digitalWrite(PIN_GPS_EN, LOW); + #endif + + // set led on and wait for button release before poweroff + #ifdef LED_PIN + digitalWrite(LED_PIN, HIGH); + #endif + #ifdef BUTTON_PIN + while(digitalRead(BUTTON_PIN)); + #endif + #ifdef LED_GREEN + digitalWrite(LED_GREEN, LOW); + #endif + #ifdef LED_BLUE + digitalWrite(LED_BLUE, LOW); + #endif + + #ifdef BUTTON_PIN + nrf_gpio_cfg_sense_input(digitalPinToInterrupt(BUTTON_PIN), NRF_GPIO_PIN_NOPULL, NRF_GPIO_PIN_SENSE_HIGH); + #endif + + sd_power_system_off(); + } +}; diff --git a/variants/rak_wismesh_tag/platformio.ini b/variants/rak_wismesh_tag/platformio.ini new file mode 100644 index 0000000..6f7d28b --- /dev/null +++ b/variants/rak_wismesh_tag/platformio.ini @@ -0,0 +1,116 @@ +[rak_wismesh_tag] +extends = nrf52_base +platform = https://github.com/maxgerhardt/platform-nordicnrf52.git#rak +board = wiscore_rak4631 +board_check = true +build_flags = ${nrf52_base.build_flags} + ${sensor_base.build_flags} + -I variants/rak_wismesh_tag + -I src/helpers/ui + -D RAK_WISMESH_TAG + -D RAK_BOARD + -D P_LORA_TX_LED=LED_GREEN + -D P_LORA_DIO_1=SX126X_DIO1 + -D P_LORA_NSS=PIN_SPI_NSS + -D P_LORA_RESET=SX126X_RESET + -D P_LORA_BUSY=SX126X_BUSY + -D P_LORA_SCLK=PIN_SPI_SCK + -D P_LORA_MISO=PIN_SPI_MISO + -D P_LORA_MOSI=PIN_SPI_MOSI + -D RADIO_CLASS=CustomSX1262 + -D WRAPPER_CLASS=CustomSX1262Wrapper + -D DISPLAY_CLASS=NullDisplayDriver + -D LORA_TX_POWER=22 + -D SX126X_CURRENT_LIMIT=140 + -D SX126X_RX_BOOSTED_GAIN=1 + -D PIN_BUZZER=21 + -D PIN_BOARD_SDA=PIN_WIRE_SDA + -D PIN_BOARD_SCL=PIN_WIRE_SCL +build_src_filter = ${nrf52_base.build_src_filter} + +<../variants/rak_wismesh_tag> + + + + + + + + +lib_deps = + ${nrf52_base.lib_deps} + ${sensor_base.lib_deps} + +[env:RAK_WisMesh_Tag_Repeater] +extends = rak_wismesh_tag +build_flags = + ${rak_wismesh_tag.build_flags} + -D ADVERT_NAME='"RAK WM Repeater"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${rak_wismesh_tag.build_src_filter} + +<../examples/simple_repeater> + +[env:RAK_WisMesh_Tag_room_server] +extends = rak_wismesh_tag +build_flags = + ${rak_wismesh_tag.build_flags} + -D ADVERT_NAME='"RAK WM Room"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D ROOM_PASSWORD='"hello"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${rak_wismesh_tag.build_src_filter} + +<../examples/simple_room_server> + +[env:RAK_WisMesh_Tag_companion_radio_usb] +extends = rak_wismesh_tag +build_flags = + ${rak_wismesh_tag.build_flags} + -I examples/companion_radio/ui-orig + -D MAX_CONTACTS=100 + -D MAX_GROUP_CHANNELS=8 +; NOTE: DO NOT ENABLE --> -D MESH_PACKET_LOGGING=1 +; NOTE: DO NOT ENABLE --> -D MESH_DEBUG=1 +build_src_filter = ${rak_wismesh_tag.build_src_filter} + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-orig/*.cpp> +lib_deps = + ${rak_wismesh_tag.lib_deps} + densaugeo/base64 @ ~1.4.0 + end2endzone/NonBlockingRTTTL@^1.3.0 + +[env:RAK_WisMesh_Tag_companion_radio_ble] +extends = rak_wismesh_tag +build_flags = + ${rak_wismesh_tag.build_flags} + -I examples/companion_radio/ui-orig + -D MAX_CONTACTS=100 + -D MAX_GROUP_CHANNELS=8 + -D BLE_PIN_CODE=123456 + -D BLE_DEBUG_LOGGING=1 + -D OFFLINE_QUEUE_SIZE=256 +; -D MESH_PACKET_LOGGING=1 + -D MESH_DEBUG=1 +build_src_filter = ${rak_wismesh_tag.build_src_filter} + + + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-orig/*.cpp> +lib_deps = + ${rak4631.lib_deps} + densaugeo/base64 @ ~1.4.0 + end2endzone/NonBlockingRTTTL@^1.3.0 + +[env:RAK_WisMesh_Tag_sensor] +extends = rak4631 +build_flags = + ${rak4631.build_flags} + -D ADVERT_NAME='"RAK WM Sensor"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' +; -D MESH_PACKET_LOGGING=1 + -D MESH_DEBUG=1 +build_src_filter = ${rak4631.build_src_filter} + +<../examples/simple_sensor> \ No newline at end of file diff --git a/variants/rak_wismesh_tag/target.cpp b/variants/rak_wismesh_tag/target.cpp new file mode 100644 index 0000000..2bd3086 --- /dev/null +++ b/variants/rak_wismesh_tag/target.cpp @@ -0,0 +1,54 @@ +#include +#include "target.h" +#include + +RAKWismeshTagBoard board; + +#ifndef PIN_USER_BTN + #define PIN_USER_BTN (-1) +#endif + +#ifdef DISPLAY_CLASS + DISPLAY_CLASS display; + MomentaryButton user_btn(PIN_USER_BTN, 1000, true, true); +#endif + +RADIO_CLASS radio = new Module(P_LORA_NSS, P_LORA_DIO_1, P_LORA_RESET, P_LORA_BUSY, SPI); + +WRAPPER_CLASS radio_driver(radio, board); + +VolatileRTCClock fallback_clock; +AutoDiscoverRTCClock rtc_clock(fallback_clock); + +#if ENV_INCLUDE_GPS + #include + MicroNMEALocationProvider nmea = MicroNMEALocationProvider(Serial1); + EnvironmentSensorManager sensors = EnvironmentSensorManager(nmea); +#else + EnvironmentSensorManager sensors; +#endif + +bool radio_init() { + rtc_clock.begin(Wire); + return radio.std_init(&SPI); +} + +uint32_t radio_get_rng_seed() { + return radio.random(0x7FFFFFFF); +} + +void radio_set_params(float freq, float bw, uint8_t sf, uint8_t cr) { + radio.setFrequency(freq); + radio.setSpreadingFactor(sf); + radio.setBandwidth(bw); + radio.setCodingRate(cr); +} + +void radio_set_tx_power(uint8_t dbm) { + radio.setOutputPower(dbm); +} + +mesh::LocalIdentity radio_new_identity() { + RadioNoiseListener rng(radio); + return mesh::LocalIdentity(&rng); // create new random identity +} diff --git a/variants/rak_wismesh_tag/target.h b/variants/rak_wismesh_tag/target.h new file mode 100644 index 0000000..150d083 --- /dev/null +++ b/variants/rak_wismesh_tag/target.h @@ -0,0 +1,27 @@ +#pragma once + +#define RADIOLIB_STATIC_ONLY 1 +#include +#include +#include +#include +#include +#include + +#ifdef DISPLAY_CLASS + #include + extern DISPLAY_CLASS display; + #include + extern MomentaryButton user_btn; +#endif + +extern RAKWismeshTagBoard board; +extern WRAPPER_CLASS radio_driver; +extern AutoDiscoverRTCClock rtc_clock; +extern EnvironmentSensorManager sensors; + +bool radio_init(); +uint32_t radio_get_rng_seed(); +void radio_set_params(float freq, float bw, uint8_t sf, uint8_t cr); +void radio_set_tx_power(uint8_t dbm); +mesh::LocalIdentity radio_new_identity(); diff --git a/variants/rak_wismesh_tag/variant.cpp b/variants/rak_wismesh_tag/variant.cpp new file mode 100644 index 0000000..ac3af5d --- /dev/null +++ b/variants/rak_wismesh_tag/variant.cpp @@ -0,0 +1,21 @@ +#include "variant.h" +#include "nrf.h" +#include "wiring_constants.h" +#include "wiring_digital.h" + +const uint32_t g_ADigitalPinMap[] = { + 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, + 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47 +}; + +void initVariant() { + // LEDs + pinMode(LED_BLUE, OUTPUT); + pinMode(LED_GREEN, OUTPUT); + digitalWrite(LED_BLUE, LOW); + digitalWrite(LED_GREEN, LOW); + + // GPS + pinMode(PIN_GPS_EN, OUTPUT); + digitalWrite(PIN_GPS_EN, HIGH); +} \ No newline at end of file diff --git a/variants/rak_wismesh_tag/variant.h b/variants/rak_wismesh_tag/variant.h new file mode 100644 index 0000000..b0e51ef --- /dev/null +++ b/variants/rak_wismesh_tag/variant.h @@ -0,0 +1,121 @@ +/* + * variant.h + * Copyright (C) 2023 Seeed K.K. + * MIT License + */ + +#pragma once + +#include "WVariant.h" + +//////////////////////////////////////////////////////////////////////////////// +// Low frequency clock source + +#define USE_LFXO // 32.768 kHz crystal oscillator +#define VARIANT_MCK (64000000ul) + +#define WIRE_INTERFACES_COUNT (1) +#define PIN_TXCO (21) +//////////////////////////////////////////////////////////////////////////////// +// Power + +#define PIN_PWR_EN (12) + +#define BATTERY_PIN (5) +#define ADC_MULTIPLIER (1.73F) + +#define ADC_RESOLUTION (14) +#define BATTERY_SENSE_RES (12) + +#define AREF_VOLTAGE (3.0) + +//////////////////////////////////////////////////////////////////////////////// +// Number of pins + +#define PINS_COUNT (48) +#define NUM_DIGITAL_PINS (48) +#define NUM_ANALOG_INPUTS (6) +#define NUM_ANALOG_OUTPUTS (0) + +//////////////////////////////////////////////////////////////////////////////// +// UART pin definition + +#define PIN_SERIAL1_RX (15) +#define PIN_SERIAL1_TX (16) + +//////////////////////////////////////////////////////////////////////////////// +// I2C pin definition +#define WIRE_INTERFACES_COUNT (1) +#define PIN_WIRE_SDA (25) +#define PIN_WIRE_SCL (24) + +//////////////////////////////////////////////////////////////////////////////// +// SPI pin definition + +#define SPI_INTERFACES_COUNT (2) + +#define PIN_SPI_MISO (45) +#define PIN_SPI_MOSI (44) +#define PIN_SPI_SCK (43) +#define PIN_SPI_NSS (42) + +//////////////////////////////////////////////////////////////////////////////// +// Builtin LEDs + +#define LED_RED (-1) +#define LED_BLUE (36) +#define LED_GREEN (35) + +//#define PIN_STATUS_LED LED_BLUE +#define LED_BUILTIN LED_GREEN +#define LED_PIN LED_GREEN +#define LED_STATE_ON HIGH + +//////////////////////////////////////////////////////////////////////////////// +// Builtin buttons + +#define PIN_BUTTON1 (9) +#define BUTTON_PIN PIN_BUTTON1 +#define PIN_USER_BTN BUTTON_PIN + +#define PIN_BUTTON2 (12) +#define BUTTON_PIN2 PIN_BUTTON2 + +//////////////////////////////////////////////////////////////////////////////// +// Lora + +#define USE_SX1262 +#define LORA_CS (42) +#define SX126X_DIO1 (47) +#define SX126X_BUSY (46) +#define SX126X_RESET (38) +#define SX126X_POWER_EN (37) +#define SX126X_DIO2_AS_RF_SWITCH +#define SX126X_DIO3_TCXO_VOLTAGE 1.8 + +//////////////////////////////////////////////////////////////////////////////// +// SPI1 + +#define PIN_SPI1_MISO (29) +#define PIN_SPI1_MOSI (30) +#define PIN_SPI1_SCK (3) + +// GxEPD2 needs that for a panel that is not even used ! +extern const int MISO; +extern const int MOSI; +extern const int SCK; + +//////////////////////////////////////////////////////////////////////////////// +// GPS + +#define PIN_GPS_RX (PIN_SERIAL1_TX) +#define PIN_GPS_TX (PIN_SERIAL1_RX) +#define PIN_GPS_PPS (17) +#define PIN_GPS_EN (34) + +/////////////////////////////////////////////////////////////////////////////// +// OTHER PINS +#define PIN_AREF (2) +#define PIN_NFC1 (9) +#define PIN_NFC2 (10) +#define PIN_BUZZER (21) From 132ca7273513523952b1e93739465ad0c9f41345 Mon Sep 17 00:00:00 2001 From: ViezeVingertjes Date: Sat, 6 Sep 2025 18:45:08 +0200 Subject: [PATCH 20/50] T1000-E: ensure rails off and radio idle before system off; fix button wake pin --- variants/t1000-e/T1000eBoard.h | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/variants/t1000-e/T1000eBoard.h b/variants/t1000-e/T1000eBoard.h index 090c1b9..581a907 100644 --- a/variants/t1000-e/T1000eBoard.h +++ b/variants/t1000-e/T1000eBoard.h @@ -56,6 +56,7 @@ public: digitalWrite(GPS_RESET, LOW); digitalWrite(GPS_SLEEP_INT, LOW); digitalWrite(GPS_RTC_INT, LOW); + digitalWrite(GPS_EN, LOW); pinMode(GPS_RESETB, OUTPUT); digitalWrite(GPS_RESETB, LOW); #endif @@ -68,6 +69,13 @@ public: digitalWrite(PIN_3V3_EN, LOW); #endif + #ifdef PIN_3V3_ACC_EN + digitalWrite(PIN_3V3_ACC_EN, LOW); + #endif + #ifdef SENSOR_EN + digitalWrite(SENSOR_EN, LOW); + #endif + // set led on and wait for button release before poweroff #ifdef LED_PIN digitalWrite(LED_PIN, HIGH); @@ -80,7 +88,7 @@ public: #endif #ifdef BUTTON_PIN - nrf_gpio_cfg_sense_input(digitalPinToInterrupt(BUTTON_PIN), NRF_GPIO_PIN_NOPULL, NRF_GPIO_PIN_SENSE_HIGH); + nrf_gpio_cfg_sense_input(BUTTON_PIN, NRF_GPIO_PIN_NOPULL, NRF_GPIO_PIN_SENSE_HIGH); #endif sd_power_system_off(); From ac8ec172ef74e21bf0febc5e37c416eac88149e2 Mon Sep 17 00:00:00 2001 From: ViezeVingertjes Date: Sat, 6 Sep 2025 20:42:11 +0200 Subject: [PATCH 21/50] T1000-E: refactor GPS initialization; set GPS_RESETB pin as OUTPUT and remove redundant pin settings --- variants/t1000-e/target.cpp | 9 --------- variants/t1000-e/variant.cpp | 3 ++- 2 files changed, 2 insertions(+), 10 deletions(-) diff --git a/variants/t1000-e/target.cpp b/variants/t1000-e/target.cpp index 06509c4..2a6380d 100644 --- a/variants/t1000-e/target.cpp +++ b/variants/t1000-e/target.cpp @@ -146,15 +146,6 @@ void T1000SensorManager::stop_gps() { bool T1000SensorManager::begin() { // init GPS Serial1.begin(115200); - - // make sure gps pin are off - digitalWrite(GPS_VRTC_EN, LOW); - digitalWrite(GPS_RESET, LOW); - digitalWrite(GPS_SLEEP_INT, LOW); - digitalWrite(GPS_RTC_INT, LOW); - pinMode(GPS_RESETB, OUTPUT); - digitalWrite(GPS_RESETB, LOW); - return true; } diff --git a/variants/t1000-e/variant.cpp b/variants/t1000-e/variant.cpp index f17b3a8..f9328e3 100644 --- a/variants/t1000-e/variant.cpp +++ b/variants/t1000-e/variant.cpp @@ -69,7 +69,7 @@ void initVariant() pinMode(BATTERY_PIN, INPUT); pinMode(EXT_CHRG_DETECT, INPUT); pinMode(EXT_PWR_DETECT, INPUT); - pinMode(GPS_RESETB, INPUT); + pinMode(GPS_RESETB, OUTPUT); pinMode(PIN_BUTTON1, INPUT); pinMode(PIN_3V3_EN, OUTPUT); @@ -92,5 +92,6 @@ void initVariant() digitalWrite(GPS_VRTC_EN, LOW); digitalWrite(GPS_SLEEP_INT, HIGH); digitalWrite(GPS_RTC_INT, LOW); + digitalWrite(GPS_RESETB, LOW); digitalWrite(LED_PIN, LOW); } From 8521b0eb082604691c7b8d9cecdd006c458a2e9f Mon Sep 17 00:00:00 2001 From: taco Date: Sun, 7 Sep 2025 19:54:42 +1000 Subject: [PATCH 22/50] new version of CustomLFS lib --- platformio.ini | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/platformio.ini b/platformio.ini index c08cd85..4702ba5 100644 --- a/platformio.ini +++ b/platformio.ini @@ -81,8 +81,7 @@ build_flags = ${arduino_base.build_flags} -D EXTRAFS=1 lib_deps = ${arduino_base.lib_deps} - https://github.com/oltaco/CustomLFS @ 0.2 - + https://github.com/oltaco/CustomLFS @ 0.2.1 ; ----------------- RP2040 --------------------- [rp2040_base] From acf6110001038ecb69840ed388274c147e99497f Mon Sep 17 00:00:00 2001 From: taco Date: Sun, 7 Sep 2025 19:59:01 +1000 Subject: [PATCH 23/50] add companion usb to ThinkNode M1 --- variants/thinknode_m1/platformio.ini | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/variants/thinknode_m1/platformio.ini b/variants/thinknode_m1/platformio.ini index a530d25..eeeb692 100644 --- a/variants/thinknode_m1/platformio.ini +++ b/variants/thinknode_m1/platformio.ini @@ -96,3 +96,30 @@ lib_deps = zinggjm/GxEPD2 @ 1.6.2 bakercp/CRC32 @ ^2.0.0 end2endzone/NonBlockingRTTTL@^1.3.0 + +[env:ThinkNode_M1_companion_radio_usb] +extends = ThinkNode_M1 +build_flags = + ${ThinkNode_M1.build_flags} + -I src/helpers/ui + -I examples/companion_radio/ui-new + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 + -D DISPLAY_ROTATION=4 + -D QSPIFLASH=1 + -D DISPLAY_CLASS=GxEPDDisplay + -D OFFLINE_QUEUE_SIZE=256 + -D PIN_BUZZER=6 + -D AUTO_SHUTDOWN_MILLIVOLTS=3300 +build_src_filter = ${ThinkNode_M1.build_src_filter} + + + + + + + +<../examples/companion_radio/*.cpp> + +<../examples/companion_radio/ui-new/*.cpp> +lib_deps = + ${ThinkNode_M1.lib_deps} + densaugeo/base64 @ ~1.4.0 + zinggjm/GxEPD2 @ 1.6.2 + bakercp/CRC32 @ ^2.0.0 + end2endzone/NonBlockingRTTTL@^1.3.0 \ No newline at end of file From 18be92615bd3593b29d60e68126ba506c0d9be96 Mon Sep 17 00:00:00 2001 From: taco Date: Sun, 7 Sep 2025 20:00:44 +1000 Subject: [PATCH 24/50] add QSPI pins to Lilygo T-Echo --- variants/lilygo_techo/variant.h | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/variants/lilygo_techo/variant.h b/variants/lilygo_techo/variant.h index da8d81d..1de62d9 100644 --- a/variants/lilygo_techo/variant.h +++ b/variants/lilygo_techo/variant.h @@ -58,6 +58,19 @@ #define PIN_SPI_SCK (19) #define PIN_SPI_NSS (24) +//////////////////////////////////////////////////////////////////////////////// +// QSPI FLASH + +#define PIN_QSPI_SCK (46) +#define PIN_QSPI_CS (47) +#define PIN_QSPI_IO0 (44) +#define PIN_QSPI_IO1 (45) +#define PIN_QSPI_IO2 (7) +#define PIN_QSPI_IO3 (5) + +#define EXTERNAL_FLASH_DEVICES ZD25WQ16BUIGR +#define EXTERNAL_FLASH_USE_QSPI + //////////////////////////////////////////////////////////////////////////////// // Builtin LEDs From 7363a4f67dbeb95cbecffde5f6e6ddd2ae6fcfa8 Mon Sep 17 00:00:00 2001 From: ViezeVingertjes Date: Sun, 7 Sep 2025 14:08:26 +0200 Subject: [PATCH 25/50] Few adjustments after testing. --- src/helpers/nrf52/SerialBLEInterface.cpp | 30 ++++-------------------- 1 file changed, 5 insertions(+), 25 deletions(-) diff --git a/src/helpers/nrf52/SerialBLEInterface.cpp b/src/helpers/nrf52/SerialBLEInterface.cpp index 283fe40..4870895 100644 --- a/src/helpers/nrf52/SerialBLEInterface.cpp +++ b/src/helpers/nrf52/SerialBLEInterface.cpp @@ -25,28 +25,14 @@ void SerialBLEInterface::begin(const char* device_name, uint32_t pin_code) { char charpin[20]; sprintf(charpin, "%d", pin_code); - Bluefruit.configPrphBandwidth( + Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); + Bluefruit.configPrphConn(250, BLE_GAP_EVENT_LENGTH_MIN, 16, 16); // increase MTU #ifdef BLE_LOW_POWER - BANDWIDTH_NORMAL + Bluefruit.setTxPower(0); #else - BANDWIDTH_MAX + Bluefruit.setTxPower(4); #endif - ); - Bluefruit.configPrphConn( -#ifdef BLE_LOW_POWER - 400, BLE_GAP_EVENT_LENGTH_MIN, 8, 8 -#else - 250, BLE_GAP_EVENT_LENGTH_MIN, 16, 16 // increase MTU -#endif - ); Bluefruit.begin(); - Bluefruit.setTxPower( -#ifdef BLE_LOW_POWER - 0 -#else - 4 -#endif - ); // Check bluefruit.h for supported values Bluefruit.setName(device_name); Bluefruit.Security.setMITM(true); @@ -98,13 +84,7 @@ void SerialBLEInterface::startAdv() { * https://developer.apple.com/library/content/qa/qa1931/_index.html */ Bluefruit.Advertising.restartOnDisconnect(false); // don't restart automatically as we handle it in onDisconnect - Bluefruit.Advertising.setInterval( -#ifdef BLE_LOW_POWER - 160, 1600 -#else - 32, 244 -#endif - ); // in unit of 0.625 ms + Bluefruit.Advertising.setInterval(32, 1600); Bluefruit.Advertising.setFastTimeout(30); // number of seconds in fast mode Bluefruit.Advertising.start(0); // 0 = Don't stop advertising after n seconds From 5370667bd85b9c3c24d7f430a318e975dc9ab5d4 Mon Sep 17 00:00:00 2001 From: ViezeVingertjes Date: Sun, 7 Sep 2025 15:44:24 +0200 Subject: [PATCH 26/50] Replaced BLE_LOW_POWER with BLE_TX_POWER & updated usages. --- src/helpers/nrf52/SerialBLEInterface.cpp | 6 +----- src/helpers/nrf52/SerialBLEInterface.h | 4 ++++ variants/t1000-e/platformio.ini | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/helpers/nrf52/SerialBLEInterface.cpp b/src/helpers/nrf52/SerialBLEInterface.cpp index 4870895..4bc9d10 100644 --- a/src/helpers/nrf52/SerialBLEInterface.cpp +++ b/src/helpers/nrf52/SerialBLEInterface.cpp @@ -27,11 +27,7 @@ void SerialBLEInterface::begin(const char* device_name, uint32_t pin_code) { Bluefruit.configPrphBandwidth(BANDWIDTH_MAX); Bluefruit.configPrphConn(250, BLE_GAP_EVENT_LENGTH_MIN, 16, 16); // increase MTU -#ifdef BLE_LOW_POWER - Bluefruit.setTxPower(0); -#else - Bluefruit.setTxPower(4); -#endif + Bluefruit.setTxPower(BLE_TX_POWER); Bluefruit.begin(); Bluefruit.setName(device_name); diff --git a/src/helpers/nrf52/SerialBLEInterface.h b/src/helpers/nrf52/SerialBLEInterface.h index 12a4f46..239cf6c 100644 --- a/src/helpers/nrf52/SerialBLEInterface.h +++ b/src/helpers/nrf52/SerialBLEInterface.h @@ -3,6 +3,10 @@ #include "../BaseSerialInterface.h" #include +#ifndef BLE_TX_POWER +#define BLE_TX_POWER 4 +#endif + class SerialBLEInterface : public BaseSerialInterface { BLEUart bleuart; bool _isEnabled; diff --git a/variants/t1000-e/platformio.ini b/variants/t1000-e/platformio.ini index 88c0b45..8978ec1 100644 --- a/variants/t1000-e/platformio.ini +++ b/variants/t1000-e/platformio.ini @@ -100,7 +100,7 @@ build_flags = ${t1000-e.build_flags} -D MAX_CONTACTS=100 -D MAX_GROUP_CHANNELS=8 -D BLE_PIN_CODE=123456 - -D BLE_LOW_POWER=1 + -D BLE_TX_POWER=0 ; -D BLE_DEBUG_LOGGING=1 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 From 006605ce1de40dbc6f0aad4c7ffbe01d9d1aac6f Mon Sep 17 00:00:00 2001 From: Florent Date: Sun, 7 Sep 2025 19:48:02 +0200 Subject: [PATCH 27/50] t1000e: revert GPS_RESETB as an INPUT --- variants/t1000-e/T1000eBoard.h | 2 -- variants/t1000-e/variant.cpp | 3 +-- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/variants/t1000-e/T1000eBoard.h b/variants/t1000-e/T1000eBoard.h index 581a907..359e5e9 100644 --- a/variants/t1000-e/T1000eBoard.h +++ b/variants/t1000-e/T1000eBoard.h @@ -57,8 +57,6 @@ public: digitalWrite(GPS_SLEEP_INT, LOW); digitalWrite(GPS_RTC_INT, LOW); digitalWrite(GPS_EN, LOW); - pinMode(GPS_RESETB, OUTPUT); - digitalWrite(GPS_RESETB, LOW); #endif #ifdef BUZZER_EN diff --git a/variants/t1000-e/variant.cpp b/variants/t1000-e/variant.cpp index f9328e3..f17b3a8 100644 --- a/variants/t1000-e/variant.cpp +++ b/variants/t1000-e/variant.cpp @@ -69,7 +69,7 @@ void initVariant() pinMode(BATTERY_PIN, INPUT); pinMode(EXT_CHRG_DETECT, INPUT); pinMode(EXT_PWR_DETECT, INPUT); - pinMode(GPS_RESETB, OUTPUT); + pinMode(GPS_RESETB, INPUT); pinMode(PIN_BUTTON1, INPUT); pinMode(PIN_3V3_EN, OUTPUT); @@ -92,6 +92,5 @@ void initVariant() digitalWrite(GPS_VRTC_EN, LOW); digitalWrite(GPS_SLEEP_INT, HIGH); digitalWrite(GPS_RTC_INT, LOW); - digitalWrite(GPS_RESETB, LOW); digitalWrite(LED_PIN, LOW); } From 5b9d11ac8f9c91431ef417ac16280440d1920ec0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Sun, 7 Sep 2025 21:39:54 +0100 Subject: [PATCH 28/50] Support ESPNow and improve documentation --- examples/simple_repeater/main.cpp | 62 +++++--- src/helpers/bridges/ESPNowBridge.cpp | 184 ++++++++++++++++++++++ src/helpers/bridges/ESPNowBridge.h | 170 ++++++++++++++++++++ src/helpers/bridges/RS232Bridge.cpp | 5 +- src/helpers/bridges/RS232Bridge.h | 77 +++++++-- variants/lilygo_tlora_v2_1/platformio.ini | 71 ++++++--- 6 files changed, 510 insertions(+), 59 deletions(-) create mode 100644 src/helpers/bridges/ESPNowBridge.cpp create mode 100644 src/helpers/bridges/ESPNowBridge.h diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 3e2795d..b78481d 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -80,30 +80,36 @@ #ifdef WITH_RS232_BRIDGE #include "helpers/bridges/RS232Bridge.h" +#define WITH_BRIDGE #endif -#define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS -#define REQ_TYPE_KEEP_ALIVE 0x02 -#define REQ_TYPE_GET_TELEMETRY_DATA 0x03 +#ifdef WITH_ESPNOW_BRIDGE +#include "helpers/bridges/ESPNowBridge.h" +#define WITH_BRIDGE +#endif -#define RESP_SERVER_LOGIN_OK 0 // response to ANON_REQ +#define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS +#define REQ_TYPE_KEEP_ALIVE 0x02 +#define REQ_TYPE_GET_TELEMETRY_DATA 0x03 -struct RepeaterStats { - uint16_t batt_milli_volts; - uint16_t curr_tx_queue_len; - int16_t noise_floor; - int16_t last_rssi; - uint32_t n_packets_recv; - uint32_t n_packets_sent; - uint32_t total_air_time_secs; - uint32_t total_up_time_secs; - uint32_t n_sent_flood, n_sent_direct; - uint32_t n_recv_flood, n_recv_direct; - uint16_t err_events; // was 'n_full_events' - int16_t last_snr; // x 4 - uint16_t n_direct_dups, n_flood_dups; - uint32_t total_rx_air_time_secs; -}; +#define RESP_SERVER_LOGIN_OK 0 // response to ANON_REQ + + struct RepeaterStats { + uint16_t batt_milli_volts; + uint16_t curr_tx_queue_len; + int16_t noise_floor; + int16_t last_rssi; + uint32_t n_packets_recv; + uint32_t n_packets_sent; + uint32_t total_air_time_secs; + uint32_t total_up_time_secs; + uint32_t n_sent_flood, n_sent_direct; + uint32_t n_recv_flood, n_recv_direct; + uint16_t err_events; // was 'n_full_events' + int16_t last_snr; // x 4 + uint16_t n_direct_dups, n_flood_dups; + uint32_t total_rx_air_time_secs; + }; struct ClientInfo { mesh::Identity id; @@ -118,7 +124,7 @@ struct ClientInfo { #define MAX_CLIENTS 32 #endif -#ifdef WITH_RS232_BRIDGE +#ifdef WITH_BRIDGE AbstractBridge* bridge; #endif @@ -308,7 +314,7 @@ protected: } } void logTx(mesh::Packet* pkt, int len) override { -#ifdef WITH_RS232_BRIDGE +#ifdef WITH_BRIDGE bridge->onPacketTransmitted(pkt); #endif if (_logging) { @@ -576,8 +582,14 @@ public: : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) { -#ifdef WITH_RS232_BRIDGE +#ifdef WITH_BRIDGE +#if defined(WITH_RS232_BRIDGE) bridge = new RS232Bridge(WITH_RS232_BRIDGE, _mgr, &rtc); +#elif defined(WITH_ESPNOW_BRIDGE) + bridge = new ESPNowBridge(_mgr, &rtc); +#else +#error "You must choose either RS232 or ESPNow bridge" +#endif #endif memset(known_clients, 0, sizeof(known_clients)); next_local_advert = next_flood_advert = 0; @@ -779,7 +791,7 @@ public: } void loop() { -#ifdef WITH_RS232_BRIDGE +#ifdef WITH_BRIDGE bridge->loop(); #endif @@ -831,7 +843,7 @@ void setup() { Serial.begin(115200); delay(1000); -#ifdef WITH_RS232_BRIDGE +#ifdef WITH_BRIDGE bridge->begin(); #endif diff --git a/src/helpers/bridges/ESPNowBridge.cpp b/src/helpers/bridges/ESPNowBridge.cpp new file mode 100644 index 0000000..a470d52 --- /dev/null +++ b/src/helpers/bridges/ESPNowBridge.cpp @@ -0,0 +1,184 @@ +#include "ESPNowBridge.h" + +#include +#include +#include + +#ifdef WITH_ESPNOW_BRIDGE + +// Static member to handle callbacks +ESPNowBridge *ESPNowBridge::_instance = nullptr; + +// Static callback wrappers +void ESPNowBridge::recv_cb(const uint8_t *mac, const uint8_t *data, int len) { + if (_instance) { + _instance->onDataRecv(mac, data, len); + } +} + +void ESPNowBridge::send_cb(const uint8_t *mac, esp_now_send_status_t status) { + if (_instance) { + _instance->onDataSent(mac, status); + } +} + +// Fletcher16 checksum calculation +static uint16_t fletcher16(const uint8_t *data, size_t len) { + uint16_t sum1 = 0; + uint16_t sum2 = 0; + + while (len--) { + sum1 = (sum1 + *data++) % 255; + sum2 = (sum2 + sum1) % 255; + } + + return (sum2 << 8) | sum1; +} + +ESPNowBridge::ESPNowBridge(mesh::PacketManager *mgr, mesh::RTCClock *rtc) + : _mgr(mgr), _rtc(rtc), _rx_buffer_pos(0) { + _instance = this; +} + +void ESPNowBridge::begin() { + // Initialize WiFi in station mode + WiFi.mode(WIFI_STA); + + // Initialize ESP-NOW + if (esp_now_init() != ESP_OK) { + Serial.printf("%s: ESPNOW BRIDGE: Error initializing ESP-NOW\n", getLogDateTime()); + return; + } + + // Register callbacks + esp_now_register_recv_cb(recv_cb); + esp_now_register_send_cb(send_cb); + + // Add broadcast peer + esp_now_peer_info_t peerInfo = {}; + memset(&peerInfo, 0, sizeof(peerInfo)); + memset(peerInfo.peer_addr, 0xFF, ESP_NOW_ETH_ALEN); // Broadcast address + peerInfo.channel = 0; + peerInfo.encrypt = false; + + if (esp_now_add_peer(&peerInfo) != ESP_OK) { + Serial.printf("%s: ESPNOW BRIDGE: Failed to add broadcast peer\n", getLogDateTime()); + return; + } +} + +void ESPNowBridge::loop() { + // Nothing to do here - ESP-NOW is callback based +} + +void ESPNowBridge::xorCrypt(uint8_t *data, size_t len) { + size_t keyLen = strlen(_secret); + for (size_t i = 0; i < len; i++) { + data[i] ^= _secret[i % keyLen]; + } +} + +void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int len) { + // Ignore packets that are too small + if (len < 3) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: ESPNOW BRIDGE: RX packet too small, len=%d\n", getLogDateTime(), len); +#endif + return; + } + + // Check packet header magic + if (data[0] != ESPNOW_HEADER_MAGIC) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: ESPNOW BRIDGE: RX invalid magic 0x%02X\n", getLogDateTime(), data[0]); +#endif + return; + } + + // Make a copy we can decrypt + uint8_t decrypted[MAX_ESPNOW_PACKET_SIZE]; + memcpy(decrypted, data + 1, len - 1); // Skip magic byte + + // Try to decrypt + xorCrypt(decrypted, len - 1); + + // Validate checksum + uint16_t received_checksum = (decrypted[0] << 8) | decrypted[1]; + uint16_t calculated_checksum = fletcher16(decrypted + 2, len - 3); + + if (received_checksum != calculated_checksum) { + // Failed to decrypt - likely from a different network +#if MESH_PACKET_LOGGING + Serial.printf("%s: ESPNOW BRIDGE: RX checksum mismatch, rcv=0x%04X calc=0x%04X\n", getLogDateTime(), + received_checksum, calculated_checksum); +#endif + return; + } + +#if MESH_PACKET_LOGGING + Serial.printf("%s: ESPNOW BRIDGE: RX, len=%d\n", getLogDateTime(), len - 3); +#endif + + // Create mesh packet + mesh::Packet *pkt = _instance->_mgr->allocNew(); + if (!pkt) return; + + if (pkt->readFrom(decrypted + 2, len - 3)) { + _instance->onPacketReceived(pkt); + } else { + _instance->_mgr->free(pkt); + } +} + +void ESPNowBridge::onDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) { + // Could add transmission error handling here if needed +} + +void ESPNowBridge::onPacketReceived(mesh::Packet *packet) { + if (!_seen_packets.hasSeen(packet)) { + _mgr->queueInbound(packet, 0); + } else { + _mgr->free(packet); + } +} + +void ESPNowBridge::onPacketTransmitted(mesh::Packet *packet) { + if (!_seen_packets.hasSeen(packet)) { + uint8_t buffer[MAX_ESPNOW_PACKET_SIZE]; + buffer[0] = ESPNOW_HEADER_MAGIC; + + // Write packet to buffer starting after magic byte and checksum + uint16_t len = packet->writeTo(buffer + 3); + + // Calculate and add checksum + uint16_t checksum = fletcher16(buffer + 3, len); + buffer[1] = (checksum >> 8) & 0xFF; + buffer[2] = checksum & 0xFF; + + // Encrypt payload (not including magic byte) + xorCrypt(buffer + 1, len + 2); + + // Broadcast using ESP-NOW + uint8_t broadcastAddress[] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; + esp_err_t result = esp_now_send(broadcastAddress, buffer, len + 3); + +#if MESH_PACKET_LOGGING + if (result == ESP_OK) { + Serial.printf("%s: ESPNOW BRIDGE: TX, len=%d\n", getLogDateTime(), len); + } else { + Serial.printf("%s: ESPNOW BRIDGE: TX FAILED!\n", getLogDateTime()); + } +#endif + } +} + +const char *ESPNowBridge::getLogDateTime() { + static char tmp[32]; + uint32_t now = _rtc->getCurrentTime(); + DateTime dt = DateTime(now); + sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), + dt.year()); + return tmp; +} + +#endif diff --git a/src/helpers/bridges/ESPNowBridge.h b/src/helpers/bridges/ESPNowBridge.h new file mode 100644 index 0000000..7d2dbb0 --- /dev/null +++ b/src/helpers/bridges/ESPNowBridge.h @@ -0,0 +1,170 @@ +#pragma once + +#include "MeshCore.h" +#include "esp_now.h" +#include "helpers/AbstractBridge.h" +#include "helpers/SimpleMeshTables.h" + +#ifdef WITH_ESPNOW_BRIDGE + +#ifndef WITH_ESPNOW_BRIDGE_SECRET +#error WITH_ESPNOW_BRIDGE_SECRET must be defined to use ESPNowBridge +#endif + +/** + * @brief Bridge implementation using ESP-NOW protocol for packet transport + * + * This bridge enables mesh packet transport over ESP-NOW, a connectionless communication + * protocol provided by Espressif that allows ESP32 devices to communicate directly + * without WiFi router infrastructure. + * + * Features: + * - Broadcast-based communication (all bridges receive all packets) + * - Network isolation using XOR encryption with shared secret + * - Duplicate packet detection using SimpleMeshTables tracking + * - Maximum packet size of 250 bytes (ESP-NOW limitation) + * + * Packet Structure: + * [1 byte] Magic Header (0xAB) - Used to identify ESPNowBridge packets + * [2 bytes] Fletcher-16 checksum of encrypted payload (calculated over payload only) + * [n bytes] Encrypted payload containing the mesh packet + * + * The Fletcher-16 checksum is used to validate packet integrity and detect + * corrupted or tampered packets. It's calculated over the encrypted payload + * and provides a simple but effective way to verify packets are both + * uncorrupted and from the same network (since the checksum is calculated + * after encryption). + * + * Configuration: + * - Define WITH_ESPNOW_BRIDGE to enable this bridge + * - Define WITH_ESPNOW_BRIDGE_SECRET with a string to set the network encryption key + * + * Network Isolation: + * Multiple independent mesh networks can coexist by using different + * WITH_ESPNOW_BRIDGE_SECRET values. Packets encrypted with a different key will + * fail the checksum validation and be discarded. + */ +class ESPNowBridge : public AbstractBridge { +private: + static ESPNowBridge *_instance; + static void recv_cb(const uint8_t *mac, const uint8_t *data, int len); + static void send_cb(const uint8_t *mac, esp_now_send_status_t status); + + /** Packet manager for allocating and queuing mesh packets */ + mesh::PacketManager *_mgr; + + /** RTC clock for timestamping debug messages */ + mesh::RTCClock *_rtc; + + /** Tracks seen packets to prevent loops in broadcast communications */ + SimpleMeshTables _seen_packets; + + /** + * Maximum ESP-NOW packet size (250 bytes) + * This is a hardware limitation of ESP-NOW protocol: + * - ESP-NOW header: 20 bytes + * - Max payload: 250 bytes + * Source: ESP-NOW API documentation + */ + static const size_t MAX_ESPNOW_PACKET_SIZE = 250; + + /** + * Magic byte to identify ESPNowBridge packets (0xAB) + */ + static const uint8_t ESPNOW_HEADER_MAGIC = 0xAB; + + /** Buffer for receiving ESP-NOW packets */ + uint8_t _rx_buffer[MAX_ESPNOW_PACKET_SIZE]; + + /** Current position in receive buffer */ + size_t _rx_buffer_pos; + + /** + * Network encryption key from build define + * Must be defined with WITH_ESPNOW_BRIDGE_SECRET + * Used for XOR encryption to isolate different mesh networks + */ + const char *_secret = WITH_ESPNOW_BRIDGE_SECRET; + + /** + * Performs XOR encryption/decryption of data + * + * Uses WITH_ESPNOW_BRIDGE_SECRET as the key in a simple XOR operation. + * The same operation is used for both encryption and decryption. + * While not cryptographically secure, it provides basic network isolation. + * + * @param data Pointer to data to encrypt/decrypt + * @param len Length of data in bytes + */ + void xorCrypt(uint8_t *data, size_t len); + + /** + * ESP-NOW receive callback + * Called by ESP-NOW when a packet is received + * + * @param mac Source MAC address + * @param data Received data + * @param len Length of received data + */ + void onDataRecv(const uint8_t *mac, const uint8_t *data, int len); + + /** + * ESP-NOW send callback + * Called by ESP-NOW after a transmission attempt + * + * @param mac_addr Destination MAC address + * @param status Transmission status + */ + void onDataSent(const uint8_t *mac_addr, esp_now_send_status_t status); + +public: + /** + * Constructs an ESPNowBridge instance + * + * @param mgr PacketManager for allocating and queuing packets + * @param rtc RTCClock for timestamping debug messages + */ + ESPNowBridge(mesh::PacketManager *mgr, mesh::RTCClock *rtc); + + /** + * Initializes the ESP-NOW bridge + * + * - Configures WiFi in station mode + * - Initializes ESP-NOW protocol + * - Registers callbacks + * - Sets up broadcast peer + */ + void begin() override; + + /** + * Main loop handler + * ESP-NOW is callback-based, so this is currently empty + */ + void loop() override; + + /** + * Called when a packet is received via ESP-NOW + * Queues the packet for mesh processing if not seen before + * + * @param packet The received mesh packet + */ + void onPacketReceived(mesh::Packet *packet) override; + + /** + * Called when a packet needs to be transmitted via ESP-NOW + * Encrypts and broadcasts the packet if not seen before + * + * @param packet The mesh packet to transmit + */ + void onPacketTransmitted(mesh::Packet *packet) override; + + /** + * Gets formatted date/time string for logging + * Format: "HH:MM:SS - DD/MM/YYYY U" + * + * @return Formatted date/time string + */ + const char *getLogDateTime(); +}; + +#endif diff --git a/src/helpers/bridges/RS232Bridge.cpp b/src/helpers/bridges/RS232Bridge.cpp index 801bcc5..5c3b8ca 100644 --- a/src/helpers/bridges/RS232Bridge.cpp +++ b/src/helpers/bridges/RS232Bridge.cpp @@ -4,8 +4,9 @@ #ifdef WITH_RS232_BRIDGE -// Fletcher-16 -// https://en.wikipedia.org/wiki/Fletcher%27s_checksum +// Static Fletcher-16 checksum calculation +// Based on: https://en.wikipedia.org/wiki/Fletcher%27s_checksum +// Used to verify data integrity of received packets inline static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { uint8_t sum1 = 0, sum2 = 0; diff --git a/src/helpers/bridges/RS232Bridge.h b/src/helpers/bridges/RS232Bridge.h index 0e99040..2adeb50 100644 --- a/src/helpers/bridges/RS232Bridge.h +++ b/src/helpers/bridges/RS232Bridge.h @@ -7,28 +7,87 @@ #ifdef WITH_RS232_BRIDGE /** - * @brief A bridge implementation that uses a serial port to connect two mesh networks. + * @brief Bridge implementation using RS232/UART protocol for packet transport + * + * This bridge enables mesh packet transport over serial/UART connections, + * allowing nodes to communicate over wired serial links. It implements a simple + * packet framing protocol with checksums for reliable transfer. + * + * Features: + * - Point-to-point communication over hardware UART + * - Fletcher-16 checksum for data integrity verification + * - Magic header for packet synchronization + * - Configurable RX/TX pins via build defines + * - Baud rate fixed at 115200 + * + * Packet Structure: + * [2 bytes] Magic Header (0xCAFE) - Used to identify start of packet + * [2 bytes] Fletcher-16 checksum - Data integrity check + * [1 byte] Payload length + * [n bytes] Packet payload + * + * The Fletcher-16 checksum is used to validate packet integrity and detect + * corrupted or malformed packets. It provides error detection capabilities + * suitable for serial communication where noise or timing issues could + * corrupt data. + * + * Configuration: + * - Define WITH_RS232_BRIDGE to enable this bridge + * - Define WITH_RS232_BRIDGE_RX with the RX pin number + * - Define WITH_RS232_BRIDGE_TX with the TX pin number + * + * Platform Support: + * - ESP32 targets + * - NRF52 targets + * - RP2040 targets + * - STM32 targets */ class RS232Bridge : public AbstractBridge { public: /** - * @brief Construct a new Serial Bridge object - * - * @param serial The serial port to use for the bridge. - * @param mgr A pointer to the packet manager. - * @param rtc A pointer to the RTC clock. + * @brief Constructs an RS232Bridge instance + * + * @param serial The hardware serial port to use + * @param mgr PacketManager for allocating and queuing packets + * @param rtc RTCClock for timestamping debug messages */ RS232Bridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc); + + /** + * Initializes the RS232 bridge + * + * - Configures UART pins based on platform + * - Sets baud rate to 115200 + */ void begin() override; + + /** + * @brief Main loop handler + * Processes incoming serial data and builds packets + */ void loop() override; + + /** + * @brief Called when a packet needs to be transmitted over serial + * Formats and sends the packet with proper framing + * + * @param packet The mesh packet to transmit + */ void onPacketTransmitted(mesh::Packet* packet) override; + + /** + * @brief Called when a complete packet has been received from serial + * Queues the packet for mesh processing if checksum is valid + * + * @param packet The received mesh packet + */ void onPacketReceived(mesh::Packet* packet) override; private: + /** Helper function to get formatted timestamp for logging */ const char* getLogDateTime(); - /** - * @brief The 2-byte magic word used to signify the start of a packet. - */ + + /** Magic number to identify start of RS232 packets (0xCAFE) */ static constexpr uint16_t SERIAL_PKT_MAGIC = 0xCAFE; /** diff --git a/variants/lilygo_tlora_v2_1/platformio.ini b/variants/lilygo_tlora_v2_1/platformio.ini index 313b984..5e9874c 100644 --- a/variants/lilygo_tlora_v2_1/platformio.ini +++ b/variants/lilygo_tlora_v2_1/platformio.ini @@ -64,29 +64,6 @@ lib_deps = ${LilyGo_TLora_V2_1_1_6.lib_deps} ${esp32_ota.lib_deps} -[env:LilyGo_TLora_V2_1_1_6_repeater_bridge] -extends = LilyGo_TLora_V2_1_1_6 -build_src_filter = ${LilyGo_TLora_V2_1_1_6.build_src_filter} - + - + - +<../examples/simple_repeater> -build_flags = - ${LilyGo_TLora_V2_1_1_6.build_flags} - -D ADVERT_NAME='"TLora-V2.1-1.6 Bridge"' - -D ADVERT_LAT=0.0 - -D ADVERT_LON=0.0 - -D ADMIN_PASSWORD='"password"' - -D MAX_NEIGHBOURS=8 - -D WITH_RS232_BRIDGE=Serial2 - -D WITH_RS232_BRIDGE_RX=34 - -D WITH_RS232_BRIDGE_TX=25 - -D MESH_PACKET_LOGGING=1 -; -D MESH_DEBUG=1 -; -D CORE_DEBUG_LEVEL=3 -lib_deps = - ${LilyGo_TLora_V2_1_1_6.lib_deps} - ${esp32_ota.lib_deps} - [env:LilyGo_TLora_V2_1_1_6_terminal_chat] extends = LilyGo_TLora_V2_1_1_6 build_flags = @@ -179,3 +156,51 @@ build_src_filter = ${LilyGo_TLora_V2_1_1_6.build_src_filter} lib_deps = ${LilyGo_TLora_V2_1_1_6.lib_deps} densaugeo/base64 @ ~1.4.0 + +; +; Repeater Bridges +; +[env:LilyGo_TLora_V2_1_1_6_bridge_rs232] +extends = LilyGo_TLora_V2_1_1_6 +build_src_filter = ${LilyGo_TLora_V2_1_1_6.build_src_filter} + + + + + +<../examples/simple_repeater> +build_flags = + ${LilyGo_TLora_V2_1_1_6.build_flags} + -D ADVERT_NAME='"RS232 Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_RS232_BRIDGE=Serial2 + -D WITH_RS232_BRIDGE_RX=34 + -D WITH_RS232_BRIDGE_TX=25 + -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +; -D CORE_DEBUG_LEVEL=3 +lib_deps = + ${LilyGo_TLora_V2_1_1_6.lib_deps} + ${esp32_ota.lib_deps} + +[env:LilyGo_TLora_V2_1_1_6_bridge_espnow] +extends = LilyGo_TLora_V2_1_1_6 +build_src_filter = ${LilyGo_TLora_V2_1_1_6.build_src_filter} + + + + + +<../examples/simple_repeater> +build_flags = + ${LilyGo_TLora_V2_1_1_6.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' + -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +; -D CORE_DEBUG_LEVEL=3 +lib_deps = + ${LilyGo_TLora_V2_1_1_6.lib_deps} + ${esp32_ota.lib_deps} \ No newline at end of file From 04e70829a454703638e3740dc017cbf995d9f23a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Sun, 7 Sep 2025 21:46:51 +0100 Subject: [PATCH 29/50] Rename RS232 bridge environments --- variants/heltec_v3/platformio.ini | 55 +++++++++++++++++-- variants/lilygo_tlora_v2_1/platformio.ini | 4 +- variants/waveshare_rp2040_lora/platformio.ini | 6 +- 3 files changed, 54 insertions(+), 11 deletions(-) diff --git a/variants/heltec_v3/platformio.ini b/variants/heltec_v3/platformio.ini index 4ffb11b..c7ab86d 100644 --- a/variants/heltec_v3/platformio.ini +++ b/variants/heltec_v3/platformio.ini @@ -49,12 +49,12 @@ lib_deps = ${esp32_ota.lib_deps} bakercp/CRC32 @ ^2.0.0 -[env:Heltec_v3_repeater_bridge] +[env:Heltec_v3_repeater_bridge_rs232] extends = Heltec_lora32_v3 build_flags = ${Heltec_lora32_v3.build_flags} -D DISPLAY_CLASS=SSD1306Display - -D ADVERT_NAME='"Heltec Bridge"' + -D ADVERT_NAME='"RS232 Bridge"' -D ADVERT_LAT=0.0 -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' @@ -62,11 +62,33 @@ build_flags = -D WITH_RS232_BRIDGE=Serial2 -D WITH_RS232_BRIDGE_RX=5 -D WITH_RS232_BRIDGE_TX=6 - -D MESH_PACKET_LOGGING=1 +; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${Heltec_lora32_v3.build_src_filter} - + + + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_lora32_v3.lib_deps} + ${esp32_ota.lib_deps} + +[env:Heltec_v3_repeater_bridge_espnow] +extends = Heltec_lora32_v3 +build_flags = + ${Heltec_lora32_v3.build_flags} + -D DISPLAY_CLASS=SSD1306Display + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_lora32_v3.build_src_filter} + + + + +<../examples/simple_repeater> lib_deps = ${Heltec_lora32_v3.lib_deps} @@ -209,11 +231,11 @@ lib_deps = ${esp32_ota.lib_deps} bakercp/CRC32 @ ^2.0.0 -[env:Heltec_WSL3_repeater_bridge] +[env:Heltec_WSL3_repeater_bridge_rs232] extends = Heltec_lora32_v3 build_flags = ${Heltec_lora32_v3.build_flags} - -D ADVERT_NAME='"Heltec WSL3 Bridge"' + -D ADVERT_NAME='"RS232 Bridge"' -D ADVERT_LAT=0.0 -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' @@ -231,6 +253,27 @@ lib_deps = ${esp32_ota.lib_deps} bakercp/CRC32 @ ^2.0.0 +[env:Heltec_WSL3_repeater_bridge_espnow] +extends = Heltec_lora32_v3 +build_flags = + ${Heltec_lora32_v3.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_lora32_v3.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_lora32_v3.lib_deps} + ${esp32_ota.lib_deps} + bakercp/CRC32 @ ^2.0.0 + [env:Heltec_WSL3_room_server] extends = Heltec_lora32_v3 build_src_filter = ${Heltec_lora32_v3.build_src_filter} diff --git a/variants/lilygo_tlora_v2_1/platformio.ini b/variants/lilygo_tlora_v2_1/platformio.ini index 5e9874c..aa957fb 100644 --- a/variants/lilygo_tlora_v2_1/platformio.ini +++ b/variants/lilygo_tlora_v2_1/platformio.ini @@ -176,7 +176,7 @@ build_flags = -D WITH_RS232_BRIDGE=Serial2 -D WITH_RS232_BRIDGE_RX=34 -D WITH_RS232_BRIDGE_TX=25 - -D MESH_PACKET_LOGGING=1 +; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 ; -D CORE_DEBUG_LEVEL=3 lib_deps = @@ -198,7 +198,7 @@ build_flags = -D MAX_NEIGHBOURS=8 -D WITH_ESPNOW_BRIDGE=1 -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' - -D MESH_PACKET_LOGGING=1 +; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 ; -D CORE_DEBUG_LEVEL=3 lib_deps = diff --git a/variants/waveshare_rp2040_lora/platformio.ini b/variants/waveshare_rp2040_lora/platformio.ini index 8824ddb..0f33306 100644 --- a/variants/waveshare_rp2040_lora/platformio.ini +++ b/variants/waveshare_rp2040_lora/platformio.ini @@ -40,10 +40,10 @@ build_flags = ${waveshare_rp2040_lora.build_flags} build_src_filter = ${waveshare_rp2040_lora.build_src_filter} +<../examples/simple_repeater> -[env:waveshare_rp2040_lora_repeater_bridge] +[env:waveshare_rp2040_lora_repeater_bridge_rs232] extends = waveshare_rp2040_lora build_flags = ${waveshare_rp2040_lora.build_flags} - -D ADVERT_NAME='"RP2040-LoRa Bridge"' + -D ADVERT_NAME='"RS232 Bridge"' -D ADVERT_LAT=0.0 -D ADVERT_LON=0.0 -D ADMIN_PASSWORD='"password"' @@ -51,7 +51,7 @@ build_flags = ${waveshare_rp2040_lora.build_flags} -D WITH_RS232_BRIDGE=Serial2 -D WITH_RS232_BRIDGE_RX=9 -D WITH_RS232_BRIDGE_TX=8 - -D MESH_PACKET_LOGGING=1 +; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${waveshare_rp2040_lora.build_src_filter} + From 537449e6af5895bd9aa107ddd416f1b3fbb216d9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Sun, 7 Sep 2025 22:00:06 +0100 Subject: [PATCH 30/50] Refactor ESPNowBridge packet handling to use 2-byte magic header and improve packet size validation --- src/helpers/bridges/ESPNowBridge.cpp | 88 ++++++++++++++++++++-------- src/helpers/bridges/ESPNowBridge.h | 33 +++++++---- src/helpers/bridges/RS232Bridge.h | 6 +- 3 files changed, 89 insertions(+), 38 deletions(-) diff --git a/src/helpers/bridges/ESPNowBridge.cpp b/src/helpers/bridges/ESPNowBridge.cpp index a470d52..aed63a6 100644 --- a/src/helpers/bridges/ESPNowBridge.cpp +++ b/src/helpers/bridges/ESPNowBridge.cpp @@ -10,7 +10,7 @@ ESPNowBridge *ESPNowBridge::_instance = nullptr; // Static callback wrappers -void ESPNowBridge::recv_cb(const uint8_t *mac, const uint8_t *data, int len) { +void ESPNowBridge::recv_cb(const uint8_t *mac, const uint8_t *data, int32_t len) { if (_instance) { _instance->onDataRecv(mac, data, len); } @@ -78,33 +78,44 @@ void ESPNowBridge::xorCrypt(uint8_t *data, size_t len) { } } -void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int len) { - // Ignore packets that are too small - if (len < 3) { +void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int32_t len) { + // Ignore packets that are too small to contain header + checksum + if (len < (MAGIC_HEADER_SIZE + CHECKSUM_SIZE)) { #if MESH_PACKET_LOGGING Serial.printf("%s: ESPNOW BRIDGE: RX packet too small, len=%d\n", getLogDateTime(), len); #endif return; } - // Check packet header magic - if (data[0] != ESPNOW_HEADER_MAGIC) { + // Validate total packet size + if (len > MAX_ESPNOW_PACKET_SIZE) { #if MESH_PACKET_LOGGING - Serial.printf("%s: ESPNOW BRIDGE: RX invalid magic 0x%02X\n", getLogDateTime(), data[0]); + Serial.printf("%s: ESPNOW BRIDGE: RX packet too large, len=%d\n", getLogDateTime(), len); +#endif + return; + } + + // Check packet header magic + uint16_t received_magic = (data[0] << 8) | data[1]; + if (received_magic != ESPNOW_HEADER_MAGIC) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: ESPNOW BRIDGE: RX invalid magic 0x%04X\n", getLogDateTime(), received_magic); #endif return; } // Make a copy we can decrypt uint8_t decrypted[MAX_ESPNOW_PACKET_SIZE]; - memcpy(decrypted, data + 1, len - 1); // Skip magic byte + const size_t encryptedDataLen = len - MAGIC_HEADER_SIZE; + memcpy(decrypted, data + MAGIC_HEADER_SIZE, encryptedDataLen); - // Try to decrypt - xorCrypt(decrypted, len - 1); + // Try to decrypt (checksum + payload) + xorCrypt(decrypted, encryptedDataLen); // Validate checksum uint16_t received_checksum = (decrypted[0] << 8) | decrypted[1]; - uint16_t calculated_checksum = fletcher16(decrypted + 2, len - 3); + const size_t payloadLen = encryptedDataLen - CHECKSUM_SIZE; + uint16_t calculated_checksum = fletcher16(decrypted + CHECKSUM_SIZE, payloadLen); if (received_checksum != calculated_checksum) { // Failed to decrypt - likely from a different network @@ -116,14 +127,14 @@ void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int len) } #if MESH_PACKET_LOGGING - Serial.printf("%s: ESPNOW BRIDGE: RX, len=%d\n", getLogDateTime(), len - 3); + Serial.printf("%s: ESPNOW BRIDGE: RX, payload_len=%d\n", getLogDateTime(), payloadLen); #endif // Create mesh packet mesh::Packet *pkt = _instance->_mgr->allocNew(); if (!pkt) return; - if (pkt->readFrom(decrypted + 2, len - 3)) { + if (pkt->readFrom(decrypted + CHECKSUM_SIZE, payloadLen)) { _instance->onPacketReceived(pkt); } else { _instance->_mgr->free(pkt); @@ -144,27 +155,56 @@ void ESPNowBridge::onPacketReceived(mesh::Packet *packet) { void ESPNowBridge::onPacketTransmitted(mesh::Packet *packet) { if (!_seen_packets.hasSeen(packet)) { + + // First validate the packet pointer + if (!packet) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: ESPNOW BRIDGE: TX invalid packet pointer\n", getLogDateTime()); +#endif + return; + } + + // Create a temporary buffer just for size calculation and reuse for actual writing + uint8_t sizingBuffer[MAX_PAYLOAD_SIZE]; + uint16_t meshPacketLen = packet->writeTo(sizingBuffer); + + // Check if packet fits within our maximum payload size + if (meshPacketLen > MAX_PAYLOAD_SIZE) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: ESPNOW BRIDGE: TX packet too large (payload=%d, max=%d)\n", getLogDateTime(), + meshPacketLen, MAX_PAYLOAD_SIZE); +#endif + return; + } + uint8_t buffer[MAX_ESPNOW_PACKET_SIZE]; - buffer[0] = ESPNOW_HEADER_MAGIC; - // Write packet to buffer starting after magic byte and checksum - uint16_t len = packet->writeTo(buffer + 3); + // Write magic header (2 bytes) + buffer[0] = (ESPNOW_HEADER_MAGIC >> 8) & 0xFF; + buffer[1] = ESPNOW_HEADER_MAGIC & 0xFF; - // Calculate and add checksum - uint16_t checksum = fletcher16(buffer + 3, len); - buffer[1] = (checksum >> 8) & 0xFF; - buffer[2] = checksum & 0xFF; + // Write packet payload starting after magic header and checksum + const size_t packetOffset = MAGIC_HEADER_SIZE + CHECKSUM_SIZE; + memcpy(buffer + packetOffset, sizingBuffer, meshPacketLen); - // Encrypt payload (not including magic byte) - xorCrypt(buffer + 1, len + 2); + // Calculate and add checksum (only of the payload) + uint16_t checksum = fletcher16(buffer + packetOffset, meshPacketLen); + buffer[2] = (checksum >> 8) & 0xFF; // High byte + buffer[3] = checksum & 0xFF; // Low byte + + // Encrypt payload and checksum (not including magic header) + xorCrypt(buffer + MAGIC_HEADER_SIZE, meshPacketLen + CHECKSUM_SIZE); + + // Total packet size: magic header + checksum + payload + const size_t totalPacketSize = MAGIC_HEADER_SIZE + CHECKSUM_SIZE + meshPacketLen; // Broadcast using ESP-NOW uint8_t broadcastAddress[] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; - esp_err_t result = esp_now_send(broadcastAddress, buffer, len + 3); + esp_err_t result = esp_now_send(broadcastAddress, buffer, totalPacketSize); #if MESH_PACKET_LOGGING if (result == ESP_OK) { - Serial.printf("%s: ESPNOW BRIDGE: TX, len=%d\n", getLogDateTime(), len); + Serial.printf("%s: ESPNOW BRIDGE: TX, len=%d\n", getLogDateTime(), meshPacketLen); } else { Serial.printf("%s: ESPNOW BRIDGE: TX FAILED!\n", getLogDateTime()); } diff --git a/src/helpers/bridges/ESPNowBridge.h b/src/helpers/bridges/ESPNowBridge.h index 7d2dbb0..5c77147 100644 --- a/src/helpers/bridges/ESPNowBridge.h +++ b/src/helpers/bridges/ESPNowBridge.h @@ -25,9 +25,9 @@ * - Maximum packet size of 250 bytes (ESP-NOW limitation) * * Packet Structure: - * [1 byte] Magic Header (0xAB) - Used to identify ESPNowBridge packets + * [2 bytes] Magic Header - Used to identify ESPNowBridge packets * [2 bytes] Fletcher-16 checksum of encrypted payload (calculated over payload only) - * [n bytes] Encrypted payload containing the mesh packet + * [246 bytes max] Encrypted payload containing the mesh packet * * The Fletcher-16 checksum is used to validate packet integrity and detect * corrupted or tampered packets. It's calculated over the encrypted payload @@ -47,7 +47,7 @@ class ESPNowBridge : public AbstractBridge { private: static ESPNowBridge *_instance; - static void recv_cb(const uint8_t *mac, const uint8_t *data, int len); + static void recv_cb(const uint8_t *mac, const uint8_t *data, int32_t len); static void send_cb(const uint8_t *mac, esp_now_send_status_t status); /** Packet manager for allocating and queuing mesh packets */ @@ -60,18 +60,29 @@ private: SimpleMeshTables _seen_packets; /** - * Maximum ESP-NOW packet size (250 bytes) - * This is a hardware limitation of ESP-NOW protocol: - * - ESP-NOW header: 20 bytes - * - Max payload: 250 bytes - * Source: ESP-NOW API documentation + * ESP-NOW Protocol Structure: + * - ESP-NOW header: 20 bytes (handled by ESP-NOW protocol) + * - ESP-NOW payload: 250 bytes maximum + * Total ESP-NOW packet: 270 bytes + * + * Our Bridge Packet Structure (must fit in ESP-NOW payload): + * - Magic header: 2 bytes + * - Checksum: 2 bytes + * - Available payload: 246 bytes */ static const size_t MAX_ESPNOW_PACKET_SIZE = 250; /** - * Magic byte to identify ESPNowBridge packets (0xAB) + * Size constants for packet parsing */ - static const uint8_t ESPNOW_HEADER_MAGIC = 0xAB; + static const size_t MAGIC_HEADER_SIZE = 2; + static const size_t CHECKSUM_SIZE = 2; + static const size_t MAX_PAYLOAD_SIZE = MAX_ESPNOW_PACKET_SIZE - (MAGIC_HEADER_SIZE + CHECKSUM_SIZE); + + /** + * Magic bytes to identify ESPNowBridge packets + */ + static const uint16_t ESPNOW_HEADER_MAGIC = 0xC03E; /** Buffer for receiving ESP-NOW packets */ uint8_t _rx_buffer[MAX_ESPNOW_PACKET_SIZE]; @@ -106,7 +117,7 @@ private: * @param data Received data * @param len Length of received data */ - void onDataRecv(const uint8_t *mac, const uint8_t *data, int len); + void onDataRecv(const uint8_t *mac, const uint8_t *data, int32_t len); /** * ESP-NOW send callback diff --git a/src/helpers/bridges/RS232Bridge.h b/src/helpers/bridges/RS232Bridge.h index 2adeb50..49c781c 100644 --- a/src/helpers/bridges/RS232Bridge.h +++ b/src/helpers/bridges/RS232Bridge.h @@ -21,7 +21,7 @@ * - Baud rate fixed at 115200 * * Packet Structure: - * [2 bytes] Magic Header (0xCAFE) - Used to identify start of packet + * [2 bytes] Magic Header - Used to identify start of packet * [2 bytes] Fletcher-16 checksum - Data integrity check * [1 byte] Payload length * [n bytes] Packet payload @@ -87,8 +87,8 @@ private: /** Helper function to get formatted timestamp for logging */ const char* getLogDateTime(); - /** Magic number to identify start of RS232 packets (0xCAFE) */ - static constexpr uint16_t SERIAL_PKT_MAGIC = 0xCAFE; + /** Magic number to identify start of RS232 packets */ + static constexpr uint16_t SERIAL_PKT_MAGIC = 0xC03E; /** * @brief The total overhead of the serial protocol in bytes. From 0051ccef2603bcd207217036930654d7b660ccb0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Mon, 8 Sep 2025 02:03:08 +0100 Subject: [PATCH 31/50] Refactor bridge implementations to inherit from BridgeBase --- platformio.ini | 1 + src/helpers/bridges/BridgeBase.cpp | 34 +++++++ src/helpers/bridges/BridgeBase.h | 84 +++++++++++++++++ src/helpers/bridges/ESPNowBridge.cpp | 52 +++-------- src/helpers/bridges/ESPNowBridge.h | 22 +---- src/helpers/bridges/RS232Bridge.cpp | 115 ++++++++++++++---------- src/helpers/bridges/RS232Bridge.h | 129 +++++++++++++++++---------- 7 files changed, 282 insertions(+), 155 deletions(-) create mode 100644 src/helpers/bridges/BridgeBase.cpp create mode 100644 src/helpers/bridges/BridgeBase.h diff --git a/platformio.ini b/platformio.ini index 1c89465..d21f513 100644 --- a/platformio.ini +++ b/platformio.ini @@ -47,6 +47,7 @@ build_src_filter = +<*.cpp> + + + + + ; ----------------- ESP32 --------------------- diff --git a/src/helpers/bridges/BridgeBase.cpp b/src/helpers/bridges/BridgeBase.cpp new file mode 100644 index 0000000..2055119 --- /dev/null +++ b/src/helpers/bridges/BridgeBase.cpp @@ -0,0 +1,34 @@ +#include "BridgeBase.h" + +const char *BridgeBase::getLogDateTime() { + static char tmp[32]; + uint32_t now = _rtc->getCurrentTime(); + DateTime dt = DateTime(now); + sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), + dt.year()); + return tmp; +} + +uint16_t BridgeBase::fletcher16(const uint8_t *data, size_t len) { + uint8_t sum1 = 0, sum2 = 0; + + for (size_t i = 0; i < len; i++) { + sum1 = (sum1 + data[i]) % 255; + sum2 = (sum2 + sum1) % 255; + } + + return (sum2 << 8) | sum1; +} + +bool BridgeBase::validateChecksum(const uint8_t *data, size_t len, uint16_t received_checksum) { + uint16_t calculated_checksum = fletcher16(data, len); + return received_checksum == calculated_checksum; +} + +void BridgeBase::handleReceivedPacket(mesh::Packet *packet) { + if (!_seen_packets.hasSeen(packet)) { + _mgr->queueInbound(packet, 0); + } else { + _mgr->free(packet); + } +} diff --git a/src/helpers/bridges/BridgeBase.h b/src/helpers/bridges/BridgeBase.h new file mode 100644 index 0000000..2aff230 --- /dev/null +++ b/src/helpers/bridges/BridgeBase.h @@ -0,0 +1,84 @@ +#pragma once + +#include "helpers/AbstractBridge.h" +#include "helpers/SimpleMeshTables.h" + +#include + +/** + * @brief Base class implementing common bridge functionality + * + * This class provides common functionality used by different bridge implementations + * like packet tracking, checksum calculation, timestamping, and duplicate detection. + * + * Features: + * - Fletcher-16 checksum calculation for data integrity + * - Packet duplicate detection using SimpleMeshTables + * - Common timestamp formatting for debug logging + * - Shared packet management and queuing logic + */ +class BridgeBase : public AbstractBridge { +public: + virtual ~BridgeBase() = default; + +protected: + /** Packet manager for allocating and queuing mesh packets */ + mesh::PacketManager *_mgr; + + /** RTC clock for timestamping debug messages */ + mesh::RTCClock *_rtc; + + /** Tracks seen packets to prevent loops in broadcast communications */ + SimpleMeshTables _seen_packets; + + /** + * @brief Constructs a BridgeBase instance + * + * @param mgr PacketManager for allocating and queuing packets + * @param rtc RTCClock for timestamping debug messages + */ + BridgeBase(mesh::PacketManager *mgr, mesh::RTCClock *rtc) : _mgr(mgr), _rtc(rtc) {} + + /** + * @brief Gets formatted date/time string for logging + * + * Format: "HH:MM:SS - DD/MM/YYYY U" + * + * @return Formatted date/time string + */ + const char *getLogDateTime(); + + /** + * @brief Calculate Fletcher-16 checksum + * + * Based on: https://en.wikipedia.org/wiki/Fletcher%27s_checksum + * Used to verify data integrity of received packets + * + * @param data Pointer to data to calculate checksum for + * @param len Length of data in bytes + * @return Calculated Fletcher-16 checksum + */ + static uint16_t fletcher16(const uint8_t *data, size_t len); + + /** + * @brief Validate received checksum against calculated checksum + * + * @param data Pointer to data to validate + * @param len Length of data in bytes + * @param received_checksum Checksum received with data + * @return true if checksum is valid, false otherwise + */ + bool validateChecksum(const uint8_t *data, size_t len, uint16_t received_checksum); + + /** + * @brief Common packet handling for received packets + * + * Implements the standard pattern used by all bridges: + * - Check if packet was seen before using _seen_packets.hasSeen() + * - Queue packet for mesh processing if not seen before + * - Free packet if already seen to prevent duplicates + * + * @param packet The received mesh packet + */ + void handleReceivedPacket(mesh::Packet *packet); +}; diff --git a/src/helpers/bridges/ESPNowBridge.cpp b/src/helpers/bridges/ESPNowBridge.cpp index aed63a6..baf683c 100644 --- a/src/helpers/bridges/ESPNowBridge.cpp +++ b/src/helpers/bridges/ESPNowBridge.cpp @@ -1,6 +1,5 @@ #include "ESPNowBridge.h" -#include #include #include @@ -22,21 +21,8 @@ void ESPNowBridge::send_cb(const uint8_t *mac, esp_now_send_status_t status) { } } -// Fletcher16 checksum calculation -static uint16_t fletcher16(const uint8_t *data, size_t len) { - uint16_t sum1 = 0; - uint16_t sum2 = 0; - - while (len--) { - sum1 = (sum1 + *data++) % 255; - sum2 = (sum2 + sum1) % 255; - } - - return (sum2 << 8) | sum1; -} - ESPNowBridge::ESPNowBridge(mesh::PacketManager *mgr, mesh::RTCClock *rtc) - : _mgr(mgr), _rtc(rtc), _rx_buffer_pos(0) { + : BridgeBase(mgr, rtc), _rx_buffer_pos(0) { _instance = this; } @@ -115,13 +101,12 @@ void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int32_t l // Validate checksum uint16_t received_checksum = (decrypted[0] << 8) | decrypted[1]; const size_t payloadLen = encryptedDataLen - CHECKSUM_SIZE; - uint16_t calculated_checksum = fletcher16(decrypted + CHECKSUM_SIZE, payloadLen); - if (received_checksum != calculated_checksum) { + if (!validateChecksum(decrypted + CHECKSUM_SIZE, payloadLen, received_checksum)) { // Failed to decrypt - likely from a different network #if MESH_PACKET_LOGGING - Serial.printf("%s: ESPNOW BRIDGE: RX checksum mismatch, rcv=0x%04X calc=0x%04X\n", getLogDateTime(), - received_checksum, calculated_checksum); + Serial.printf("%s: ESPNOW BRIDGE: RX checksum mismatch, rcv=0x%04X\n", getLogDateTime(), + received_checksum); #endif return; } @@ -146,23 +131,19 @@ void ESPNowBridge::onDataSent(const uint8_t *mac_addr, esp_now_send_status_t sta } void ESPNowBridge::onPacketReceived(mesh::Packet *packet) { - if (!_seen_packets.hasSeen(packet)) { - _mgr->queueInbound(packet, 0); - } else { - _mgr->free(packet); - } + handleReceivedPacket(packet); } void ESPNowBridge::onPacketTransmitted(mesh::Packet *packet) { - if (!_seen_packets.hasSeen(packet)) { - - // First validate the packet pointer - if (!packet) { + // First validate the packet pointer + if (!packet) { #if MESH_PACKET_LOGGING - Serial.printf("%s: ESPNOW BRIDGE: TX invalid packet pointer\n", getLogDateTime()); + Serial.printf("%s: ESPNOW BRIDGE: TX invalid packet pointer\n", getLogDateTime()); #endif - return; - } + return; + } + + if (!_seen_packets.hasSeen(packet)) { // Create a temporary buffer just for size calculation and reuse for actual writing uint8_t sizingBuffer[MAX_PAYLOAD_SIZE]; @@ -212,13 +193,4 @@ void ESPNowBridge::onPacketTransmitted(mesh::Packet *packet) { } } -const char *ESPNowBridge::getLogDateTime() { - static char tmp[32]; - uint32_t now = _rtc->getCurrentTime(); - DateTime dt = DateTime(now); - sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), - dt.year()); - return tmp; -} - #endif diff --git a/src/helpers/bridges/ESPNowBridge.h b/src/helpers/bridges/ESPNowBridge.h index 5c77147..d9962c7 100644 --- a/src/helpers/bridges/ESPNowBridge.h +++ b/src/helpers/bridges/ESPNowBridge.h @@ -2,8 +2,7 @@ #include "MeshCore.h" #include "esp_now.h" -#include "helpers/AbstractBridge.h" -#include "helpers/SimpleMeshTables.h" +#include "helpers/bridges/BridgeBase.h" #ifdef WITH_ESPNOW_BRIDGE @@ -44,21 +43,12 @@ * WITH_ESPNOW_BRIDGE_SECRET values. Packets encrypted with a different key will * fail the checksum validation and be discarded. */ -class ESPNowBridge : public AbstractBridge { +class ESPNowBridge : public BridgeBase { private: static ESPNowBridge *_instance; static void recv_cb(const uint8_t *mac, const uint8_t *data, int32_t len); static void send_cb(const uint8_t *mac, esp_now_send_status_t status); - /** Packet manager for allocating and queuing mesh packets */ - mesh::PacketManager *_mgr; - - /** RTC clock for timestamping debug messages */ - mesh::RTCClock *_rtc; - - /** Tracks seen packets to prevent loops in broadcast communications */ - SimpleMeshTables _seen_packets; - /** * ESP-NOW Protocol Structure: * - ESP-NOW header: 20 bytes (handled by ESP-NOW protocol) @@ -168,14 +158,6 @@ public: * @param packet The mesh packet to transmit */ void onPacketTransmitted(mesh::Packet *packet) override; - - /** - * Gets formatted date/time string for logging - * Format: "HH:MM:SS - DD/MM/YYYY U" - * - * @return Formatted date/time string - */ - const char *getLogDateTime(); }; #endif diff --git a/src/helpers/bridges/RS232Bridge.cpp b/src/helpers/bridges/RS232Bridge.cpp index 5c3b8ca..39a0968 100644 --- a/src/helpers/bridges/RS232Bridge.cpp +++ b/src/helpers/bridges/RS232Bridge.cpp @@ -1,32 +1,11 @@ #include "RS232Bridge.h" + #include -#include #ifdef WITH_RS232_BRIDGE -// Static Fletcher-16 checksum calculation -// Based on: https://en.wikipedia.org/wiki/Fletcher%27s_checksum -// Used to verify data integrity of received packets -inline static uint16_t fletcher16(const uint8_t *bytes, const size_t len) { - uint8_t sum1 = 0, sum2 = 0; - - for (size_t i = 0; i < len; i++) { - sum1 = (sum1 + bytes[i]) % 255; - sum2 = (sum2 + sum1) % 255; - } - - return (sum2 << 8) | sum1; -}; - -const char* RS232Bridge::getLogDateTime() { - static char tmp[32]; - uint32_t now = _rtc->getCurrentTime(); - DateTime dt = DateTime(now); - sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), dt.year()); - return tmp; -} - -RS232Bridge::RS232Bridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc) : _serial(&serial), _mgr(mgr), _rtc(rtc) {} +RS232Bridge::RS232Bridge(Stream &serial, mesh::PacketManager *mgr, mesh::RTCClock *rtc) + : BridgeBase(mgr, rtc), _serial(&serial) {} void RS232Bridge::begin() { #if !defined(WITH_RS232_BRIDGE_RX) || !defined(WITH_RS232_BRIDGE_TX) @@ -46,27 +25,48 @@ void RS232Bridge::begin() { #else #error RS232Bridge was not tested on the current platform #endif - ((HardwareSerial*)_serial)->begin(115200); + ((HardwareSerial *)_serial)->begin(115200); } -void RS232Bridge::onPacketTransmitted(mesh::Packet* packet) { +void RS232Bridge::onPacketTransmitted(mesh::Packet *packet) { + // First validate the packet pointer + if (!packet) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: RS232 BRIDGE: TX invalid packet pointer\n", getLogDateTime()); +#endif + return; + } + if (!_seen_packets.hasSeen(packet)) { + uint8_t buffer[MAX_SERIAL_PACKET_SIZE]; uint16_t len = packet->writeTo(buffer + 4); - buffer[0] = (SERIAL_PKT_MAGIC >> 8) & 0xFF; - buffer[1] = SERIAL_PKT_MAGIC & 0xFF; - buffer[2] = (len >> 8) & 0xFF; - buffer[3] = len & 0xFF; + // Check if packet fits within our maximum payload size + if (len > (MAX_TRANS_UNIT + 1)) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: RS232 BRIDGE: TX packet too large (payload=%d, max=%d)\n", getLogDateTime(), len, + MAX_TRANS_UNIT + 1); +#endif + return; + } + // Build packet header + buffer[0] = (SERIAL_PKT_MAGIC >> 8) & 0xFF; // Magic high byte + buffer[1] = SERIAL_PKT_MAGIC & 0xFF; // Magic low byte + buffer[2] = (len >> 8) & 0xFF; // Length high byte + buffer[3] = len & 0xFF; // Length low byte + + // Calculate checksum over the payload uint16_t checksum = fletcher16(buffer + 4, len); - buffer[4 + len] = (checksum >> 8) & 0xFF; - buffer[5 + len] = checksum & 0xFF; + buffer[4 + len] = (checksum >> 8) & 0xFF; // Checksum high byte + buffer[5 + len] = checksum & 0xFF; // Checksum low byte + // Send complete packet _serial->write(buffer, len + SERIAL_OVERHEAD); #if MESH_PACKET_LOGGING - Serial.printf("%s: BRIDGE: TX, len=%d crc=0x%04x\n", getLogDateTime(), len, checksum); + Serial.printf("%s: RS232 BRIDGE: TX, len=%d crc=0x%04x\n", getLogDateTime(), len, checksum); #endif } } @@ -81,7 +81,12 @@ void RS232Bridge::loop() { (_rx_buffer_pos == 1 && b == (SERIAL_PKT_MAGIC & 0xFF))) { _rx_buffer[_rx_buffer_pos++] = b; } else { + // Invalid magic byte, reset and start over _rx_buffer_pos = 0; + // Check if this byte could be the start of a new magic word + if (b == ((SERIAL_PKT_MAGIC >> 8) & 0xFF)) { + _rx_buffer[_rx_buffer_pos++] = b; + } } } else { // Reading length, payload, and checksum @@ -89,22 +94,44 @@ void RS232Bridge::loop() { if (_rx_buffer_pos >= 4) { uint16_t len = (_rx_buffer[2] << 8) | _rx_buffer[3]; + + // Validate length field if (len > (MAX_TRANS_UNIT + 1)) { +#if MESH_PACKET_LOGGING + Serial.printf("%s: RS232 BRIDGE: RX invalid length %d, resetting\n", getLogDateTime(), len); +#endif _rx_buffer_pos = 0; // Invalid length, reset - return; + continue; } if (_rx_buffer_pos == len + SERIAL_OVERHEAD) { // Full packet received - uint16_t checksum = (_rx_buffer[4 + len] << 8) | _rx_buffer[5 + len]; - if (checksum == fletcher16(_rx_buffer + 4, len)) { + uint16_t received_checksum = (_rx_buffer[4 + len] << 8) | _rx_buffer[5 + len]; + + if (validateChecksum(_rx_buffer + 4, len, received_checksum)) { #if MESH_PACKET_LOGGING - Serial.printf("%s: BRIDGE: RX, len=%d crc=0x%04x\n", getLogDateTime(), len, checksum); + Serial.printf("%s: RS232 BRIDGE: RX, len=%d crc=0x%04x\n", getLogDateTime(), len, + received_checksum); #endif - mesh::Packet* pkt = _mgr->allocNew(); + mesh::Packet *pkt = _mgr->allocNew(); if (pkt) { - pkt->readFrom(_rx_buffer + 4, len); - onPacketReceived(pkt); + if (pkt->readFrom(_rx_buffer + 4, len)) { + onPacketReceived(pkt); + } else { +#if MESH_PACKET_LOGGING + Serial.printf("%s: RS232 BRIDGE: RX failed to parse packet\n", getLogDateTime()); +#endif + _mgr->free(pkt); + } + } else { +#if MESH_PACKET_LOGGING + Serial.printf("%s: RS232 BRIDGE: RX failed to allocate packet\n", getLogDateTime()); +#endif } + } else { +#if MESH_PACKET_LOGGING + Serial.printf("%s: RS232 BRIDGE: RX checksum mismatch, rcv=0x%04x\n", getLogDateTime(), + received_checksum); +#endif } _rx_buffer_pos = 0; // Reset for next packet } @@ -113,12 +140,8 @@ void RS232Bridge::loop() { } } -void RS232Bridge::onPacketReceived(mesh::Packet* packet) { - if (!_seen_packets.hasSeen(packet)) { - _mgr->queueInbound(packet, 0); - } else { - _mgr->free(packet); - } +void RS232Bridge::onPacketReceived(mesh::Packet *packet) { + handleReceivedPacket(packet); } #endif diff --git a/src/helpers/bridges/RS232Bridge.h b/src/helpers/bridges/RS232Bridge.h index 49c781c..32fad17 100644 --- a/src/helpers/bridges/RS232Bridge.h +++ b/src/helpers/bridges/RS232Bridge.h @@ -1,7 +1,7 @@ #pragma once -#include "helpers/AbstractBridge.h" -#include "helpers/SimpleMeshTables.h" +#include "helpers/bridges/BridgeBase.h" + #include #ifdef WITH_RS232_BRIDGE @@ -15,21 +15,22 @@ * * Features: * - Point-to-point communication over hardware UART - * - Fletcher-16 checksum for data integrity verification - * - Magic header for packet synchronization + * - Fletcher-16 checksum for data integrity verification + * - Magic header for packet synchronization and frame alignment + * - Duplicate packet detection using SimpleMeshTables tracking * - Configurable RX/TX pins via build defines - * - Baud rate fixed at 115200 + * - Fixed baud rate at 115200 for consistent timing * * Packet Structure: - * [2 bytes] Magic Header - Used to identify start of packet - * [2 bytes] Fletcher-16 checksum - Data integrity check - * [1 byte] Payload length - * [n bytes] Packet payload + * [2 bytes] Magic Header (0xC03E) - Used to identify start of RS232Bridge packets + * [2 bytes] Payload Length - Length of the mesh packet payload + * [n bytes] Mesh Packet Payload - The actual mesh packet data + * [2 bytes] Fletcher-16 Checksum - Calculated over the payload for integrity verification * - * The Fletcher-16 checksum is used to validate packet integrity and detect - * corrupted or malformed packets. It provides error detection capabilities - * suitable for serial communication where noise or timing issues could - * corrupt data. + * The Fletcher-16 checksum is calculated over the mesh packet payload and provides + * error detection capabilities suitable for serial communication where electrical + * noise, timing issues, or hardware problems could corrupt data. The checksum + * validation ensures only valid packets are forwarded to the mesh. * * Configuration: * - Define WITH_RS232_BRIDGE to enable this bridge @@ -37,12 +38,13 @@ * - Define WITH_RS232_BRIDGE_TX with the TX pin number * * Platform Support: - * - ESP32 targets - * - NRF52 targets - * - RP2040 targets - * - STM32 targets + * Different platforms require different pin configuration methods: + * - ESP32: Uses HardwareSerial::setPins(rx, tx) + * - NRF52: Uses HardwareSerial::setPins(rx, tx) + * - RP2040: Uses SerialUART::setRX(rx) and SerialUART::setTX(tx) + * - STM32: Uses HardwareSerial::setRx(rx) and HardwareSerial::setTx(tx) */ -class RS232Bridge : public AbstractBridge { +class RS232Bridge : public BridgeBase { public: /** * @brief Constructs an RS232Bridge instance @@ -51,69 +53,98 @@ public: * @param mgr PacketManager for allocating and queuing packets * @param rtc RTCClock for timestamping debug messages */ - RS232Bridge(Stream& serial, mesh::PacketManager* mgr, mesh::RTCClock* rtc); + RS232Bridge(Stream &serial, mesh::PacketManager *mgr, mesh::RTCClock *rtc); /** * Initializes the RS232 bridge - * - * - Configures UART pins based on platform - * - Sets baud rate to 115200 + * + * - Validates that RX/TX pins are defined + * - Configures UART pins based on target platform + * - Sets baud rate to 115200 for consistent communication + * - Platform-specific pin configuration methods are used */ void begin() override; /** - * @brief Main loop handler - * Processes incoming serial data and builds packets + * @brief Main loop handler for processing incoming serial data + * + * Implements a state machine for packet reception: + * 1. Searches for magic header bytes for packet synchronization + * 2. Reads length field to determine expected packet size + * 3. Validates packet length against maximum allowed size + * 4. Receives complete packet payload and checksum + * 5. Validates Fletcher-16 checksum for data integrity + * 6. Creates mesh packet and forwards if valid */ void loop() override; /** * @brief Called when a packet needs to be transmitted over serial - * Formats and sends the packet with proper framing + * + * Formats the mesh packet with RS232 framing protocol: + * - Adds magic header for synchronization + * - Includes payload length field + * - Calculates Fletcher-16 checksum over payload + * - Transmits complete framed packet + * - Uses duplicate detection to prevent retransmission * * @param packet The mesh packet to transmit */ - void onPacketTransmitted(mesh::Packet* packet) override; + void onPacketTransmitted(mesh::Packet *packet) override; /** - * @brief Called when a complete packet has been received from serial - * Queues the packet for mesh processing if checksum is valid - * - * @param packet The received mesh packet + * @brief Called when a complete valid packet has been received from serial + * + * Forwards the received packet to the mesh for processing. + * The packet has already been validated for checksum integrity + * and parsed successfully at this point. + * + * @param packet The received mesh packet ready for processing */ - void onPacketReceived(mesh::Packet* packet) override; + void onPacketReceived(mesh::Packet *packet) override; private: - /** Helper function to get formatted timestamp for logging */ - const char* getLogDateTime(); + /** + * RS232 Protocol Structure: + * - Magic header: 2 bytes (packet identification) + * - Length field: 2 bytes (payload length) + * - Payload: variable bytes (mesh packet data) + * - Checksum: 2 bytes (Fletcher-16 over payload) + * Total overhead: 6 bytes + */ - /** Magic number to identify start of RS232 packets */ + /** Magic number to identify start of RS232Bridge packets */ static constexpr uint16_t SERIAL_PKT_MAGIC = 0xC03E; /** - * @brief The total overhead of the serial protocol in bytes. - * [MAGIC_WORD (2 bytes)] [LENGTH (2 bytes)] [PAYLOAD (variable)] [CHECKSUM (2 bytes)] + * Size constants for packet parsing and construction */ - static constexpr uint16_t SERIAL_OVERHEAD = 6; + static constexpr uint16_t MAGIC_HEADER_SIZE = 2; + static constexpr uint16_t LENGTH_FIELD_SIZE = 2; + static constexpr uint16_t CHECKSUM_SIZE = 2; /** - * @brief The maximum size of a packet on the serial line. + * @brief The total overhead of the serial protocol in bytes. + * Includes: MAGIC_WORD (2) + LENGTH (2) + CHECKSUM (2) = 6 bytes + */ + static constexpr uint16_t SERIAL_OVERHEAD = MAGIC_HEADER_SIZE + LENGTH_FIELD_SIZE + CHECKSUM_SIZE; + + /** + * @brief The maximum size of a complete packet on the serial line. * * This is calculated as the sum of: - * - 1 byte for the packet header (from mesh::Packet) - * - 4 bytes for transport codes (from mesh::Packet) - * - 1 byte for the path length (from mesh::Packet) - * - MAX_PATH_SIZE for the path itself (from MeshCore.h) - * - MAX_PACKET_PAYLOAD for the payload (from MeshCore.h) - * - SERIAL_OVERHEAD for the serial framing + * - MAX_TRANS_UNIT + 1 for the maximum mesh packet size + * - SERIAL_OVERHEAD for the framing (magic + length + checksum) */ static constexpr uint16_t MAX_SERIAL_PACKET_SIZE = (MAX_TRANS_UNIT + 1) + SERIAL_OVERHEAD; - Stream* _serial; - mesh::PacketManager* _mgr; - mesh::RTCClock* _rtc; - SimpleMeshTables _seen_packets; - uint8_t _rx_buffer[MAX_SERIAL_PACKET_SIZE]; // Buffer for serial data + /** Hardware serial port interface */ + Stream *_serial; + + /** Buffer for building received packets */ + uint8_t _rx_buffer[MAX_SERIAL_PACKET_SIZE]; + + /** Current position in the receive buffer */ uint16_t _rx_buffer_pos = 0; }; From a44b8e626a05692001573337fc15e8834cd904be Mon Sep 17 00:00:00 2001 From: recrof Date: Mon, 8 Sep 2025 13:26:19 +0200 Subject: [PATCH 32/50] set the max_contacts and max_group channels in line with other nrf52 targets --- variants/rak_wismesh_tag/platformio.ini | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/variants/rak_wismesh_tag/platformio.ini b/variants/rak_wismesh_tag/platformio.ini index 6f7d28b..572919e 100644 --- a/variants/rak_wismesh_tag/platformio.ini +++ b/variants/rak_wismesh_tag/platformio.ini @@ -69,8 +69,8 @@ extends = rak_wismesh_tag build_flags = ${rak_wismesh_tag.build_flags} -I examples/companion_radio/ui-orig - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 ; NOTE: DO NOT ENABLE --> -D MESH_PACKET_LOGGING=1 ; NOTE: DO NOT ENABLE --> -D MESH_DEBUG=1 build_src_filter = ${rak_wismesh_tag.build_src_filter} @@ -86,8 +86,8 @@ extends = rak_wismesh_tag build_flags = ${rak_wismesh_tag.build_flags} -I examples/companion_radio/ui-orig - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 -D BLE_PIN_CODE=123456 -D BLE_DEBUG_LOGGING=1 -D OFFLINE_QUEUE_SIZE=256 From f2e8fb0259f2100571f49ebdf0ecc6f50333c0be Mon Sep 17 00:00:00 2001 From: Scott Powell Date: Mon, 8 Sep 2025 21:46:19 +1000 Subject: [PATCH 33/50] * refactor: MyMesh class extracted --- examples/simple_repeater/MyMesh.cpp | 684 ++++++++++++++++++++++++ examples/simple_repeater/MyMesh.h | 173 ++++++ examples/simple_repeater/main.cpp | 795 +--------------------------- 3 files changed, 861 insertions(+), 791 deletions(-) create mode 100644 examples/simple_repeater/MyMesh.cpp create mode 100644 examples/simple_repeater/MyMesh.h diff --git a/examples/simple_repeater/MyMesh.cpp b/examples/simple_repeater/MyMesh.cpp new file mode 100644 index 0000000..6e789f9 --- /dev/null +++ b/examples/simple_repeater/MyMesh.cpp @@ -0,0 +1,684 @@ +#include "MyMesh.h" + +/* ------------------------------ Config -------------------------------- */ + +#ifndef LORA_FREQ + #define LORA_FREQ 915.0 +#endif +#ifndef LORA_BW + #define LORA_BW 250 +#endif +#ifndef LORA_SF + #define LORA_SF 10 +#endif +#ifndef LORA_CR + #define LORA_CR 5 +#endif +#ifndef LORA_TX_POWER + #define LORA_TX_POWER 20 +#endif + +#ifndef ADVERT_NAME + #define ADVERT_NAME "repeater" +#endif +#ifndef ADVERT_LAT + #define ADVERT_LAT 0.0 +#endif +#ifndef ADVERT_LON + #define ADVERT_LON 0.0 +#endif + +#ifndef ADMIN_PASSWORD + #define ADMIN_PASSWORD "password" +#endif + +#ifndef SERVER_RESPONSE_DELAY + #define SERVER_RESPONSE_DELAY 300 +#endif + +#ifndef TXT_ACK_DELAY + #define TXT_ACK_DELAY 200 +#endif + +#define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS +#define REQ_TYPE_KEEP_ALIVE 0x02 +#define REQ_TYPE_GET_TELEMETRY_DATA 0x03 + +#define RESP_SERVER_LOGIN_OK 0 // response to ANON_REQ + +#define CLI_REPLY_DELAY_MILLIS 600 + + +ClientInfo *MyMesh::putClient(const mesh::Identity &id) { + uint32_t min_time = 0xFFFFFFFF; + ClientInfo *oldest = &known_clients[0]; + for (int i = 0; i < MAX_CLIENTS; i++) { + if (known_clients[i].last_activity < min_time) { + oldest = &known_clients[i]; + min_time = oldest->last_activity; + } + if (id.matches(known_clients[i].id)) return &known_clients[i]; // already known + } + + oldest->id = id; + oldest->out_path_len = -1; // initially out_path is unknown + oldest->last_timestamp = 0; + return oldest; +} + +void MyMesh::putNeighbour(const mesh::Identity &id, uint32_t timestamp, float snr) { +#if MAX_NEIGHBOURS // check if neighbours enabled + // find existing neighbour, else use least recently updated + uint32_t oldest_timestamp = 0xFFFFFFFF; + NeighbourInfo *neighbour = &neighbours[0]; + for (int i = 0; i < MAX_NEIGHBOURS; i++) { + // if neighbour already known, we should update it + if (id.matches(neighbours[i].id)) { + neighbour = &neighbours[i]; + break; + } + + // otherwise we should update the least recently updated neighbour + if (neighbours[i].heard_timestamp < oldest_timestamp) { + neighbour = &neighbours[i]; + oldest_timestamp = neighbour->heard_timestamp; + } + } + + // update neighbour info + neighbour->id = id; + neighbour->advert_timestamp = timestamp; + neighbour->heard_timestamp = getRTCClock()->getCurrentTime(); + neighbour->snr = (int8_t)(snr * 4); +#endif +} + +int MyMesh::handleRequest(ClientInfo *sender, uint32_t sender_timestamp, uint8_t *payload, + size_t payload_len) { + // uint32_t now = getRTCClock()->getCurrentTimeUnique(); + // memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp + memcpy(reply_data, &sender_timestamp, + 4); // reflect sender_timestamp back in response packet (kind of like a 'tag') + + switch (payload[0]) { + case REQ_TYPE_GET_STATUS: { // guests can also access this now + RepeaterStats stats; + stats.batt_milli_volts = board.getBattMilliVolts(); + stats.curr_tx_queue_len = _mgr->getOutboundCount(0xFFFFFFFF); + stats.noise_floor = (int16_t)_radio->getNoiseFloor(); + stats.last_rssi = (int16_t)radio_driver.getLastRSSI(); + stats.n_packets_recv = radio_driver.getPacketsRecv(); + stats.n_packets_sent = radio_driver.getPacketsSent(); + stats.total_air_time_secs = getTotalAirTime() / 1000; + stats.total_up_time_secs = _ms->getMillis() / 1000; + stats.n_sent_flood = getNumSentFlood(); + stats.n_sent_direct = getNumSentDirect(); + stats.n_recv_flood = getNumRecvFlood(); + stats.n_recv_direct = getNumRecvDirect(); + stats.err_events = _err_flags; + stats.last_snr = (int16_t)(radio_driver.getLastSNR() * 4); + stats.n_direct_dups = ((SimpleMeshTables *)getTables())->getNumDirectDups(); + stats.n_flood_dups = ((SimpleMeshTables *)getTables())->getNumFloodDups(); + stats.total_rx_air_time_secs = getReceiveAirTime() / 1000; + + memcpy(&reply_data[4], &stats, sizeof(stats)); + + return 4 + sizeof(stats); // reply_len + } + case REQ_TYPE_GET_TELEMETRY_DATA: { + uint8_t perm_mask = ~(payload[1]); // NEW: first reserved byte (of 4), is now inverse mask to apply to permissions + + telemetry.reset(); + telemetry.addVoltage(TELEM_CHANNEL_SELF, (float)board.getBattMilliVolts() / 1000.0f); + // query other sensors -- target specific + sensors.querySensors((sender->is_admin ? 0xFF : 0x00) & perm_mask, telemetry); + + uint8_t tlen = telemetry.getSize(); + memcpy(&reply_data[4], telemetry.getBuffer(), tlen); + return 4 + tlen; // reply_len + } + } + return 0; // unknown command +} + +mesh::Packet *MyMesh::createSelfAdvert() { + uint8_t app_data[MAX_ADVERT_DATA_SIZE]; + uint8_t app_data_len; + { + AdvertDataBuilder builder(ADV_TYPE_REPEATER, _prefs.node_name, _prefs.node_lat, _prefs.node_lon); + app_data_len = builder.encodeTo(app_data); + } + + return createAdvert(self_id, app_data, app_data_len); +} + +File MyMesh::openAppend(const char *fname) { +#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) + return _fs->open(fname, FILE_O_WRITE); +#elif defined(RP2040_PLATFORM) + return _fs->open(fname, "a"); +#else + return _fs->open(fname, "a", true); +#endif +} + +bool MyMesh::allowPacketForward(const mesh::Packet *packet) { + if (_prefs.disable_fwd) return false; + if (packet->isRouteFlood() && packet->path_len >= _prefs.flood_max) return false; + return true; +} + +const char *MyMesh::getLogDateTime() { + static char tmp[32]; + uint32_t now = getRTCClock()->getCurrentTime(); + DateTime dt = DateTime(now); + sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), + dt.year()); + return tmp; +} + +void MyMesh::logRxRaw(float snr, float rssi, const uint8_t raw[], int len) { +#if MESH_PACKET_LOGGING + Serial.print(getLogDateTime()); + Serial.print(" RAW: "); + mesh::Utils::printHex(Serial, raw, len); + Serial.println(); +#endif +} + +void MyMesh::logRx(mesh::Packet *pkt, int len, float score) { + if (_logging) { + File f = openAppend(PACKET_LOG_FILE); + if (f) { + f.print(getLogDateTime()); + f.printf(": RX, len=%d (type=%d, route=%s, payload_len=%d) SNR=%d RSSI=%d score=%d", len, + pkt->getPayloadType(), pkt->isRouteDirect() ? "D" : "F", pkt->payload_len, + (int)_radio->getLastSNR(), (int)_radio->getLastRSSI(), (int)(score * 1000)); + + if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH || pkt->getPayloadType() == PAYLOAD_TYPE_REQ || + pkt->getPayloadType() == PAYLOAD_TYPE_RESPONSE || pkt->getPayloadType() == PAYLOAD_TYPE_TXT_MSG) { + f.printf(" [%02X -> %02X]\n", (uint32_t)pkt->payload[1], (uint32_t)pkt->payload[0]); + } else { + f.printf("\n"); + } + f.close(); + } + } +} + +void MyMesh::logTx(mesh::Packet *pkt, int len) { + if (_logging) { + File f = openAppend(PACKET_LOG_FILE); + if (f) { + f.print(getLogDateTime()); + f.printf(": TX, len=%d (type=%d, route=%s, payload_len=%d)", len, pkt->getPayloadType(), + pkt->isRouteDirect() ? "D" : "F", pkt->payload_len); + + if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH || pkt->getPayloadType() == PAYLOAD_TYPE_REQ || + pkt->getPayloadType() == PAYLOAD_TYPE_RESPONSE || pkt->getPayloadType() == PAYLOAD_TYPE_TXT_MSG) { + f.printf(" [%02X -> %02X]\n", (uint32_t)pkt->payload[1], (uint32_t)pkt->payload[0]); + } else { + f.printf("\n"); + } + f.close(); + } + } +} + +void MyMesh::logTxFail(mesh::Packet *pkt, int len) { + if (_logging) { + File f = openAppend(PACKET_LOG_FILE); + if (f) { + f.print(getLogDateTime()); + f.printf(": TX FAIL!, len=%d (type=%d, route=%s, payload_len=%d)\n", len, pkt->getPayloadType(), + pkt->isRouteDirect() ? "D" : "F", pkt->payload_len); + f.close(); + } + } +} + +int MyMesh::calcRxDelay(float score, uint32_t air_time) const { + if (_prefs.rx_delay_base <= 0.0f) return 0; + return (int)((pow(_prefs.rx_delay_base, 0.85f - score) - 1.0) * air_time); +} + +uint32_t MyMesh::getRetransmitDelay(const mesh::Packet *packet) { + uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.tx_delay_factor); + return getRNG()->nextInt(0, 6) * t; +} +uint32_t MyMesh::getDirectRetransmitDelay(const mesh::Packet *packet) { + uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.direct_tx_delay_factor); + return getRNG()->nextInt(0, 6) * t; +} + +void MyMesh::onAnonDataRecv(mesh::Packet *packet, const uint8_t *secret, const mesh::Identity &sender, + uint8_t *data, size_t len) { + if (packet->getPayloadType() == PAYLOAD_TYPE_ANON_REQ) { // received an initial request by a possible admin + // client (unknown at this stage) + uint32_t timestamp; + memcpy(×tamp, data, 4); + + bool is_admin; + data[len] = 0; // ensure null terminator + if (strcmp((char *)&data[4], _prefs.password) == 0) { // check for valid password + is_admin = true; + } else if (strcmp((char *)&data[4], _prefs.guest_password) == 0) { // check guest password + is_admin = false; + } else { +#if MESH_DEBUG + MESH_DEBUG_PRINTLN("Invalid password: %s", &data[4]); +#endif + return; + } + + auto client = putClient(sender); // add to known clients (if not already known) + if (timestamp <= client->last_timestamp) { + MESH_DEBUG_PRINTLN("Possible login replay attack!"); + return; // FATAL: client table is full -OR- replay attack + } + + MESH_DEBUG_PRINTLN("Login success!"); + client->last_timestamp = timestamp; + client->last_activity = getRTCClock()->getCurrentTime(); + client->is_admin = is_admin; + memcpy(client->secret, secret, PUB_KEY_SIZE); + + uint32_t now = getRTCClock()->getCurrentTimeUnique(); + memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp +#if 0 + memcpy(&reply_data[4], "OK", 2); // legacy response +#else + reply_data[4] = RESP_SERVER_LOGIN_OK; + reply_data[5] = 0; // NEW: recommended keep-alive interval (secs / 16) + reply_data[6] = is_admin ? 1 : 0; + reply_data[7] = 0; // FUTURE: reserved + getRNG()->random(&reply_data[8], 4); // random blob to help packet-hash uniqueness +#endif + + if (packet->isRouteFlood()) { + // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response + mesh::Packet *path = createPathReturn(sender, client->secret, packet->path, packet->path_len, + PAYLOAD_TYPE_RESPONSE, reply_data, 12); + if (path) sendFlood(path, SERVER_RESPONSE_DELAY); + } else { + mesh::Packet *reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, client->secret, reply_data, 12); + if (reply) { + if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT + sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); + } else { + sendFlood(reply, SERVER_RESPONSE_DELAY); + } + } + } + } +} + +int MyMesh::searchPeersByHash(const uint8_t *hash) { + int n = 0; + for (int i = 0; i < MAX_CLIENTS; i++) { + if (known_clients[i].id.isHashMatch(hash)) { + matching_peer_indexes[n++] = i; // store the INDEXES of matching contacts (for subsequent 'peer' methods) + } + } + return n; +} + +void MyMesh::getPeerSharedSecret(uint8_t *dest_secret, int peer_idx) { + int i = matching_peer_indexes[peer_idx]; + if (i >= 0 && i < MAX_CLIENTS) { + // lookup pre-calculated shared_secret + memcpy(dest_secret, known_clients[i].secret, PUB_KEY_SIZE); + } else { + MESH_DEBUG_PRINTLN("getPeerSharedSecret: Invalid peer idx: %d", i); + } +} + +void MyMesh::onAdvertRecv(mesh::Packet *packet, const mesh::Identity &id, uint32_t timestamp, + const uint8_t *app_data, size_t app_data_len) { + mesh::Mesh::onAdvertRecv(packet, id, timestamp, app_data, app_data_len); // chain to super impl + + // if this a zero hop advert, add it to neighbours + if (packet->path_len == 0) { + AdvertDataParser parser(app_data, app_data_len); + if (parser.isValid() && parser.getType() == ADV_TYPE_REPEATER) { // just keep neigbouring Repeaters + putNeighbour(id, timestamp, packet->getSNR()); + } + } +} + +void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx, const uint8_t *secret, + uint8_t *data, size_t len) { + int i = matching_peer_indexes[sender_idx]; + if (i < 0 || + i >= MAX_CLIENTS) { // get from our known_clients table (sender SHOULD already be known in this context) + MESH_DEBUG_PRINTLN("onPeerDataRecv: invalid peer idx: %d", i); + return; + } + auto client = &known_clients[i]; + if (type == PAYLOAD_TYPE_REQ) { // request (from a Known admin client!) + uint32_t timestamp; + memcpy(×tamp, data, 4); + + if (timestamp > client->last_timestamp) { // prevent replay attacks + int reply_len = handleRequest(client, timestamp, &data[4], len - 4); + if (reply_len == 0) return; // invalid command + + client->last_timestamp = timestamp; + client->last_activity = getRTCClock()->getCurrentTime(); + + if (packet->isRouteFlood()) { + // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response + mesh::Packet *path = createPathReturn(client->id, secret, packet->path, packet->path_len, + PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); + if (path) sendFlood(path, SERVER_RESPONSE_DELAY); + } else { + mesh::Packet *reply = + createDatagram(PAYLOAD_TYPE_RESPONSE, client->id, secret, reply_data, reply_len); + if (reply) { + if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT + sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); + } else { + sendFlood(reply, SERVER_RESPONSE_DELAY); + } + } + } + } else { + MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); + } + } else if (type == PAYLOAD_TYPE_TXT_MSG && len > 5 && client->is_admin) { // a CLI command + uint32_t sender_timestamp; + memcpy(&sender_timestamp, data, 4); // timestamp (by sender's RTC clock - which could be wrong) + uint flags = (data[4] >> 2); // message attempt number, and other flags + + if (!(flags == TXT_TYPE_PLAIN || flags == TXT_TYPE_CLI_DATA)) { + MESH_DEBUG_PRINTLN("onPeerDataRecv: unsupported text type received: flags=%02x", (uint32_t)flags); + } else if (sender_timestamp >= client->last_timestamp) { // prevent replay attacks + bool is_retry = (sender_timestamp == client->last_timestamp); + client->last_timestamp = sender_timestamp; + client->last_activity = getRTCClock()->getCurrentTime(); + + // len can be > original length, but 'text' will be padded with zeroes + data[len] = 0; // need to make a C string again, with null terminator + + if (flags == TXT_TYPE_PLAIN) { // for legacy CLI, send Acks + uint32_t ack_hash; // calc truncated hash of the message timestamp + text + sender pub_key, to prove + // to sender that we got it + mesh::Utils::sha256((uint8_t *)&ack_hash, 4, data, 5 + strlen((char *)&data[5]), client->id.pub_key, + PUB_KEY_SIZE); + + mesh::Packet *ack = createAck(ack_hash); + if (ack) { + if (client->out_path_len < 0) { + sendFlood(ack, TXT_ACK_DELAY); + } else { + sendDirect(ack, client->out_path, client->out_path_len, TXT_ACK_DELAY); + } + } + } + + uint8_t temp[166]; + char *command = (char *)&data[5]; + char *reply = (char *)&temp[5]; + if (is_retry) { + *reply = 0; + } else { + handleCommand(sender_timestamp, command, reply); + } + int text_len = strlen(reply); + if (text_len > 0) { + uint32_t timestamp = getRTCClock()->getCurrentTimeUnique(); + if (timestamp == sender_timestamp) { + // WORKAROUND: the two timestamps need to be different, in the CLI view + timestamp++; + } + memcpy(temp, ×tamp, 4); // mostly an extra blob to help make packet_hash unique + temp[4] = (TXT_TYPE_CLI_DATA << 2); // NOTE: legacy was: TXT_TYPE_PLAIN + + auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, secret, temp, 5 + text_len); + if (reply) { + if (client->out_path_len < 0) { + sendFlood(reply, CLI_REPLY_DELAY_MILLIS); + } else { + sendDirect(reply, client->out_path, client->out_path_len, CLI_REPLY_DELAY_MILLIS); + } + } + } + } else { + MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); + } + } +} + +bool MyMesh::onPeerPathRecv(mesh::Packet *packet, int sender_idx, const uint8_t *secret, uint8_t *path, + uint8_t path_len, uint8_t extra_type, uint8_t *extra, uint8_t extra_len) { + // TODO: prevent replay attacks + int i = matching_peer_indexes[sender_idx]; + + if (i >= 0 && + i < MAX_CLIENTS) { // get from our known_clients table (sender SHOULD already be known in this context) + MESH_DEBUG_PRINTLN("PATH to client, path_len=%d", (uint32_t)path_len); + auto client = &known_clients[i]; + memcpy(client->out_path, path, client->out_path_len = path_len); // store a copy of path, for sendDirect() + } else { + MESH_DEBUG_PRINTLN("onPeerPathRecv: invalid peer idx: %d", i); + } + + // NOTE: no reciprocal path send!! + return false; +} + +MyMesh::MyMesh(mesh::MainBoard &board, mesh::Radio &radio, mesh::MillisecondClock &ms, mesh::RNG &rng, + mesh::RTCClock &rtc, mesh::MeshTables &tables) + : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), + _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) { + memset(known_clients, 0, sizeof(known_clients)); + next_local_advert = next_flood_advert = 0; + set_radio_at = revert_radio_at = 0; + _logging = false; + +#if MAX_NEIGHBOURS + memset(neighbours, 0, sizeof(neighbours)); +#endif + + // defaults + memset(&_prefs, 0, sizeof(_prefs)); + _prefs.airtime_factor = 1.0; // one half + _prefs.rx_delay_base = 0.0f; // turn off by default, was 10.0; + _prefs.tx_delay_factor = 0.5f; // was 0.25f + StrHelper::strncpy(_prefs.node_name, ADVERT_NAME, sizeof(_prefs.node_name)); + _prefs.node_lat = ADVERT_LAT; + _prefs.node_lon = ADVERT_LON; + StrHelper::strncpy(_prefs.password, ADMIN_PASSWORD, sizeof(_prefs.password)); + _prefs.freq = LORA_FREQ; + _prefs.sf = LORA_SF; + _prefs.bw = LORA_BW; + _prefs.cr = LORA_CR; + _prefs.tx_power_dbm = LORA_TX_POWER; + _prefs.advert_interval = 1; // default to 2 minutes for NEW installs + _prefs.flood_advert_interval = 12; // 12 hours + _prefs.flood_max = 64; + _prefs.interference_threshold = 0; // disabled +} + +void MyMesh::begin(FILESYSTEM *fs) { + mesh::Mesh::begin(); + _fs = fs; + // load persisted prefs + _cli.loadPrefs(_fs); + + radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); + radio_set_tx_power(_prefs.tx_power_dbm); + + updateAdvertTimer(); + updateFloodAdvertTimer(); +} + +void MyMesh::applyTempRadioParams(float freq, float bw, uint8_t sf, uint8_t cr, int timeout_mins) { + set_radio_at = futureMillis(2000); // give CLI reply some time to be sent back, before applying temp radio params + pending_freq = freq; + pending_bw = bw; + pending_sf = sf; + pending_cr = cr; + + revert_radio_at = futureMillis(2000 + timeout_mins * 60 * 1000); // schedule when to revert radio params +} + +bool MyMesh::formatFileSystem() { +#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) + return InternalFS.format(); +#elif defined(RP2040_PLATFORM) + return LittleFS.format(); +#elif defined(ESP32) + return SPIFFS.format(); +#else +#error "need to implement file system erase" + return false; +#endif +} + +void MyMesh::sendSelfAdvertisement(int delay_millis) { + mesh::Packet *pkt = createSelfAdvert(); + if (pkt) { + sendFlood(pkt, delay_millis); + } else { + MESH_DEBUG_PRINTLN("ERROR: unable to create advertisement packet!"); + } +} + +void MyMesh::updateAdvertTimer() { + if (_prefs.advert_interval > 0) { // schedule local advert timer + next_local_advert = futureMillis(((uint32_t)_prefs.advert_interval) * 2 * 60 * 1000); + } else { + next_local_advert = 0; // stop the timer + } +} + +void MyMesh::updateFloodAdvertTimer() { + if (_prefs.flood_advert_interval > 0) { // schedule flood advert timer + next_flood_advert = futureMillis(((uint32_t)_prefs.flood_advert_interval) * 60 * 60 * 1000); + } else { + next_flood_advert = 0; // stop the timer + } +} + +void MyMesh::dumpLogFile() { +#if defined(RP2040_PLATFORM) + File f = _fs->open(PACKET_LOG_FILE, "r"); +#else + File f = _fs->open(PACKET_LOG_FILE); +#endif + if (f) { + while (f.available()) { + int c = f.read(); + if (c < 0) break; + Serial.print((char)c); + } + f.close(); + } +} + +void MyMesh::setTxPower(uint8_t power_dbm) { + radio_set_tx_power(power_dbm); +} + +void MyMesh::formatNeighborsReply(char *reply) { + char *dp = reply; + +#if MAX_NEIGHBOURS + for (int i = 0; i < MAX_NEIGHBOURS && dp - reply < 134; i++) { + NeighbourInfo *neighbour = &neighbours[i]; + if (neighbour->heard_timestamp == 0) continue; // skip empty slots + + // add new line if not first item + if (i > 0) *dp++ = '\n'; + + char hex[10]; + // get 4 bytes of neighbour id as hex + mesh::Utils::toHex(hex, neighbour->id.pub_key, 4); + + // add next neighbour + uint32_t secs_ago = getRTCClock()->getCurrentTime() - neighbour->heard_timestamp; + sprintf(dp, "%s:%d:%d", hex, secs_ago, neighbour->snr); + while (*dp) + dp++; // find end of string + } +#endif + if (dp == reply) { // no neighbours, need empty response + strcpy(dp, "-none-"); + dp += 6; + } + *dp = 0; // null terminator +} + +void MyMesh::removeNeighbor(const uint8_t *pubkey, int key_len) { +#if MAX_NEIGHBOURS + for (int i = 0; i < MAX_NEIGHBOURS; i++) { + NeighbourInfo *neighbour = &neighbours[i]; + if (memcmp(neighbour->id.pub_key, pubkey, key_len) == 0) { + neighbours[i] = NeighbourInfo(); // clear neighbour entry + } + } +#endif +} + +void MyMesh::saveIdentity(const mesh::LocalIdentity &new_id) { + self_id = new_id; +#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) + IdentityStore store(*_fs, ""); +#elif defined(ESP32) + IdentityStore store(*_fs, "/identity"); +#elif defined(RP2040_PLATFORM) + IdentityStore store(*_fs, "/identity"); +#else +#error "need to define saveIdentity()" +#endif + store.save("_main", self_id); +} + +void MyMesh::clearStats() { + radio_driver.resetStats(); + resetStats(); + ((SimpleMeshTables *)getTables())->resetStats(); +} + +void MyMesh::handleCommand(uint32_t sender_timestamp, char *command, char *reply) { + while (*command == ' ') + command++; // skip leading spaces + + if (strlen(command) > 4 && command[2] == '|') { // optional prefix (for companion radio CLI) + memcpy(reply, command, 3); // reflect the prefix back + reply += 3; + command += 3; + } + + _cli.handleCommand(sender_timestamp, command, reply); // common CLI commands +} + +void MyMesh::loop() { + mesh::Mesh::loop(); + + if (next_flood_advert && millisHasNowPassed(next_flood_advert)) { + mesh::Packet *pkt = createSelfAdvert(); + if (pkt) sendFlood(pkt); + + updateFloodAdvertTimer(); // schedule next flood advert + updateAdvertTimer(); // also schedule local advert (so they don't overlap) + } else if (next_local_advert && millisHasNowPassed(next_local_advert)) { + mesh::Packet *pkt = createSelfAdvert(); + if (pkt) sendZeroHop(pkt); + + updateAdvertTimer(); // schedule next local advert + } + + if (set_radio_at && millisHasNowPassed(set_radio_at)) { // apply pending (temporary) radio params + set_radio_at = 0; // clear timer + radio_set_params(pending_freq, pending_bw, pending_sf, pending_cr); + MESH_DEBUG_PRINTLN("Temp radio params"); + } + + if (revert_radio_at && millisHasNowPassed(revert_radio_at)) { // revert radio params to orig + revert_radio_at = 0; // clear timer + radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); + MESH_DEBUG_PRINTLN("Radio params restored"); + } +} diff --git a/examples/simple_repeater/MyMesh.h b/examples/simple_repeater/MyMesh.h new file mode 100644 index 0000000..46039e8 --- /dev/null +++ b/examples/simple_repeater/MyMesh.h @@ -0,0 +1,173 @@ +#pragma once + +#include +#include +#include + +#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) + #include +#elif defined(RP2040_PLATFORM) + #include +#elif defined(ESP32) + #include +#endif + +#include +#include +#include +#include +#include +#include +#include +#include + +struct RepeaterStats { + uint16_t batt_milli_volts; + uint16_t curr_tx_queue_len; + int16_t noise_floor; + int16_t last_rssi; + uint32_t n_packets_recv; + uint32_t n_packets_sent; + uint32_t total_air_time_secs; + uint32_t total_up_time_secs; + uint32_t n_sent_flood, n_sent_direct; + uint32_t n_recv_flood, n_recv_direct; + uint16_t err_events; // was 'n_full_events' + int16_t last_snr; // x 4 + uint16_t n_direct_dups, n_flood_dups; + uint32_t total_rx_air_time_secs; +}; + +struct ClientInfo { + mesh::Identity id; + uint32_t last_timestamp, last_activity; + uint8_t secret[PUB_KEY_SIZE]; + bool is_admin; + int8_t out_path_len; + uint8_t out_path[MAX_PATH_SIZE]; +}; + +#ifndef MAX_CLIENTS + #define MAX_CLIENTS 32 +#endif + +struct NeighbourInfo { + mesh::Identity id; + uint32_t advert_timestamp; + uint32_t heard_timestamp; + int8_t snr; // multiplied by 4, user should divide to get float value +}; + +#ifndef FIRMWARE_BUILD_DATE + #define FIRMWARE_BUILD_DATE "1 Sep 2025" +#endif + +#ifndef FIRMWARE_VERSION + #define FIRMWARE_VERSION "v1.8.1" +#endif + +#define FIRMWARE_ROLE "repeater" + +#define PACKET_LOG_FILE "/packet_log" + +class MyMesh : public mesh::Mesh, public CommonCLICallbacks { + FILESYSTEM* _fs; + unsigned long next_local_advert, next_flood_advert; + bool _logging; + NodePrefs _prefs; + CommonCLI _cli; + uint8_t reply_data[MAX_PACKET_PAYLOAD]; + ClientInfo known_clients[MAX_CLIENTS]; +#if MAX_NEIGHBOURS + NeighbourInfo neighbours[MAX_NEIGHBOURS]; +#endif + CayenneLPP telemetry; + unsigned long set_radio_at, revert_radio_at; + float pending_freq; + float pending_bw; + uint8_t pending_sf; + uint8_t pending_cr; + int matching_peer_indexes[MAX_CLIENTS]; + + ClientInfo* putClient(const mesh::Identity& id); + void putNeighbour(const mesh::Identity& id, uint32_t timestamp, float snr); + int handleRequest(ClientInfo* sender, uint32_t sender_timestamp, uint8_t* payload, size_t payload_len); + mesh::Packet* createSelfAdvert(); + + File openAppend(const char* fname); + +protected: + float getAirtimeBudgetFactor() const override { + return _prefs.airtime_factor; + } + + bool allowPacketForward(const mesh::Packet* packet) override; + const char* getLogDateTime() override; + void logRxRaw(float snr, float rssi, const uint8_t raw[], int len) override; + + void logRx(mesh::Packet* pkt, int len, float score) override; + void logTx(mesh::Packet* pkt, int len) override; + void logTxFail(mesh::Packet* pkt, int len) override; + int calcRxDelay(float score, uint32_t air_time) const override; + + uint32_t getRetransmitDelay(const mesh::Packet* packet) override; + uint32_t getDirectRetransmitDelay(const mesh::Packet* packet) override; + + int getInterferenceThreshold() const override { + return _prefs.interference_threshold; + } + int getAGCResetInterval() const override { + return ((int)_prefs.agc_reset_interval) * 4000; // milliseconds + } + uint8_t getExtraAckTransmitCount() const override { + return _prefs.multi_acks; + } + + void onAnonDataRecv(mesh::Packet* packet, const uint8_t* secret, const mesh::Identity& sender, uint8_t* data, size_t len) override; + int searchPeersByHash(const uint8_t* hash) override; + void getPeerSharedSecret(uint8_t* dest_secret, int peer_idx) override; + void onAdvertRecv(mesh::Packet* packet, const mesh::Identity& id, uint32_t timestamp, const uint8_t* app_data, size_t app_data_len); + void onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_idx, const uint8_t* secret, uint8_t* data, size_t len) override; + bool onPeerPathRecv(mesh::Packet* packet, int sender_idx, const uint8_t* secret, uint8_t* path, uint8_t path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) override; + +public: + MyMesh(mesh::MainBoard& board, mesh::Radio& radio, mesh::MillisecondClock& ms, mesh::RNG& rng, mesh::RTCClock& rtc, mesh::MeshTables& tables); + + void begin(FILESYSTEM* fs); + + const char* getFirmwareVer() override { return FIRMWARE_VERSION; } + const char* getBuildDate() override { return FIRMWARE_BUILD_DATE; } + const char* getRole() override { return FIRMWARE_ROLE; } + const char* getNodeName() { return _prefs.node_name; } + NodePrefs* getNodePrefs() { + return &_prefs; + } + + void savePrefs() override { + _cli.savePrefs(_fs); + } + + void applyTempRadioParams(float freq, float bw, uint8_t sf, uint8_t cr, int timeout_mins) override; + bool formatFileSystem() override; + void sendSelfAdvertisement(int delay_millis) override; + void updateAdvertTimer() override; + void updateFloodAdvertTimer() override; + + void setLoggingOn(bool enable) override { _logging = enable; } + + void eraseLogFile() override { + _fs->remove(PACKET_LOG_FILE); + } + + void dumpLogFile() override; + void setTxPower(uint8_t power_dbm) override; + void formatNeighborsReply(char *reply) override; + void removeNeighbor(const uint8_t* pubkey, int key_len) override; + + mesh::LocalIdentity& getSelfId() override { return self_id; } + + void saveIdentity(const mesh::LocalIdentity& new_id) override; + void clearStats() override; + void handleCommand(uint32_t sender_timestamp, char* command, char* reply); + void loop(); +}; diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 3f0c0eb..64e92aa 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -1,803 +1,13 @@ #include // needed for PlatformIO #include -#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) - #include -#elif defined(RP2040_PLATFORM) - #include -#elif defined(ESP32) - #include -#endif - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* ------------------------------ Config -------------------------------- */ - -#ifndef FIRMWARE_BUILD_DATE - #define FIRMWARE_BUILD_DATE "1 Sep 2025" -#endif - -#ifndef FIRMWARE_VERSION - #define FIRMWARE_VERSION "v1.8.1" -#endif - -#ifndef LORA_FREQ - #define LORA_FREQ 915.0 -#endif -#ifndef LORA_BW - #define LORA_BW 250 -#endif -#ifndef LORA_SF - #define LORA_SF 10 -#endif -#ifndef LORA_CR - #define LORA_CR 5 -#endif -#ifndef LORA_TX_POWER - #define LORA_TX_POWER 20 -#endif - -#ifndef ADVERT_NAME - #define ADVERT_NAME "repeater" -#endif -#ifndef ADVERT_LAT - #define ADVERT_LAT 0.0 -#endif -#ifndef ADVERT_LON - #define ADVERT_LON 0.0 -#endif - -#ifndef ADMIN_PASSWORD - #define ADMIN_PASSWORD "password" -#endif - -#ifndef SERVER_RESPONSE_DELAY - #define SERVER_RESPONSE_DELAY 300 -#endif - -#ifndef TXT_ACK_DELAY - #define TXT_ACK_DELAY 200 -#endif +#include "MyMesh.h" #ifdef DISPLAY_CLASS #include "UITask.h" static UITask ui_task(display); #endif -#define FIRMWARE_ROLE "repeater" - -#define PACKET_LOG_FILE "/packet_log" - -/* ------------------------------ Code -------------------------------- */ - -#define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS -#define REQ_TYPE_KEEP_ALIVE 0x02 -#define REQ_TYPE_GET_TELEMETRY_DATA 0x03 - -#define RESP_SERVER_LOGIN_OK 0 // response to ANON_REQ - -struct RepeaterStats { - uint16_t batt_milli_volts; - uint16_t curr_tx_queue_len; - int16_t noise_floor; - int16_t last_rssi; - uint32_t n_packets_recv; - uint32_t n_packets_sent; - uint32_t total_air_time_secs; - uint32_t total_up_time_secs; - uint32_t n_sent_flood, n_sent_direct; - uint32_t n_recv_flood, n_recv_direct; - uint16_t err_events; // was 'n_full_events' - int16_t last_snr; // x 4 - uint16_t n_direct_dups, n_flood_dups; - uint32_t total_rx_air_time_secs; -}; - -struct ClientInfo { - mesh::Identity id; - uint32_t last_timestamp, last_activity; - uint8_t secret[PUB_KEY_SIZE]; - bool is_admin; - int8_t out_path_len; - uint8_t out_path[MAX_PATH_SIZE]; -}; - -#ifndef MAX_CLIENTS - #define MAX_CLIENTS 32 -#endif - -struct NeighbourInfo { - mesh::Identity id; - uint32_t advert_timestamp; - uint32_t heard_timestamp; - int8_t snr; // multiplied by 4, user should divide to get float value -}; - -#define CLI_REPLY_DELAY_MILLIS 600 - -class MyMesh : public mesh::Mesh, public CommonCLICallbacks { - FILESYSTEM* _fs; - unsigned long next_local_advert, next_flood_advert; - bool _logging; - NodePrefs _prefs; - CommonCLI _cli; - uint8_t reply_data[MAX_PACKET_PAYLOAD]; - ClientInfo known_clients[MAX_CLIENTS]; -#if MAX_NEIGHBOURS - NeighbourInfo neighbours[MAX_NEIGHBOURS]; -#endif - CayenneLPP telemetry; - unsigned long set_radio_at, revert_radio_at; - float pending_freq; - float pending_bw; - uint8_t pending_sf; - uint8_t pending_cr; - - ClientInfo* putClient(const mesh::Identity& id) { - uint32_t min_time = 0xFFFFFFFF; - ClientInfo* oldest = &known_clients[0]; - for (int i = 0; i < MAX_CLIENTS; i++) { - if (known_clients[i].last_activity < min_time) { - oldest = &known_clients[i]; - min_time = oldest->last_activity; - } - if (id.matches(known_clients[i].id)) return &known_clients[i]; // already known - } - - oldest->id = id; - oldest->out_path_len = -1; // initially out_path is unknown - oldest->last_timestamp = 0; - return oldest; - } - - void putNeighbour(const mesh::Identity& id, uint32_t timestamp, float snr) { - #if MAX_NEIGHBOURS // check if neighbours enabled - // find existing neighbour, else use least recently updated - uint32_t oldest_timestamp = 0xFFFFFFFF; - NeighbourInfo* neighbour = &neighbours[0]; - for (int i = 0; i < MAX_NEIGHBOURS; i++) { - // if neighbour already known, we should update it - if (id.matches(neighbours[i].id)) { - neighbour = &neighbours[i]; - break; - } - - // otherwise we should update the least recently updated neighbour - if (neighbours[i].heard_timestamp < oldest_timestamp) { - neighbour = &neighbours[i]; - oldest_timestamp = neighbour->heard_timestamp; - } - } - - // update neighbour info - neighbour->id = id; - neighbour->advert_timestamp = timestamp; - neighbour->heard_timestamp = getRTCClock()->getCurrentTime(); - neighbour->snr = (int8_t) (snr * 4); - #endif - } - - int handleRequest(ClientInfo* sender, uint32_t sender_timestamp, uint8_t* payload, size_t payload_len) { - // uint32_t now = getRTCClock()->getCurrentTimeUnique(); - // memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp - memcpy(reply_data, &sender_timestamp, 4); // reflect sender_timestamp back in response packet (kind of like a 'tag') - - switch (payload[0]) { - case REQ_TYPE_GET_STATUS: { // guests can also access this now - RepeaterStats stats; - stats.batt_milli_volts = board.getBattMilliVolts(); - stats.curr_tx_queue_len = _mgr->getOutboundCount(0xFFFFFFFF); - stats.noise_floor = (int16_t)_radio->getNoiseFloor(); - stats.last_rssi = (int16_t) radio_driver.getLastRSSI(); - stats.n_packets_recv = radio_driver.getPacketsRecv(); - stats.n_packets_sent = radio_driver.getPacketsSent(); - stats.total_air_time_secs = getTotalAirTime() / 1000; - stats.total_up_time_secs = _ms->getMillis() / 1000; - stats.n_sent_flood = getNumSentFlood(); - stats.n_sent_direct = getNumSentDirect(); - stats.n_recv_flood = getNumRecvFlood(); - stats.n_recv_direct = getNumRecvDirect(); - stats.err_events = _err_flags; - stats.last_snr = (int16_t)(radio_driver.getLastSNR() * 4); - stats.n_direct_dups = ((SimpleMeshTables *)getTables())->getNumDirectDups(); - stats.n_flood_dups = ((SimpleMeshTables *)getTables())->getNumFloodDups(); - stats.total_rx_air_time_secs = getReceiveAirTime() / 1000; - - memcpy(&reply_data[4], &stats, sizeof(stats)); - - return 4 + sizeof(stats); // reply_len - } - case REQ_TYPE_GET_TELEMETRY_DATA: { - uint8_t perm_mask = ~(payload[1]); // NEW: first reserved byte (of 4), is now inverse mask to apply to permissions - - telemetry.reset(); - telemetry.addVoltage(TELEM_CHANNEL_SELF, (float)board.getBattMilliVolts() / 1000.0f); - // query other sensors -- target specific - sensors.querySensors((sender->is_admin ? 0xFF : 0x00) & perm_mask, telemetry); - - uint8_t tlen = telemetry.getSize(); - memcpy(&reply_data[4], telemetry.getBuffer(), tlen); - return 4 + tlen; // reply_len - } - } - return 0; // unknown command - } - - mesh::Packet* createSelfAdvert() { - uint8_t app_data[MAX_ADVERT_DATA_SIZE]; - uint8_t app_data_len; - { - AdvertDataBuilder builder(ADV_TYPE_REPEATER, _prefs.node_name, _prefs.node_lat, _prefs.node_lon); - app_data_len = builder.encodeTo(app_data); - } - - return createAdvert(self_id, app_data, app_data_len); - } - - File openAppend(const char* fname) { - #if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) - return _fs->open(fname, FILE_O_WRITE); - #elif defined(RP2040_PLATFORM) - return _fs->open(fname, "a"); - #else - return _fs->open(fname, "a", true); - #endif - } - -protected: - float getAirtimeBudgetFactor() const override { - return _prefs.airtime_factor; - } - - bool allowPacketForward(const mesh::Packet* packet) override { - if (_prefs.disable_fwd) return false; - if (packet->isRouteFlood() && packet->path_len >= _prefs.flood_max) return false; - return true; - } - - const char* getLogDateTime() override { - static char tmp[32]; - uint32_t now = getRTCClock()->getCurrentTime(); - DateTime dt = DateTime(now); - sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), dt.year()); - return tmp; - } - - void logRxRaw(float snr, float rssi, const uint8_t raw[], int len) override { - #if MESH_PACKET_LOGGING - Serial.print(getLogDateTime()); - Serial.print(" RAW: "); - mesh::Utils::printHex(Serial, raw, len); - Serial.println(); - #endif - } - - void logRx(mesh::Packet* pkt, int len, float score) override { - if (_logging) { - File f = openAppend(PACKET_LOG_FILE); - if (f) { - f.print(getLogDateTime()); - f.printf(": RX, len=%d (type=%d, route=%s, payload_len=%d) SNR=%d RSSI=%d score=%d", - len, pkt->getPayloadType(), pkt->isRouteDirect() ? "D" : "F", pkt->payload_len, - (int)_radio->getLastSNR(), (int)_radio->getLastRSSI(), (int)(score*1000)); - - if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH || pkt->getPayloadType() == PAYLOAD_TYPE_REQ - || pkt->getPayloadType() == PAYLOAD_TYPE_RESPONSE || pkt->getPayloadType() == PAYLOAD_TYPE_TXT_MSG) { - f.printf(" [%02X -> %02X]\n", (uint32_t)pkt->payload[1], (uint32_t)pkt->payload[0]); - } else { - f.printf("\n"); - } - f.close(); - } - } - } - void logTx(mesh::Packet* pkt, int len) override { - if (_logging) { - File f = openAppend(PACKET_LOG_FILE); - if (f) { - f.print(getLogDateTime()); - f.printf(": TX, len=%d (type=%d, route=%s, payload_len=%d)", - len, pkt->getPayloadType(), pkt->isRouteDirect() ? "D" : "F", pkt->payload_len); - - if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH || pkt->getPayloadType() == PAYLOAD_TYPE_REQ - || pkt->getPayloadType() == PAYLOAD_TYPE_RESPONSE || pkt->getPayloadType() == PAYLOAD_TYPE_TXT_MSG) { - f.printf(" [%02X -> %02X]\n", (uint32_t)pkt->payload[1], (uint32_t)pkt->payload[0]); - } else { - f.printf("\n"); - } - f.close(); - } - } - } - void logTxFail(mesh::Packet* pkt, int len) override { - if (_logging) { - File f = openAppend(PACKET_LOG_FILE); - if (f) { - f.print(getLogDateTime()); - f.printf(": TX FAIL!, len=%d (type=%d, route=%s, payload_len=%d)\n", - len, pkt->getPayloadType(), pkt->isRouteDirect() ? "D" : "F", pkt->payload_len); - f.close(); - } - } - } - - int calcRxDelay(float score, uint32_t air_time) const override { - if (_prefs.rx_delay_base <= 0.0f) return 0; - return (int) ((pow(_prefs.rx_delay_base, 0.85f - score) - 1.0) * air_time); - } - - uint32_t getRetransmitDelay(const mesh::Packet* packet) override { - uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.tx_delay_factor); - return getRNG()->nextInt(0, 6)*t; - } - uint32_t getDirectRetransmitDelay(const mesh::Packet* packet) override { - uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.direct_tx_delay_factor); - return getRNG()->nextInt(0, 6)*t; - } - int getInterferenceThreshold() const override { - return _prefs.interference_threshold; - } - int getAGCResetInterval() const override { - return ((int)_prefs.agc_reset_interval) * 4000; // milliseconds - } - uint8_t getExtraAckTransmitCount() const override { - return _prefs.multi_acks; - } - - void onAnonDataRecv(mesh::Packet* packet, const uint8_t* secret, const mesh::Identity& sender, uint8_t* data, size_t len) override { - if (packet->getPayloadType() == PAYLOAD_TYPE_ANON_REQ) { // received an initial request by a possible admin client (unknown at this stage) - uint32_t timestamp; - memcpy(×tamp, data, 4); - - bool is_admin; - data[len] = 0; // ensure null terminator - if (strcmp((char *) &data[4], _prefs.password) == 0) { // check for valid password - is_admin = true; - } else if (strcmp((char *) &data[4], _prefs.guest_password) == 0) { // check guest password - is_admin = false; - } else { - #if MESH_DEBUG - MESH_DEBUG_PRINTLN("Invalid password: %s", &data[4]); - #endif - return; - } - - auto client = putClient(sender); // add to known clients (if not already known) - if (timestamp <= client->last_timestamp) { - MESH_DEBUG_PRINTLN("Possible login replay attack!"); - return; // FATAL: client table is full -OR- replay attack - } - - MESH_DEBUG_PRINTLN("Login success!"); - client->last_timestamp = timestamp; - client->last_activity = getRTCClock()->getCurrentTime(); - client->is_admin = is_admin; - memcpy(client->secret, secret, PUB_KEY_SIZE); - - uint32_t now = getRTCClock()->getCurrentTimeUnique(); - memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp - #if 0 - memcpy(&reply_data[4], "OK", 2); // legacy response - #else - reply_data[4] = RESP_SERVER_LOGIN_OK; - reply_data[5] = 0; // NEW: recommended keep-alive interval (secs / 16) - reply_data[6] = is_admin ? 1 : 0; - reply_data[7] = 0; // FUTURE: reserved - getRNG()->random(&reply_data[8], 4); // random blob to help packet-hash uniqueness - #endif - - if (packet->isRouteFlood()) { - // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response - mesh::Packet* path = createPathReturn(sender, client->secret, packet->path, packet->path_len, - PAYLOAD_TYPE_RESPONSE, reply_data, 12); - if (path) sendFlood(path, SERVER_RESPONSE_DELAY); - } else { - mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, client->secret, reply_data, 12); - if (reply) { - if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT - sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); - } else { - sendFlood(reply, SERVER_RESPONSE_DELAY); - } - } - } - } - } - - int matching_peer_indexes[MAX_CLIENTS]; - - int searchPeersByHash(const uint8_t* hash) override { - int n = 0; - for (int i = 0; i < MAX_CLIENTS; i++) { - if (known_clients[i].id.isHashMatch(hash)) { - matching_peer_indexes[n++] = i; // store the INDEXES of matching contacts (for subsequent 'peer' methods) - } - } - return n; - } - - void getPeerSharedSecret(uint8_t* dest_secret, int peer_idx) override { - int i = matching_peer_indexes[peer_idx]; - if (i >= 0 && i < MAX_CLIENTS) { - // lookup pre-calculated shared_secret - memcpy(dest_secret, known_clients[i].secret, PUB_KEY_SIZE); - } else { - MESH_DEBUG_PRINTLN("getPeerSharedSecret: Invalid peer idx: %d", i); - } - } - - void onAdvertRecv(mesh::Packet* packet, const mesh::Identity& id, uint32_t timestamp, const uint8_t* app_data, size_t app_data_len) { - mesh::Mesh::onAdvertRecv(packet, id, timestamp, app_data, app_data_len); // chain to super impl - - // if this a zero hop advert, add it to neighbours - if (packet->path_len == 0) { - AdvertDataParser parser(app_data, app_data_len); - if (parser.isValid() && parser.getType() == ADV_TYPE_REPEATER) { // just keep neigbouring Repeaters - putNeighbour(id, timestamp, packet->getSNR()); - } - } - } - - void onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_idx, const uint8_t* secret, uint8_t* data, size_t len) override { - int i = matching_peer_indexes[sender_idx]; - if (i < 0 || i >= MAX_CLIENTS) { // get from our known_clients table (sender SHOULD already be known in this context) - MESH_DEBUG_PRINTLN("onPeerDataRecv: invalid peer idx: %d", i); - return; - } - auto client = &known_clients[i]; - if (type == PAYLOAD_TYPE_REQ) { // request (from a Known admin client!) - uint32_t timestamp; - memcpy(×tamp, data, 4); - - if (timestamp > client->last_timestamp) { // prevent replay attacks - int reply_len = handleRequest(client, timestamp, &data[4], len - 4); - if (reply_len == 0) return; // invalid command - - client->last_timestamp = timestamp; - client->last_activity = getRTCClock()->getCurrentTime(); - - if (packet->isRouteFlood()) { - // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response - mesh::Packet* path = createPathReturn(client->id, secret, packet->path, packet->path_len, - PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); - if (path) sendFlood(path, SERVER_RESPONSE_DELAY); - } else { - mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, client->id, secret, reply_data, reply_len); - if (reply) { - if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT - sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); - } else { - sendFlood(reply, SERVER_RESPONSE_DELAY); - } - } - } - } else { - MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); - } - } else if (type == PAYLOAD_TYPE_TXT_MSG && len > 5 && client->is_admin) { // a CLI command - uint32_t sender_timestamp; - memcpy(&sender_timestamp, data, 4); // timestamp (by sender's RTC clock - which could be wrong) - uint flags = (data[4] >> 2); // message attempt number, and other flags - - if (!(flags == TXT_TYPE_PLAIN || flags == TXT_TYPE_CLI_DATA)) { - MESH_DEBUG_PRINTLN("onPeerDataRecv: unsupported text type received: flags=%02x", (uint32_t)flags); - } else if (sender_timestamp >= client->last_timestamp) { // prevent replay attacks - bool is_retry = (sender_timestamp == client->last_timestamp); - client->last_timestamp = sender_timestamp; - client->last_activity = getRTCClock()->getCurrentTime(); - - // len can be > original length, but 'text' will be padded with zeroes - data[len] = 0; // need to make a C string again, with null terminator - - if (flags == TXT_TYPE_PLAIN) { // for legacy CLI, send Acks - uint32_t ack_hash; // calc truncated hash of the message timestamp + text + sender pub_key, to prove to sender that we got it - mesh::Utils::sha256((uint8_t *) &ack_hash, 4, data, 5 + strlen((char *)&data[5]), client->id.pub_key, PUB_KEY_SIZE); - - mesh::Packet* ack = createAck(ack_hash); - if (ack) { - if (client->out_path_len < 0) { - sendFlood(ack, TXT_ACK_DELAY); - } else { - sendDirect(ack, client->out_path, client->out_path_len, TXT_ACK_DELAY); - } - } - } - - uint8_t temp[166]; - char *command = (char *) &data[5]; - char *reply = (char *) &temp[5]; - if (is_retry) { - *reply = 0; - } else { - handleCommand(sender_timestamp, command, reply); - } - int text_len = strlen(reply); - if (text_len > 0) { - uint32_t timestamp = getRTCClock()->getCurrentTimeUnique(); - if (timestamp == sender_timestamp) { - // WORKAROUND: the two timestamps need to be different, in the CLI view - timestamp++; - } - memcpy(temp, ×tamp, 4); // mostly an extra blob to help make packet_hash unique - temp[4] = (TXT_TYPE_CLI_DATA << 2); // NOTE: legacy was: TXT_TYPE_PLAIN - - auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, secret, temp, 5 + text_len); - if (reply) { - if (client->out_path_len < 0) { - sendFlood(reply, CLI_REPLY_DELAY_MILLIS); - } else { - sendDirect(reply, client->out_path, client->out_path_len, CLI_REPLY_DELAY_MILLIS); - } - } - } - } else { - MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); - } - } - } - - bool onPeerPathRecv(mesh::Packet* packet, int sender_idx, const uint8_t* secret, uint8_t* path, uint8_t path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) override { - // TODO: prevent replay attacks - int i = matching_peer_indexes[sender_idx]; - - if (i >= 0 && i < MAX_CLIENTS) { // get from our known_clients table (sender SHOULD already be known in this context) - MESH_DEBUG_PRINTLN("PATH to client, path_len=%d", (uint32_t) path_len); - auto client = &known_clients[i]; - memcpy(client->out_path, path, client->out_path_len = path_len); // store a copy of path, for sendDirect() - } else { - MESH_DEBUG_PRINTLN("onPeerPathRecv: invalid peer idx: %d", i); - } - - // NOTE: no reciprocal path send!! - return false; - } - -public: - MyMesh(mesh::MainBoard& board, mesh::Radio& radio, mesh::MillisecondClock& ms, mesh::RNG& rng, mesh::RTCClock& rtc, mesh::MeshTables& tables) - : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), - _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) - { - memset(known_clients, 0, sizeof(known_clients)); - next_local_advert = next_flood_advert = 0; - set_radio_at = revert_radio_at = 0; - _logging = false; - - #if MAX_NEIGHBOURS - memset(neighbours, 0, sizeof(neighbours)); - #endif - - // defaults - memset(&_prefs, 0, sizeof(_prefs)); - _prefs.airtime_factor = 1.0; // one half - _prefs.rx_delay_base = 0.0f; // turn off by default, was 10.0; - _prefs.tx_delay_factor = 0.5f; // was 0.25f - StrHelper::strncpy(_prefs.node_name, ADVERT_NAME, sizeof(_prefs.node_name)); - _prefs.node_lat = ADVERT_LAT; - _prefs.node_lon = ADVERT_LON; - StrHelper::strncpy(_prefs.password, ADMIN_PASSWORD, sizeof(_prefs.password)); - _prefs.freq = LORA_FREQ; - _prefs.sf = LORA_SF; - _prefs.bw = LORA_BW; - _prefs.cr = LORA_CR; - _prefs.tx_power_dbm = LORA_TX_POWER; - _prefs.advert_interval = 1; // default to 2 minutes for NEW installs - _prefs.flood_advert_interval = 12; // 12 hours - _prefs.flood_max = 64; - _prefs.interference_threshold = 0; // disabled - } - - void begin(FILESYSTEM* fs) { - mesh::Mesh::begin(); - _fs = fs; - // load persisted prefs - _cli.loadPrefs(_fs); - - radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); - radio_set_tx_power(_prefs.tx_power_dbm); - - updateAdvertTimer(); - updateFloodAdvertTimer(); - } - - const char* getFirmwareVer() override { return FIRMWARE_VERSION; } - const char* getBuildDate() override { return FIRMWARE_BUILD_DATE; } - const char* getRole() override { return FIRMWARE_ROLE; } - const char* getNodeName() { return _prefs.node_name; } - NodePrefs* getNodePrefs() { - return &_prefs; - } - - void savePrefs() override { - _cli.savePrefs(_fs); - } - - void applyTempRadioParams(float freq, float bw, uint8_t sf, uint8_t cr, int timeout_mins) override { - set_radio_at = futureMillis(2000); // give CLI reply some time to be sent back, before applying temp radio params - pending_freq = freq; - pending_bw = bw; - pending_sf = sf; - pending_cr = cr; - - revert_radio_at = futureMillis(2000 + timeout_mins*60*1000); // schedule when to revert radio params - } - - bool formatFileSystem() override { -#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) - return InternalFS.format(); -#elif defined(RP2040_PLATFORM) - return LittleFS.format(); -#elif defined(ESP32) - return SPIFFS.format(); -#else - #error "need to implement file system erase" - return false; -#endif - } - - void sendSelfAdvertisement(int delay_millis) override { - mesh::Packet* pkt = createSelfAdvert(); - if (pkt) { - sendFlood(pkt, delay_millis); - } else { - MESH_DEBUG_PRINTLN("ERROR: unable to create advertisement packet!"); - } - } - - void updateAdvertTimer() override { - if (_prefs.advert_interval > 0) { // schedule local advert timer - next_local_advert = futureMillis( ((uint32_t)_prefs.advert_interval) * 2 * 60 * 1000); - } else { - next_local_advert = 0; // stop the timer - } - } - void updateFloodAdvertTimer() override { - if (_prefs.flood_advert_interval > 0) { // schedule flood advert timer - next_flood_advert = futureMillis( ((uint32_t)_prefs.flood_advert_interval) * 60 * 60 * 1000); - } else { - next_flood_advert = 0; // stop the timer - } - } - - void setLoggingOn(bool enable) override { _logging = enable; } - - void eraseLogFile() override { - _fs->remove(PACKET_LOG_FILE); - } - - void dumpLogFile() override { -#if defined(RP2040_PLATFORM) - File f = _fs->open(PACKET_LOG_FILE, "r"); -#else - File f = _fs->open(PACKET_LOG_FILE); -#endif - if (f) { - while (f.available()) { - int c = f.read(); - if (c < 0) break; - Serial.print((char)c); - } - f.close(); - } - } - - void setTxPower(uint8_t power_dbm) override { - radio_set_tx_power(power_dbm); - } - - void formatNeighborsReply(char *reply) override { - char *dp = reply; - -#if MAX_NEIGHBOURS - for (int i = 0; i < MAX_NEIGHBOURS && dp - reply < 134; i++) { - NeighbourInfo* neighbour = &neighbours[i]; - if (neighbour->heard_timestamp == 0) continue; // skip empty slots - - // add new line if not first item - if (i > 0) *dp++ = '\n'; - - char hex[10]; - // get 4 bytes of neighbour id as hex - mesh::Utils::toHex(hex, neighbour->id.pub_key, 4); - - // add next neighbour - uint32_t secs_ago = getRTCClock()->getCurrentTime() - neighbour->heard_timestamp; - sprintf(dp, "%s:%d:%d", hex, secs_ago, neighbour->snr); - while (*dp) dp++; // find end of string - } -#endif - if (dp == reply) { // no neighbours, need empty response - strcpy(dp, "-none-"); dp += 6; - } - *dp = 0; // null terminator - } - - void removeNeighbor(const uint8_t* pubkey, int key_len) override { -#if MAX_NEIGHBOURS - for (int i = 0; i < MAX_NEIGHBOURS; i++) { - NeighbourInfo* neighbour = &neighbours[i]; - if(memcmp(neighbour->id.pub_key, pubkey, key_len) == 0){ - neighbours[i] = NeighbourInfo(); // clear neighbour entry - } - } -#endif - } - - mesh::LocalIdentity& getSelfId() override { return self_id; } - - void saveIdentity(const mesh::LocalIdentity& new_id) override { - self_id = new_id; -#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) - IdentityStore store(*_fs, ""); -#elif defined(ESP32) - IdentityStore store(*_fs, "/identity"); -#elif defined(RP2040_PLATFORM) - IdentityStore store(*_fs, "/identity"); -#else - #error "need to define saveIdentity()" -#endif - store.save("_main", self_id); - } - - void clearStats() override { - radio_driver.resetStats(); - resetStats(); - ((SimpleMeshTables *)getTables())->resetStats(); - } - - void handleCommand(uint32_t sender_timestamp, char* command, char* reply) { - while (*command == ' ') command++; // skip leading spaces - - if (strlen(command) > 4 && command[2] == '|') { // optional prefix (for companion radio CLI) - memcpy(reply, command, 3); // reflect the prefix back - reply += 3; - command += 3; - } - - _cli.handleCommand(sender_timestamp, command, reply); // common CLI commands - } - - void loop() { - mesh::Mesh::loop(); - - if (next_flood_advert && millisHasNowPassed(next_flood_advert)) { - mesh::Packet* pkt = createSelfAdvert(); - if (pkt) sendFlood(pkt); - - updateFloodAdvertTimer(); // schedule next flood advert - updateAdvertTimer(); // also schedule local advert (so they don't overlap) - } else if (next_local_advert && millisHasNowPassed(next_local_advert)) { - mesh::Packet* pkt = createSelfAdvert(); - if (pkt) sendZeroHop(pkt); - - updateAdvertTimer(); // schedule next local advert - } - - if (set_radio_at && millisHasNowPassed(set_radio_at)) { // apply pending (temporary) radio params - set_radio_at = 0; // clear timer - radio_set_params(pending_freq, pending_bw, pending_sf, pending_cr); - MESH_DEBUG_PRINTLN("Temp radio params"); - } - - if (revert_radio_at && millisHasNowPassed(revert_radio_at)) { // revert radio params to orig - revert_radio_at = 0; // clear timer - radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); - MESH_DEBUG_PRINTLN("Radio params restored"); - } - - #ifdef DISPLAY_CLASS - ui_task.loop(); - #endif - } -}; - StdRNG fast_rng; SimpleMeshTables tables; @@ -899,4 +109,7 @@ void loop() { the_mesh.loop(); sensors.loop(); +#ifdef DISPLAY_CLASS + ui_task.loop(); +#endif } From a0e7b47e29ebfc78820f98ac0d87050311b70a60 Mon Sep 17 00:00:00 2001 From: taco Date: Mon, 8 Sep 2025 22:06:15 +1000 Subject: [PATCH 34/50] correct max contacts and channels for some nrf devices --- variants/heltec_t114/platformio.ini | 8 ++++---- variants/lilygo_techo/platformio.ini | 4 ++-- variants/mesh_pocket/platformio.ini | 8 ++++---- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/variants/heltec_t114/platformio.ini b/variants/heltec_t114/platformio.ini index 696b39d..dec3282 100644 --- a/variants/heltec_t114/platformio.ini +++ b/variants/heltec_t114/platformio.ini @@ -161,8 +161,8 @@ extends = Heltec_t114_with_display build_flags = ${Heltec_t114_with_display.build_flags} -I examples/companion_radio/ui-new - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 -D BLE_PIN_CODE=123456 ; -D BLE_DEBUG_LOGGING=1 -D OFFLINE_QUEUE_SIZE=256 @@ -181,8 +181,8 @@ extends = Heltec_t114_with_display build_flags = ${Heltec_t114_with_display.build_flags} -I examples/companion_radio/ui-new - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 ; -D BLE_PIN_CODE=123456 ; -D BLE_DEBUG_LOGGING=1 ; -D MESH_PACKET_LOGGING=1 diff --git a/variants/lilygo_techo/platformio.ini b/variants/lilygo_techo/platformio.ini index 9122320..7d64fad 100644 --- a/variants/lilygo_techo/platformio.ini +++ b/variants/lilygo_techo/platformio.ini @@ -105,8 +105,8 @@ build_flags = ${LilyGo_T-Echo.build_flags} -I src/helpers/ui -I examples/companion_radio/ui-new - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 -D OFFLINE_QUEUE_SIZE=256 -D UI_RECENT_LIST_SIZE=9 -D AUTO_SHUTDOWN_MILLIVOLTS=3300 diff --git a/variants/mesh_pocket/platformio.ini b/variants/mesh_pocket/platformio.ini index 3fa4c7b..7c99615 100644 --- a/variants/mesh_pocket/platformio.ini +++ b/variants/mesh_pocket/platformio.ini @@ -70,8 +70,8 @@ extends = Mesh_pocket build_flags = ${Mesh_pocket.build_flags} -I examples/companion_radio/ui-new - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 -D BLE_PIN_CODE=123456 -D OFFLINE_QUEUE_SIZE=256 -D AUTO_OFF_MILLIS=0 @@ -92,8 +92,8 @@ extends = Mesh_pocket build_flags = ${Mesh_pocket.build_flags} -I examples/companion_radio/ui-new - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 -D AUTO_OFF_MILLIS=0 ; -D BLE_PIN_CODE=123456 ; -D BLE_DEBUG_LOGGING=1 From 1d25c87c57ddca51eb0abbad272b5d45951c64e5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Mon, 8 Sep 2025 11:15:28 +0100 Subject: [PATCH 35/50] Refactor bridge packet handling to use common magic number and size constants --- src/helpers/bridges/BridgeBase.h | 20 +++++++++++++++++++ src/helpers/bridges/ESPNowBridge.cpp | 24 +++++++++++------------ src/helpers/bridges/ESPNowBridge.h | 9 +-------- src/helpers/bridges/RS232Bridge.cpp | 10 +++++----- src/helpers/bridges/RS232Bridge.h | 12 +----------- variants/lilygo_tlora_v2_1/platformio.ini | 2 +- 6 files changed, 40 insertions(+), 37 deletions(-) diff --git a/src/helpers/bridges/BridgeBase.h b/src/helpers/bridges/BridgeBase.h index 2aff230..c1764ae 100644 --- a/src/helpers/bridges/BridgeBase.h +++ b/src/helpers/bridges/BridgeBase.h @@ -21,6 +21,26 @@ class BridgeBase : public AbstractBridge { public: virtual ~BridgeBase() = default; + /** + * @brief Common magic number used by all bridge implementations for packet identification + * + * This magic number is placed at the beginning of bridge packets to identify + * them as mesh bridge packets and provide frame synchronization. + */ + static constexpr uint16_t BRIDGE_PACKET_MAGIC = 0xC03E; + + /** + * @brief Common field sizes used by bridge implementations + * + * These constants define the size of common packet fields used across bridges. + * BRIDGE_MAGIC_SIZE is used by all bridges for packet identification. + * BRIDGE_LENGTH_SIZE is used by bridges that need explicit length fields (like RS232). + * BRIDGE_CHECKSUM_SIZE is used by all bridges for Fletcher-16 checksums. + */ + static constexpr uint16_t BRIDGE_MAGIC_SIZE = sizeof(BRIDGE_PACKET_MAGIC); + static constexpr uint16_t BRIDGE_LENGTH_SIZE = sizeof(uint16_t); + static constexpr uint16_t BRIDGE_CHECKSUM_SIZE = sizeof(uint16_t); + protected: /** Packet manager for allocating and queuing mesh packets */ mesh::PacketManager *_mgr; diff --git a/src/helpers/bridges/ESPNowBridge.cpp b/src/helpers/bridges/ESPNowBridge.cpp index baf683c..a02f804 100644 --- a/src/helpers/bridges/ESPNowBridge.cpp +++ b/src/helpers/bridges/ESPNowBridge.cpp @@ -66,7 +66,7 @@ void ESPNowBridge::xorCrypt(uint8_t *data, size_t len) { void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int32_t len) { // Ignore packets that are too small to contain header + checksum - if (len < (MAGIC_HEADER_SIZE + CHECKSUM_SIZE)) { + if (len < (BRIDGE_MAGIC_SIZE + BRIDGE_CHECKSUM_SIZE)) { #if MESH_PACKET_LOGGING Serial.printf("%s: ESPNOW BRIDGE: RX packet too small, len=%d\n", getLogDateTime(), len); #endif @@ -83,7 +83,7 @@ void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int32_t l // Check packet header magic uint16_t received_magic = (data[0] << 8) | data[1]; - if (received_magic != ESPNOW_HEADER_MAGIC) { + if (received_magic != BRIDGE_PACKET_MAGIC) { #if MESH_PACKET_LOGGING Serial.printf("%s: ESPNOW BRIDGE: RX invalid magic 0x%04X\n", getLogDateTime(), received_magic); #endif @@ -92,17 +92,17 @@ void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int32_t l // Make a copy we can decrypt uint8_t decrypted[MAX_ESPNOW_PACKET_SIZE]; - const size_t encryptedDataLen = len - MAGIC_HEADER_SIZE; - memcpy(decrypted, data + MAGIC_HEADER_SIZE, encryptedDataLen); + const size_t encryptedDataLen = len - BRIDGE_MAGIC_SIZE; + memcpy(decrypted, data + BRIDGE_MAGIC_SIZE, encryptedDataLen); // Try to decrypt (checksum + payload) xorCrypt(decrypted, encryptedDataLen); // Validate checksum uint16_t received_checksum = (decrypted[0] << 8) | decrypted[1]; - const size_t payloadLen = encryptedDataLen - CHECKSUM_SIZE; + const size_t payloadLen = encryptedDataLen - BRIDGE_CHECKSUM_SIZE; - if (!validateChecksum(decrypted + CHECKSUM_SIZE, payloadLen, received_checksum)) { + if (!validateChecksum(decrypted + BRIDGE_CHECKSUM_SIZE, payloadLen, received_checksum)) { // Failed to decrypt - likely from a different network #if MESH_PACKET_LOGGING Serial.printf("%s: ESPNOW BRIDGE: RX checksum mismatch, rcv=0x%04X\n", getLogDateTime(), @@ -119,7 +119,7 @@ void ESPNowBridge::onDataRecv(const uint8_t *mac, const uint8_t *data, int32_t l mesh::Packet *pkt = _instance->_mgr->allocNew(); if (!pkt) return; - if (pkt->readFrom(decrypted + CHECKSUM_SIZE, payloadLen)) { + if (pkt->readFrom(decrypted + BRIDGE_CHECKSUM_SIZE, payloadLen)) { _instance->onPacketReceived(pkt); } else { _instance->_mgr->free(pkt); @@ -161,11 +161,11 @@ void ESPNowBridge::onPacketTransmitted(mesh::Packet *packet) { uint8_t buffer[MAX_ESPNOW_PACKET_SIZE]; // Write magic header (2 bytes) - buffer[0] = (ESPNOW_HEADER_MAGIC >> 8) & 0xFF; - buffer[1] = ESPNOW_HEADER_MAGIC & 0xFF; + buffer[0] = (BRIDGE_PACKET_MAGIC >> 8) & 0xFF; + buffer[1] = BRIDGE_PACKET_MAGIC & 0xFF; // Write packet payload starting after magic header and checksum - const size_t packetOffset = MAGIC_HEADER_SIZE + CHECKSUM_SIZE; + const size_t packetOffset = BRIDGE_MAGIC_SIZE + BRIDGE_CHECKSUM_SIZE; memcpy(buffer + packetOffset, sizingBuffer, meshPacketLen); // Calculate and add checksum (only of the payload) @@ -174,10 +174,10 @@ void ESPNowBridge::onPacketTransmitted(mesh::Packet *packet) { buffer[3] = checksum & 0xFF; // Low byte // Encrypt payload and checksum (not including magic header) - xorCrypt(buffer + MAGIC_HEADER_SIZE, meshPacketLen + CHECKSUM_SIZE); + xorCrypt(buffer + BRIDGE_MAGIC_SIZE, meshPacketLen + BRIDGE_CHECKSUM_SIZE); // Total packet size: magic header + checksum + payload - const size_t totalPacketSize = MAGIC_HEADER_SIZE + CHECKSUM_SIZE + meshPacketLen; + const size_t totalPacketSize = BRIDGE_MAGIC_SIZE + BRIDGE_CHECKSUM_SIZE + meshPacketLen; // Broadcast using ESP-NOW uint8_t broadcastAddress[] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; diff --git a/src/helpers/bridges/ESPNowBridge.h b/src/helpers/bridges/ESPNowBridge.h index d9962c7..b43f174 100644 --- a/src/helpers/bridges/ESPNowBridge.h +++ b/src/helpers/bridges/ESPNowBridge.h @@ -65,14 +65,7 @@ private: /** * Size constants for packet parsing */ - static const size_t MAGIC_HEADER_SIZE = 2; - static const size_t CHECKSUM_SIZE = 2; - static const size_t MAX_PAYLOAD_SIZE = MAX_ESPNOW_PACKET_SIZE - (MAGIC_HEADER_SIZE + CHECKSUM_SIZE); - - /** - * Magic bytes to identify ESPNowBridge packets - */ - static const uint16_t ESPNOW_HEADER_MAGIC = 0xC03E; + static const size_t MAX_PAYLOAD_SIZE = MAX_ESPNOW_PACKET_SIZE - (BRIDGE_MAGIC_SIZE + BRIDGE_CHECKSUM_SIZE); /** Buffer for receiving ESP-NOW packets */ uint8_t _rx_buffer[MAX_ESPNOW_PACKET_SIZE]; diff --git a/src/helpers/bridges/RS232Bridge.cpp b/src/helpers/bridges/RS232Bridge.cpp index 39a0968..b209a6d 100644 --- a/src/helpers/bridges/RS232Bridge.cpp +++ b/src/helpers/bridges/RS232Bridge.cpp @@ -52,8 +52,8 @@ void RS232Bridge::onPacketTransmitted(mesh::Packet *packet) { } // Build packet header - buffer[0] = (SERIAL_PKT_MAGIC >> 8) & 0xFF; // Magic high byte - buffer[1] = SERIAL_PKT_MAGIC & 0xFF; // Magic low byte + buffer[0] = (BRIDGE_PACKET_MAGIC >> 8) & 0xFF; // Magic high byte + buffer[1] = BRIDGE_PACKET_MAGIC & 0xFF; // Magic low byte buffer[2] = (len >> 8) & 0xFF; // Length high byte buffer[3] = len & 0xFF; // Length low byte @@ -77,14 +77,14 @@ void RS232Bridge::loop() { if (_rx_buffer_pos < 2) { // Waiting for magic word - if ((_rx_buffer_pos == 0 && b == ((SERIAL_PKT_MAGIC >> 8) & 0xFF)) || - (_rx_buffer_pos == 1 && b == (SERIAL_PKT_MAGIC & 0xFF))) { + if ((_rx_buffer_pos == 0 && b == ((BRIDGE_PACKET_MAGIC >> 8) & 0xFF)) || + (_rx_buffer_pos == 1 && b == (BRIDGE_PACKET_MAGIC & 0xFF))) { _rx_buffer[_rx_buffer_pos++] = b; } else { // Invalid magic byte, reset and start over _rx_buffer_pos = 0; // Check if this byte could be the start of a new magic word - if (b == ((SERIAL_PKT_MAGIC >> 8) & 0xFF)) { + if (b == ((BRIDGE_PACKET_MAGIC >> 8) & 0xFF)) { _rx_buffer[_rx_buffer_pos++] = b; } } diff --git a/src/helpers/bridges/RS232Bridge.h b/src/helpers/bridges/RS232Bridge.h index 32fad17..3b09de7 100644 --- a/src/helpers/bridges/RS232Bridge.h +++ b/src/helpers/bridges/RS232Bridge.h @@ -113,21 +113,11 @@ private: * Total overhead: 6 bytes */ - /** Magic number to identify start of RS232Bridge packets */ - static constexpr uint16_t SERIAL_PKT_MAGIC = 0xC03E; - - /** - * Size constants for packet parsing and construction - */ - static constexpr uint16_t MAGIC_HEADER_SIZE = 2; - static constexpr uint16_t LENGTH_FIELD_SIZE = 2; - static constexpr uint16_t CHECKSUM_SIZE = 2; - /** * @brief The total overhead of the serial protocol in bytes. * Includes: MAGIC_WORD (2) + LENGTH (2) + CHECKSUM (2) = 6 bytes */ - static constexpr uint16_t SERIAL_OVERHEAD = MAGIC_HEADER_SIZE + LENGTH_FIELD_SIZE + CHECKSUM_SIZE; + static constexpr uint16_t SERIAL_OVERHEAD = BRIDGE_MAGIC_SIZE + BRIDGE_LENGTH_SIZE + BRIDGE_CHECKSUM_SIZE; /** * @brief The maximum size of a complete packet on the serial line. diff --git a/variants/lilygo_tlora_v2_1/platformio.ini b/variants/lilygo_tlora_v2_1/platformio.ini index aa957fb..d9ff170 100644 --- a/variants/lilygo_tlora_v2_1/platformio.ini +++ b/variants/lilygo_tlora_v2_1/platformio.ini @@ -198,7 +198,7 @@ build_flags = -D MAX_NEIGHBOURS=8 -D WITH_ESPNOW_BRIDGE=1 -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' -; -D MESH_PACKET_LOGGING=1 + -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 ; -D CORE_DEBUG_LEVEL=3 lib_deps = From 1c93c162a18bcf61bedbafe343d680e06333aa40 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Mon, 8 Sep 2025 18:49:33 +0100 Subject: [PATCH 36/50] Add ESPNow bridge configurations for all ESP32 targets --- variants/generic-e22/platformio.ini | 94 ++++++++++++++++++ variants/heltec_ct62/platformio.ini | 41 ++++++++ variants/heltec_e213/platformio.ini | 45 +++++++++ variants/heltec_e290/platformio.ini | 45 +++++++++ variants/heltec_t190/platformio.ini | 41 ++++++++ variants/heltec_tracker/platformio.ini | 47 +++++++++ variants/heltec_v2/platformio.ini | 47 +++++++++ variants/heltec_wireless_paper/platformio.ini | 45 +++++++++ variants/lilygo_t3s3/platformio.ini | 45 +++++++++ variants/lilygo_t3s3_sx1276/platformio.ini | 45 +++++++++ variants/lilygo_tbeam_SX1262/platformio.ini | 41 ++++++++ variants/lilygo_tbeam_SX1276/platformio.ini | 43 ++++++++ .../platformio.ini | 41 ++++++++ variants/lilygo_tlora_v2_1/platformio.ini | 2 +- variants/meshadventurer/platformio.ini | 98 +++++++++++++++++++ variants/station_g2/platformio.ini | 84 ++++++++++++++++ variants/tenstar_c3/platformio.ini | 96 ++++++++++++++++++ variants/xiao_s3_wio/platformio.ini | 41 ++++++++ 18 files changed, 940 insertions(+), 1 deletion(-) diff --git a/variants/generic-e22/platformio.ini b/variants/generic-e22/platformio.ini index 8b2c293..c9a6722 100644 --- a/variants/generic-e22/platformio.ini +++ b/variants/generic-e22/platformio.ini @@ -47,6 +47,53 @@ lib_deps = ${Generic_E22.lib_deps} ${esp32_ota.lib_deps} +; [env:Generic_E22_sx1262_repeater_bridge_rs232] +; extends = Generic_E22 +; build_src_filter = ${Generic_E22.build_src_filter} +; + +; +<../examples/simple_repeater/main.cpp> +; build_flags = +; ${Generic_E22.build_flags} +; -D RADIO_CLASS=CustomSX1262 +; -D WRAPPER_CLASS=CustomSX1262Wrapper +; -D LORA_TX_POWER=22 +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; lib_deps = +; ${Generic_E22.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Generic_E22_sx1262_repeater_bridge_espnow] +extends = Generic_E22 +build_src_filter = ${Generic_E22.build_src_filter} + + + +<../examples/simple_repeater/main.cpp> +build_flags = + ${Generic_E22.build_flags} + -D RADIO_CLASS=CustomSX1262 + -D WRAPPER_CLASS=CustomSX1262Wrapper + -D LORA_TX_POWER=22 + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +lib_deps = + ${Generic_E22.lib_deps} + ${esp32_ota.lib_deps} + [env:Generic_E22_sx1268_repeater] extends = Generic_E22 build_src_filter = ${Generic_E22.build_src_filter} @@ -66,3 +113,50 @@ build_flags = lib_deps = ${Generic_E22.lib_deps} ${esp32_ota.lib_deps} + +; [env:Generic_E22_sx1268_repeater_bridge_rs232] +; extends = Generic_E22 +; build_src_filter = ${Generic_E22.build_src_filter} +; + +; +<../examples/simple_repeater/main.cpp> +; build_flags = +; ${Generic_E22.build_flags} +; -D RADIO_CLASS=CustomSX1268 +; -D WRAPPER_CLASS=CustomSX1268Wrapper +; -D LORA_TX_POWER=22 +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; lib_deps = +; ${Generic_E22.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Generic_E22_sx1268_repeater_bridge_espnow] +extends = Generic_E22 +build_src_filter = ${Generic_E22.build_src_filter} + + + +<../examples/simple_repeater/main.cpp> +build_flags = + ${Generic_E22.build_flags} + -D RADIO_CLASS=CustomSX1268 + -D WRAPPER_CLASS=CustomSX1268Wrapper + -D LORA_TX_POWER=22 + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +lib_deps = + ${Generic_E22.lib_deps} + ${esp32_ota.lib_deps} diff --git a/variants/heltec_ct62/platformio.ini b/variants/heltec_ct62/platformio.ini index 0dc512b..1b83adb 100644 --- a/variants/heltec_ct62/platformio.ini +++ b/variants/heltec_ct62/platformio.ini @@ -49,6 +49,47 @@ lib_deps = ${Heltec_ct62.lib_deps} ${esp32_ota.lib_deps} +; [env:Heltec_ct62_repeater_bridge_rs232] +; extends = Heltec_ct62 +; build_flags = +; ${Heltec_ct62.build_flags} +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Heltec_ct62.build_src_filter} +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Heltec_ct62.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Heltec_ct62_repeater_bridge_espnow] +extends = Heltec_ct62 +build_flags = + ${Heltec_ct62.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_ct62.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_ct62.lib_deps} + ${esp32_ota.lib_deps} + [env:Heltec_ct62_companion_radio_usb] extends = Heltec_ct62 build_flags = diff --git a/variants/heltec_e213/platformio.ini b/variants/heltec_e213/platformio.ini index c8efc81..a6fe256 100644 --- a/variants/heltec_e213/platformio.ini +++ b/variants/heltec_e213/platformio.ini @@ -93,6 +93,51 @@ lib_deps = ${Heltec_E213_base.lib_deps} ${esp32_ota.lib_deps} +; [env:Heltec_E213_repeater_bridge_rs232] +; extends = Heltec_E213_base +; build_flags = +; ${Heltec_E213_base.build_flags} +; -D DISPLAY_CLASS=E213Display +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Heltec_E213_base.build_src_filter} +; + +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Heltec_E213_base.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Heltec_E213_repeater_bridge_espnow] +extends = Heltec_E213_base +build_flags = + ${Heltec_E213_base.build_flags} + -D DISPLAY_CLASS=E213Display + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_E213_base.build_src_filter} + + + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_E213_base.lib_deps} + ${esp32_ota.lib_deps} + [env:Heltec_E213_room_server] extends = Heltec_E213_base build_flags = diff --git a/variants/heltec_e290/platformio.ini b/variants/heltec_e290/platformio.ini index 377162f..0223b30 100644 --- a/variants/heltec_e290/platformio.ini +++ b/variants/heltec_e290/platformio.ini @@ -89,6 +89,51 @@ lib_deps = ${Heltec_E290_base.lib_deps} ${esp32_ota.lib_deps} +; [env:Heltec_E290_repeater_bridge_rs232] +; extends = Heltec_E290_base +; build_flags = +; ${Heltec_E290_base.build_flags} +; -D DISPLAY_CLASS=E290Display +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Heltec_E290_base.build_src_filter} +; + +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Heltec_E290_base.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Heltec_E290_repeater_bridge_espnow] +extends = Heltec_E290_base +build_flags = + ${Heltec_E290_base.build_flags} + -D DISPLAY_CLASS=E290Display + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_E290_base.build_src_filter} + + + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_E290_base.lib_deps} + ${esp32_ota.lib_deps} + [env:Heltec_E290_room_server] extends = Heltec_E290_base build_flags = diff --git a/variants/heltec_t190/platformio.ini b/variants/heltec_t190/platformio.ini index 7debe17..52bb79e 100644 --- a/variants/heltec_t190/platformio.ini +++ b/variants/heltec_t190/platformio.ini @@ -94,6 +94,47 @@ lib_deps = ${Heltec_T190_base.lib_deps} ${esp32_ota.lib_deps} +; [env:Heltec_T190_repeater_bridge_rs232] +; extends = Heltec_T190_base +; build_flags = +; ${Heltec_T190_base.build_flags} +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Heltec_T190_base.build_src_filter} +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Heltec_T190_base.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Heltec_T190_repeater_bridge_espnow] +extends = Heltec_T190_base +build_flags = + ${Heltec_T190_base.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_T190_base.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_T190_base.lib_deps} + ${esp32_ota.lib_deps} + [env:Heltec_T190_room_server] extends = Heltec_T190_base build_flags = diff --git a/variants/heltec_tracker/platformio.ini b/variants/heltec_tracker/platformio.ini index f1477e9..5c0df00 100644 --- a/variants/heltec_tracker/platformio.ini +++ b/variants/heltec_tracker/platformio.ini @@ -80,6 +80,53 @@ lib_deps = ${Heltec_tracker_base.lib_deps} ${esp32_ota.lib_deps} +; [env:Heltec_Wireless_Tracker_repeater_bridge_rs232] +; extends = Heltec_tracker_base +; build_flags = +; ${Heltec_tracker_base.build_flags} +; -D DISPLAY_ROTATION=1 +; -D DISPLAY_CLASS=ST7735Display +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Heltec_tracker_base.build_src_filter} +; + +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Heltec_tracker_base.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Heltec_Wireless_Tracker_repeater_bridge_espnow] +extends = Heltec_tracker_base +build_flags = + ${Heltec_tracker_base.build_flags} + -D DISPLAY_ROTATION=1 + -D DISPLAY_CLASS=ST7735Display + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_tracker_base.build_src_filter} + + + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_tracker_base.lib_deps} + ${esp32_ota.lib_deps} + [env:Heltec_Wireless_Tracker_room_server] extends = Heltec_tracker_base build_flags = diff --git a/variants/heltec_v2/platformio.ini b/variants/heltec_v2/platformio.ini index 352ea34..d2afe4d 100644 --- a/variants/heltec_v2/platformio.ini +++ b/variants/heltec_v2/platformio.ini @@ -40,6 +40,53 @@ lib_deps = ${Heltec_lora32_v2.lib_deps} ${esp32_ota.lib_deps} +; [env:Heltec_v2_repeater_bridge_rs232] +; extends = Heltec_lora32_v2 +; build_flags = +; ${Heltec_lora32_v2.build_flags} +; -D DISPLAY_CLASS=SSD1306Display +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Heltec_lora32_v2.build_src_filter} +; + +; + +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Heltec_lora32_v2.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Heltec_v2_repeater_bridge_espnow] +extends = Heltec_lora32_v2 +build_flags = + ${Heltec_lora32_v2.build_flags} + -D DISPLAY_CLASS=SSD1306Display + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_lora32_v2.build_src_filter} + + + + + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_lora32_v2.lib_deps} + ${esp32_ota.lib_deps} + [env:Heltec_v2_room_server] extends = Heltec_lora32_v2 build_flags = diff --git a/variants/heltec_wireless_paper/platformio.ini b/variants/heltec_wireless_paper/platformio.ini index 8de826e..43ac2a8 100644 --- a/variants/heltec_wireless_paper/platformio.ini +++ b/variants/heltec_wireless_paper/platformio.ini @@ -68,6 +68,51 @@ lib_deps = ${Heltec_Wireless_Paper_base.lib_deps} ${esp32_ota.lib_deps} +; [env:Heltec_Wireless_Paper_repeater_bridge_rs232] +; extends = Heltec_Wireless_Paper_base +; build_flags = +; ${Heltec_Wireless_Paper_base.build_flags} +; -D DISPLAY_CLASS=E213Display +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Heltec_Wireless_Paper_base.build_src_filter} +; + +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Heltec_Wireless_Paper_base.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Heltec_Wireless_Paper_repeater_bridge_espnow] +extends = Heltec_Wireless_Paper_base +build_flags = + ${Heltec_Wireless_Paper_base.build_flags} + -D DISPLAY_CLASS=E213Display + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Heltec_Wireless_Paper_base.build_src_filter} + + + + + +<../examples/simple_repeater> +lib_deps = + ${Heltec_Wireless_Paper_base.lib_deps} + ${esp32_ota.lib_deps} + [env:Heltec_Wireless_Paper_room_server] extends = Heltec_Wireless_Paper_base build_flags = diff --git a/variants/lilygo_t3s3/platformio.ini b/variants/lilygo_t3s3/platformio.ini index 637cc12..ca22110 100644 --- a/variants/lilygo_t3s3/platformio.ini +++ b/variants/lilygo_t3s3/platformio.ini @@ -52,6 +52,51 @@ lib_deps = ${LilyGo_T3S3_sx1262.lib_deps} ${esp32_ota.lib_deps} +; [env:LilyGo_T3S3_sx1262_Repeater_bridge_rs232] +; extends = LilyGo_T3S3_sx1262 +; build_flags = +; ${LilyGo_T3S3_sx1262.build_flags} +; -D DISPLAY_CLASS=SSD1306Display +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${LilyGo_T3S3_sx1262.build_src_filter} +; + +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${LilyGo_T3S3_sx1262.lib_deps} +; ${esp32_ota.lib_deps} + +[env:LilyGo_T3S3_sx1262_Repeater_bridge_espnow] +extends = LilyGo_T3S3_sx1262 +build_flags = + ${LilyGo_T3S3_sx1262.build_flags} + -D DISPLAY_CLASS=SSD1306Display + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${LilyGo_T3S3_sx1262.build_src_filter} + + + + + +<../examples/simple_repeater> +lib_deps = + ${LilyGo_T3S3_sx1262.lib_deps} + ${esp32_ota.lib_deps} + [env:LilyGo_T3S3_sx1262_terminal_chat] extends = LilyGo_T3S3_sx1262 build_flags = diff --git a/variants/lilygo_t3s3_sx1276/platformio.ini b/variants/lilygo_t3s3_sx1276/platformio.ini index 23c58fb..1c0d5cf 100644 --- a/variants/lilygo_t3s3_sx1276/platformio.ini +++ b/variants/lilygo_t3s3_sx1276/platformio.ini @@ -50,6 +50,51 @@ lib_deps = ${LilyGo_T3S3_sx1276.lib_deps} ${esp32_ota.lib_deps} +; [env:LilyGo_T3S3_sx1276_Repeater_bridge_rs232] +; extends = LilyGo_T3S3_sx1276 +; build_flags = +; ${LilyGo_T3S3_sx1276.build_flags} +; -D DISPLAY_CLASS=SSD1306Display +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${LilyGo_T3S3_sx1276.build_src_filter} +; + +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${LilyGo_T3S3_sx1276.lib_deps} +; ${esp32_ota.lib_deps} + +[env:LilyGo_T3S3_sx1276_Repeater_bridge_espnow] +extends = LilyGo_T3S3_sx1276 +build_flags = + ${LilyGo_T3S3_sx1276.build_flags} + -D DISPLAY_CLASS=SSD1306Display + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' + ; -D MESH_PACKET_LOGGING=1 + ; -D MESH_DEBUG=1 +build_src_filter = ${LilyGo_T3S3_sx1276.build_src_filter} + + + + + +<../examples/simple_repeater> +lib_deps = + ${LilyGo_T3S3_sx1276.lib_deps} + ${esp32_ota.lib_deps} + [env:LilyGo_T3S3_sx1276_terminal_chat] extends = LilyGo_T3S3_sx1276 build_flags = diff --git a/variants/lilygo_tbeam_SX1262/platformio.ini b/variants/lilygo_tbeam_SX1262/platformio.ini index ea8872d..f7d1a76 100644 --- a/variants/lilygo_tbeam_SX1262/platformio.ini +++ b/variants/lilygo_tbeam_SX1262/platformio.ini @@ -74,6 +74,47 @@ lib_deps = ${LilyGo_TBeam_SX1262.lib_deps} ${esp32_ota.lib_deps} +; [env:Tbeam_SX1262_repeater_bridge_rs232] +; extends = LilyGo_TBeam_SX1262 +; build_flags = +; ${LilyGo_TBeam_SX1262.build_flags} +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${LilyGo_TBeam_SX1262.build_src_filter} +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${LilyGo_TBeam_SX1262.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Tbeam_SX1262_repeater_bridge_espnow] +extends = LilyGo_TBeam_SX1262 +build_flags = + ${LilyGo_TBeam_SX1262.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${LilyGo_TBeam_SX1262.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${LilyGo_TBeam_SX1262.lib_deps} + ${esp32_ota.lib_deps} + [env:Tbeam_SX1262_room_server] extends = LilyGo_TBeam_SX1262 build_flags = diff --git a/variants/lilygo_tbeam_SX1276/platformio.ini b/variants/lilygo_tbeam_SX1276/platformio.ini index 782b74c..d7e119e 100644 --- a/variants/lilygo_tbeam_SX1276/platformio.ini +++ b/variants/lilygo_tbeam_SX1276/platformio.ini @@ -72,6 +72,49 @@ lib_deps = ${LilyGo_TBeam_SX1276.lib_deps} ${esp32_ota.lib_deps} +; [env:Tbeam_SX1276_repeater_bridge_rs232] +; extends = LilyGo_TBeam_SX1276 +; build_flags = +; ${LilyGo_TBeam_SX1276.build_flags} +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D PERSISTANT_GPS=1 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${LilyGo_TBeam_SX1276.build_src_filter} +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${LilyGo_TBeam_SX1276.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Tbeam_SX1276_repeater_bridge_espnow] +extends = LilyGo_TBeam_SX1276 +build_flags = + ${LilyGo_TBeam_SX1276.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D PERSISTANT_GPS=1 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${LilyGo_TBeam_SX1276.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${LilyGo_TBeam_SX1276.lib_deps} + ${esp32_ota.lib_deps} + [env:Tbeam_SX1276_room_server] extends = LilyGo_TBeam_SX1276 build_flags = diff --git a/variants/lilygo_tbeam_supreme_SX1262/platformio.ini b/variants/lilygo_tbeam_supreme_SX1262/platformio.ini index e613587..328ebf0 100644 --- a/variants/lilygo_tbeam_supreme_SX1262/platformio.ini +++ b/variants/lilygo_tbeam_supreme_SX1262/platformio.ini @@ -52,6 +52,47 @@ lib_deps = ${T_Beam_S3_Supreme_SX1262.lib_deps} ${esp32_ota.lib_deps} +; [env:T_Beam_S3_Supreme_SX1262_repeater_bridge_rs232] +; extends = T_Beam_S3_Supreme_SX1262 +; build_flags = +; ${T_Beam_S3_Supreme_SX1262.build_flags} +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0 +; -D ADVERT_LON=0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${T_Beam_S3_Supreme_SX1262.build_src_filter} +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${T_Beam_S3_Supreme_SX1262.lib_deps} +; ${esp32_ota.lib_deps} + +[env:T_Beam_S3_Supreme_SX1262_repeater_bridge_espnow] +extends = T_Beam_S3_Supreme_SX1262 +build_flags = + ${T_Beam_S3_Supreme_SX1262.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0 + -D ADVERT_LON=0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${T_Beam_S3_Supreme_SX1262.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${T_Beam_S3_Supreme_SX1262.lib_deps} + ${esp32_ota.lib_deps} + [env:T_Beam_S3_Supreme_SX1262_room_server] extends = T_Beam_S3_Supreme_SX1262 build_flags = diff --git a/variants/lilygo_tlora_v2_1/platformio.ini b/variants/lilygo_tlora_v2_1/platformio.ini index d9ff170..aa957fb 100644 --- a/variants/lilygo_tlora_v2_1/platformio.ini +++ b/variants/lilygo_tlora_v2_1/platformio.ini @@ -198,7 +198,7 @@ build_flags = -D MAX_NEIGHBOURS=8 -D WITH_ESPNOW_BRIDGE=1 -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' - -D MESH_PACKET_LOGGING=1 +; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 ; -D CORE_DEBUG_LEVEL=3 lib_deps = diff --git a/variants/meshadventurer/platformio.ini b/variants/meshadventurer/platformio.ini index 1b881c1..be3b494 100644 --- a/variants/meshadventurer/platformio.ini +++ b/variants/meshadventurer/platformio.ini @@ -54,6 +54,55 @@ lib_deps = ${Meshadventurer.lib_deps} ${esp32_ota.lib_deps} +; [env:Meshadventurer_sx1262_repeater_bridge_rs232] +; extends = Meshadventurer +; build_src_filter = ${Meshadventurer.build_src_filter} +; + +; +<../examples/simple_repeater> +; + +; build_flags = +; ${Meshadventurer.build_flags} +; -D RADIO_CLASS=CustomSX1262 +; -D WRAPPER_CLASS=CustomSX1262Wrapper +; -D LORA_TX_POWER=22 +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; lib_deps = +; ${Meshadventurer.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Meshadventurer_sx1262_repeater_bridge_espnow] +extends = Meshadventurer +build_src_filter = ${Meshadventurer.build_src_filter} + + + +<../examples/simple_repeater> + + +build_flags = + ${Meshadventurer.build_flags} + -D RADIO_CLASS=CustomSX1262 + -D WRAPPER_CLASS=CustomSX1262Wrapper + -D LORA_TX_POWER=22 + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +lib_deps = + ${Meshadventurer.lib_deps} + ${esp32_ota.lib_deps} + [env:Meshadventurer_sx1268_repeater] extends = Meshadventurer build_src_filter = ${Meshadventurer.build_src_filter} @@ -75,6 +124,55 @@ lib_deps = ${Meshadventurer.lib_deps} ${esp32_ota.lib_deps} +; [env:Meshadventurer_sx1268_repeater_bridge_rs232] +; extends = Meshadventurer +; build_src_filter = ${Meshadventurer.build_src_filter} +; + +; +<../examples/simple_repeater> +; + +; build_flags = +; ${Meshadventurer.build_flags} +; -D RADIO_CLASS=CustomSX1268 +; -D WRAPPER_CLASS=CustomSX1268Wrapper +; -D LORA_TX_POWER=22 +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; lib_deps = +; ${Meshadventurer.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Meshadventurer_sx1268_repeater_bridge_espnow] +extends = Meshadventurer +build_src_filter = ${Meshadventurer.build_src_filter} + + + +<../examples/simple_repeater> + + +build_flags = + ${Meshadventurer.build_flags} + -D RADIO_CLASS=CustomSX1268 + -D WRAPPER_CLASS=CustomSX1268Wrapper + -D LORA_TX_POWER=22 + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +lib_deps = + ${Meshadventurer.lib_deps} + ${esp32_ota.lib_deps} + [env:Meshadventurer_sx1262_companion_radio_usb] extends = Meshadventurer build_src_filter = ${Meshadventurer.build_src_filter} diff --git a/variants/station_g2/platformio.ini b/variants/station_g2/platformio.ini index 0e1631a..908d644 100644 --- a/variants/station_g2/platformio.ini +++ b/variants/station_g2/platformio.ini @@ -45,6 +45,47 @@ lib_deps = ${Station_G2.lib_deps} ${esp32_ota.lib_deps} +; [env:Station_G2_repeater_bridge_rs232] +; extends = Station_G2 +; build_flags = +; ${Station_G2.build_flags} +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Station_G2.build_src_filter} +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Station_G2.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Station_G2_repeater_bridge_espnow] +extends = Station_G2 +build_flags = + ${Station_G2.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +build_src_filter = ${Station_G2.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${Station_G2.lib_deps} + ${esp32_ota.lib_deps} + [env:Station_G2_logging_repeater] extends = Station_G2 build_flags = @@ -64,6 +105,49 @@ lib_deps = ${Station_G2.lib_deps} ${esp32_ota.lib_deps} +; [env:Station_G2_logging_repeater_bridge_rs232] +; extends = Station_G2 +; build_flags = +; ${Station_G2.build_flags} +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D MESH_PACKET_LOGGING=1 +; -D SX126X_RX_BOOSTED_GAIN=1 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_DEBUG=1 +; build_src_filter = ${Station_G2.build_src_filter} +; + +; +<../examples/simple_repeater> +; lib_deps = +; ${Station_G2.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Station_G2_logging_repeater_bridge_espnow] +extends = Station_G2 +build_flags = + ${Station_G2.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D MESH_PACKET_LOGGING=1 + -D SX126X_RX_BOOSTED_GAIN=1 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_DEBUG=1 +build_src_filter = ${Station_G2.build_src_filter} + + + +<../examples/simple_repeater> +lib_deps = + ${Station_G2.lib_deps} + ${esp32_ota.lib_deps} + [env:Station_G2_room_server] extends = Station_G2 build_src_filter = ${Station_G2.build_src_filter} diff --git a/variants/tenstar_c3/platformio.ini b/variants/tenstar_c3/platformio.ini index 4967ec5..c22b377 100644 --- a/variants/tenstar_c3/platformio.ini +++ b/variants/tenstar_c3/platformio.ini @@ -44,6 +44,55 @@ lib_deps = ${Tenstar_esp32_C3.lib_deps} ${esp32_ota.lib_deps} +; [env:Tenstar_C3_Repeater_sx1262_bridge_rs232] +; extends = Tenstar_esp32_C3 +; build_src_filter = ${Tenstar_esp32_C3.build_src_filter} +; + +; +<../examples/simple_repeater/main.cpp> +; build_flags = +; ${Tenstar_esp32_C3.build_flags} +; -D RADIO_CLASS=CustomSX1262 +; -D WRAPPER_CLASS=CustomSX1262Wrapper +; -D SX126X_RX_BOOSTED_GAIN=1 +; -D LORA_TX_POWER=22 +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; lib_deps = +; ${Tenstar_esp32_C3.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Tenstar_C3_Repeater_sx1262_bridge_espnow] +extends = Tenstar_esp32_C3 +build_src_filter = ${Tenstar_esp32_C3.build_src_filter} + + + +<../examples/simple_repeater/main.cpp> +build_flags = + ${Tenstar_esp32_C3.build_flags} + -D RADIO_CLASS=CustomSX1262 + -D WRAPPER_CLASS=CustomSX1262Wrapper + -D SX126X_RX_BOOSTED_GAIN=1 + -D LORA_TX_POWER=22 + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +lib_deps = + ${Tenstar_esp32_C3.lib_deps} + ${esp32_ota.lib_deps} + [env:Tenstar_C3_Repeater_sx1268] extends = Tenstar_esp32_C3 build_src_filter = ${Tenstar_esp32_C3.build_src_filter} @@ -63,3 +112,50 @@ build_flags = lib_deps = ${Tenstar_esp32_C3.lib_deps} ${esp32_ota.lib_deps} + +; [env:Tenstar_C3_Repeater_sx1268_bridge_rs232] +; extends = Tenstar_esp32_C3 +; build_src_filter = ${Tenstar_esp32_C3.build_src_filter} +; + +; +<../examples/simple_repeater/main.cpp> +; build_flags = +; ${Tenstar_esp32_C3.build_flags} +; -D RADIO_CLASS=CustomSX1268 +; -D WRAPPER_CLASS=CustomSX1268Wrapper +; -D LORA_TX_POWER=22 +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; lib_deps = +; ${Tenstar_esp32_C3.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Tenstar_C3_Repeater_sx1268_bridge_espnow] +extends = Tenstar_esp32_C3 +build_src_filter = ${Tenstar_esp32_C3.build_src_filter} + + + +<../examples/simple_repeater/main.cpp> +build_flags = + ${Tenstar_esp32_C3.build_flags} + -D RADIO_CLASS=CustomSX1268 + -D WRAPPER_CLASS=CustomSX1268Wrapper + -D LORA_TX_POWER=22 + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' + ; -D MESH_PACKET_LOGGING=1 + ; -D MESH_DEBUG=1 +lib_deps = + ${Tenstar_esp32_C3.lib_deps} + ${esp32_ota.lib_deps} diff --git a/variants/xiao_s3_wio/platformio.ini b/variants/xiao_s3_wio/platformio.ini index b4f25e5..7408f85 100644 --- a/variants/xiao_s3_wio/platformio.ini +++ b/variants/xiao_s3_wio/platformio.ini @@ -44,6 +44,47 @@ lib_deps = ${Xiao_S3_WIO.lib_deps} ${esp32_ota.lib_deps} +; [env:Xiao_S3_WIO_Repeater_bridge_rs232] +; extends = Xiao_S3_WIO +; build_src_filter = ${Xiao_S3_WIO.build_src_filter} +; + +; +<../examples/simple_repeater/main.cpp> +; build_flags = +; ${Xiao_S3_WIO.build_flags} +; -D ADVERT_NAME='"RS232 Bridge"' +; -D ADVERT_LAT=0.0 +; -D ADVERT_LON=0.0 +; -D ADMIN_PASSWORD='"password"' +; -D MAX_NEIGHBOURS=8 +; -D WITH_RS232_BRIDGE=Serial2 +; -D WITH_RS232_BRIDGE_RX=5 +; -D WITH_RS232_BRIDGE_TX=6 +; ; -D MESH_PACKET_LOGGING=1 +; ; -D MESH_DEBUG=1 +; lib_deps = +; ${Xiao_S3_WIO.lib_deps} +; ${esp32_ota.lib_deps} + +[env:Xiao_S3_WIO_Repeater_bridge_espnow] +extends = Xiao_S3_WIO +build_src_filter = ${Xiao_S3_WIO.build_src_filter} + + + +<../examples/simple_repeater/main.cpp> +build_flags = + ${Xiao_S3_WIO.build_flags} + -D ADVERT_NAME='"ESPNow Bridge"' + -D ADVERT_LAT=0.0 + -D ADVERT_LON=0.0 + -D ADMIN_PASSWORD='"password"' + -D MAX_NEIGHBOURS=8 + -D WITH_ESPNOW_BRIDGE=1 + -D WITH_ESPNOW_BRIDGE_SECRET='"shared-secret"' +; -D MESH_PACKET_LOGGING=1 +; -D MESH_DEBUG=1 +lib_deps = + ${Xiao_S3_WIO.lib_deps} + ${esp32_ota.lib_deps} + [env:Xiao_S3_WIO_room_server] extends = Xiao_S3_WIO build_src_filter = ${Xiao_S3_WIO.build_src_filter} From a55fa8d8ecc987f2fbdf2f792a6fb62e24099c54 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Mon, 8 Sep 2025 20:21:33 +0100 Subject: [PATCH 37/50] Add BRIDGE_DELAY as a buffer to prevent immediate processing conflicts in the mesh network --- src/helpers/bridges/BridgeBase.cpp | 4 +++- src/helpers/bridges/BridgeBase.h | 12 ++++++++++-- src/helpers/bridges/RS232Bridge.cpp | 4 ++-- 3 files changed, 15 insertions(+), 5 deletions(-) diff --git a/src/helpers/bridges/BridgeBase.cpp b/src/helpers/bridges/BridgeBase.cpp index 2055119..0387141 100644 --- a/src/helpers/bridges/BridgeBase.cpp +++ b/src/helpers/bridges/BridgeBase.cpp @@ -1,5 +1,7 @@ #include "BridgeBase.h" +#include + const char *BridgeBase::getLogDateTime() { static char tmp[32]; uint32_t now = _rtc->getCurrentTime(); @@ -27,7 +29,7 @@ bool BridgeBase::validateChecksum(const uint8_t *data, size_t len, uint16_t rece void BridgeBase::handleReceivedPacket(mesh::Packet *packet) { if (!_seen_packets.hasSeen(packet)) { - _mgr->queueInbound(packet, 0); + _mgr->queueInbound(packet, millis() + BRIDGE_DELAY); } else { _mgr->free(packet); } diff --git a/src/helpers/bridges/BridgeBase.h b/src/helpers/bridges/BridgeBase.h index c1764ae..ab62619 100644 --- a/src/helpers/bridges/BridgeBase.h +++ b/src/helpers/bridges/BridgeBase.h @@ -23,7 +23,7 @@ public: /** * @brief Common magic number used by all bridge implementations for packet identification - * + * * This magic number is placed at the beginning of bridge packets to identify * them as mesh bridge packets and provide frame synchronization. */ @@ -31,7 +31,7 @@ public: /** * @brief Common field sizes used by bridge implementations - * + * * These constants define the size of common packet fields used across bridges. * BRIDGE_MAGIC_SIZE is used by all bridges for packet identification. * BRIDGE_LENGTH_SIZE is used by bridges that need explicit length fields (like RS232). @@ -41,6 +41,14 @@ public: static constexpr uint16_t BRIDGE_LENGTH_SIZE = sizeof(uint16_t); static constexpr uint16_t BRIDGE_CHECKSUM_SIZE = sizeof(uint16_t); + /** + * @brief Default delay in milliseconds for scheduling inbound packet processing + * + * It provides a buffer to prevent immediate processing conflicts in the mesh network. + * Used in handleReceivedPacket() as: millis() + BRIDGE_DELAY + */ + static constexpr uint16_t BRIDGE_DELAY = 500; // TODO: maybe too high ? + protected: /** Packet manager for allocating and queuing mesh packets */ mesh::PacketManager *_mgr; diff --git a/src/helpers/bridges/RS232Bridge.cpp b/src/helpers/bridges/RS232Bridge.cpp index b209a6d..d182aea 100644 --- a/src/helpers/bridges/RS232Bridge.cpp +++ b/src/helpers/bridges/RS232Bridge.cpp @@ -54,8 +54,8 @@ void RS232Bridge::onPacketTransmitted(mesh::Packet *packet) { // Build packet header buffer[0] = (BRIDGE_PACKET_MAGIC >> 8) & 0xFF; // Magic high byte buffer[1] = BRIDGE_PACKET_MAGIC & 0xFF; // Magic low byte - buffer[2] = (len >> 8) & 0xFF; // Length high byte - buffer[3] = len & 0xFF; // Length low byte + buffer[2] = (len >> 8) & 0xFF; // Length high byte + buffer[3] = len & 0xFF; // Length low byte // Calculate checksum over the payload uint16_t checksum = fletcher16(buffer + 4, len); From e8314c9c8c6deecc2af1ecf01ed31dcf471322b1 Mon Sep 17 00:00:00 2001 From: taco Date: Tue, 9 Sep 2025 16:55:46 +1000 Subject: [PATCH 38/50] new ldscript for extrafs nrf companion envs --- boards/nrf52840_s140_v6_extrafs.ld | 38 ++++++++++++++++++++++ boards/nrf52840_s140_v7_extrafs.ld | 38 ++++++++++++++++++++++ variants/heltec_mesh_solar/platformio.ini | 4 +++ variants/heltec_t114/platformio.ini | 8 +++++ variants/ikoka_stick_nrf/platformio.ini | 4 +++ variants/lilygo_techo/platformio.ini | 4 +++ variants/mesh_pocket/platformio.ini | 4 +++ variants/minewsemi_me25ls01/platformio.ini | 4 +++ variants/nano_g2_ultra/platformio.ini | 4 +++ variants/promicro/platformio.ini | 4 +++ variants/rak4631/platformio.ini | 4 +++ variants/rak_wismesh_tag/platformio.ini | 4 +++ variants/sensecap_solar/platformio.ini | 4 +++ variants/t1000-e/platformio.ini | 4 +++ variants/thinknode_m1/platformio.ini | 4 +++ variants/wio-tracker-l1/platformio.ini | 4 +++ variants/xiao_nrf52/platformio.ini | 4 +++ 17 files changed, 140 insertions(+) create mode 100644 boards/nrf52840_s140_v6_extrafs.ld create mode 100644 boards/nrf52840_s140_v7_extrafs.ld diff --git a/boards/nrf52840_s140_v6_extrafs.ld b/boards/nrf52840_s140_v6_extrafs.ld new file mode 100644 index 0000000..3526106 --- /dev/null +++ b/boards/nrf52840_s140_v6_extrafs.ld @@ -0,0 +1,38 @@ +/* Linker script to configure memory regions. */ + +SEARCH_DIR(.) +GROUP(-lgcc -lc -lnosys) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x26000, LENGTH = 0xD4000 - 0x26000 + + /* SRAM required by Softdevice depend on + * - Attribute Table Size (Number of Services and Characteristics) + * - Vendor UUID count + * - Max ATT MTU + * - Concurrent connection peripheral + central + secure links + * - Event Len, HVN queue, Write CMD queue + */ + RAM (rwx) : ORIGIN = 0x20006000, LENGTH = 0x20040000 - 0x20006000 +} + +SECTIONS +{ + . = ALIGN(4); + .svc_data : + { + PROVIDE(__start_svc_data = .); + KEEP(*(.svc_data)) + PROVIDE(__stop_svc_data = .); + } > RAM + + .fs_data : + { + PROVIDE(__start_fs_data = .); + KEEP(*(.fs_data)) + PROVIDE(__stop_fs_data = .); + } > RAM +} INSERT AFTER .data; + +INCLUDE "nrf52_common.ld" diff --git a/boards/nrf52840_s140_v7_extrafs.ld b/boards/nrf52840_s140_v7_extrafs.ld new file mode 100644 index 0000000..5956183 --- /dev/null +++ b/boards/nrf52840_s140_v7_extrafs.ld @@ -0,0 +1,38 @@ +/* Linker script to configure memory regions. */ + +SEARCH_DIR(.) +GROUP(-lgcc -lc -lnosys) + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x27000, LENGTH = 0xD4000 - 0x27000 + + /* SRAM required by Softdevice depend on + * - Attribute Table Size (Number of Services and Characteristics) + * - Vendor UUID count + * - Max ATT MTU + * - Concurrent connection peripheral + central + secure links + * - Event Len, HVN queue, Write CMD queue + */ + RAM (rwx) : ORIGIN = 0x20006000, LENGTH = 0x20040000 - 0x20006000 +} + +SECTIONS +{ + . = ALIGN(4); + .svc_data : + { + PROVIDE(__start_svc_data = .); + KEEP(*(.svc_data)) + PROVIDE(__stop_svc_data = .); + } > RAM + + .fs_data : + { + PROVIDE(__start_fs_data = .); + KEEP(*(.fs_data)) + PROVIDE(__stop_fs_data = .); + } > RAM +} INSERT AFTER .data; + +INCLUDE "nrf52_common.ld" diff --git a/variants/heltec_mesh_solar/platformio.ini b/variants/heltec_mesh_solar/platformio.ini index 18c4ac7..c5d8c3e 100644 --- a/variants/heltec_mesh_solar/platformio.ini +++ b/variants/heltec_mesh_solar/platformio.ini @@ -57,6 +57,8 @@ build_flags = [env:Heltec_mesh_solar_companion_radio_ble] extends = Heltec_mesh_solar +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Heltec_mesh_solar.build_flags} -D MAX_CONTACTS=350 @@ -75,6 +77,8 @@ lib_deps = [env:Heltec_mesh_solar_companion_radio_usb] extends = Heltec_mesh_solar +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Heltec_mesh_solar.build_flags} -D MAX_CONTACTS=350 diff --git a/variants/heltec_t114/platformio.ini b/variants/heltec_t114/platformio.ini index dec3282..4bbc05b 100644 --- a/variants/heltec_t114/platformio.ini +++ b/variants/heltec_t114/platformio.ini @@ -70,6 +70,8 @@ build_flags = [env:Heltec_t114_without_display_companion_radio_ble] extends = Heltec_t114 +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Heltec_t114.build_flags} -I examples/companion_radio/ui-new @@ -90,6 +92,8 @@ lib_deps = [env:Heltec_t114_without_display_companion_radio_usb] extends = Heltec_t114 +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Heltec_t114.build_flags} -I examples/companion_radio/ui-new @@ -158,6 +162,8 @@ build_flags = [env:Heltec_t114_companion_radio_ble] extends = Heltec_t114_with_display +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Heltec_t114_with_display.build_flags} -I examples/companion_radio/ui-new @@ -178,6 +184,8 @@ lib_deps = [env:Heltec_t114_companion_radio_usb] extends = Heltec_t114_with_display +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Heltec_t114_with_display.build_flags} -I examples/companion_radio/ui-new diff --git a/variants/ikoka_stick_nrf/platformio.ini b/variants/ikoka_stick_nrf/platformio.ini index 1f2bbfe..071d2d4 100644 --- a/variants/ikoka_stick_nrf/platformio.ini +++ b/variants/ikoka_stick_nrf/platformio.ini @@ -101,6 +101,8 @@ build_src_filter = ${nrf52840_xiao.build_src_filter} [ikoka_stick_nrf_companion_radio_ble] extends = ikoka_stick_nrf_baseboard +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${ikoka_stick_nrf_baseboard.build_flags} -D MAX_CONTACTS=350 @@ -121,6 +123,8 @@ lib_deps = [ikoka_stick_nrf_companion_radio_usb] extends = ikoka_stick_nrf_baseboard +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${ikoka_stick_nrf_baseboard.build_flags} -D MAX_CONTACTS=350 diff --git a/variants/lilygo_techo/platformio.ini b/variants/lilygo_techo/platformio.ini index 7d64fad..fb25326 100644 --- a/variants/lilygo_techo/platformio.ini +++ b/variants/lilygo_techo/platformio.ini @@ -78,6 +78,8 @@ build_flags = [env:LilyGo_T-Echo_companion_radio_ble] extends = LilyGo_T-Echo +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${LilyGo_T-Echo.build_flags} -I src/helpers/ui @@ -101,6 +103,8 @@ lib_deps = [env:LilyGo_T-Echo_companion_radio_usb] extends = LilyGo_T-Echo +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${LilyGo_T-Echo.build_flags} -I src/helpers/ui diff --git a/variants/mesh_pocket/platformio.ini b/variants/mesh_pocket/platformio.ini index 7c99615..1ed0d1e 100644 --- a/variants/mesh_pocket/platformio.ini +++ b/variants/mesh_pocket/platformio.ini @@ -67,6 +67,8 @@ build_flags = [env:Mesh_pocket_companion_radio_ble] extends = Mesh_pocket +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Mesh_pocket.build_flags} -I examples/companion_radio/ui-new @@ -89,6 +91,8 @@ lib_deps = [env:Mesh_pocket_companion_radio_usb] extends = Mesh_pocket +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Mesh_pocket.build_flags} -I examples/companion_radio/ui-new diff --git a/variants/minewsemi_me25ls01/platformio.ini b/variants/minewsemi_me25ls01/platformio.ini index 7188700..da234dd 100644 --- a/variants/minewsemi_me25ls01/platformio.ini +++ b/variants/minewsemi_me25ls01/platformio.ini @@ -50,6 +50,8 @@ lib_deps = ${nrf52840_me25ls01.lib_deps} [env:Minewsemi_me25ls01_companion_radio_ble] extends = me25ls01 +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${me25ls01.build_flags} -I examples/companion_radio/ui-orig -D MAX_CONTACTS=350 @@ -147,6 +149,8 @@ lib_deps = ${me25ls01.lib_deps} [env:Minewsemi_me25ls01_companion_radio_usb] extends = me25ls01 +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${me25ls01.build_flags} -I examples/companion_radio/ui-orig -D MAX_CONTACTS=350 diff --git a/variants/nano_g2_ultra/platformio.ini b/variants/nano_g2_ultra/platformio.ini index 163f431..1a9a700 100644 --- a/variants/nano_g2_ultra/platformio.ini +++ b/variants/nano_g2_ultra/platformio.ini @@ -31,6 +31,8 @@ upload_protocol = nrfutil [env:Nano_G2_Ultra_companion_radio_ble] extends = Nano_G2_Ultra +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Nano_G2_Ultra.build_flags} -I src/helpers/ui @@ -62,6 +64,8 @@ lib_deps = [env:Nano_G2_Ultra_companion_radio_usb] extends = Nano_G2_Ultra +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Nano_G2_Ultra.build_flags} -I src/helpers/ui diff --git a/variants/promicro/platformio.ini b/variants/promicro/platformio.ini index 5a70f7b..a65d3c6 100644 --- a/variants/promicro/platformio.ini +++ b/variants/promicro/platformio.ini @@ -86,6 +86,8 @@ lib_deps = ${Faketec.lib_deps} [env:Faketec_companion_radio_usb] extends = Faketec +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Faketec.build_flags} -I examples/companion_radio/ui-new -D MAX_CONTACTS=350 @@ -104,6 +106,8 @@ lib_deps = ${Faketec.lib_deps} [env:Faketec_companion_radio_ble] extends = Faketec +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${Faketec.build_flags} -I examples/companion_radio/ui-new -D MAX_CONTACTS=350 diff --git a/variants/rak4631/platformio.ini b/variants/rak4631/platformio.ini index 7e7d223..01f4d08 100644 --- a/variants/rak4631/platformio.ini +++ b/variants/rak4631/platformio.ini @@ -64,6 +64,8 @@ build_src_filter = ${rak4631.build_src_filter} [env:RAK_4631_companion_radio_usb] extends = rak4631 +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${rak4631.build_flags} -I examples/companion_radio/ui-new @@ -83,6 +85,8 @@ lib_deps = [env:RAK_4631_companion_radio_ble] extends = rak4631 +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${rak4631.build_flags} -I examples/companion_radio/ui-new diff --git a/variants/rak_wismesh_tag/platformio.ini b/variants/rak_wismesh_tag/platformio.ini index 572919e..ab14a68 100644 --- a/variants/rak_wismesh_tag/platformio.ini +++ b/variants/rak_wismesh_tag/platformio.ini @@ -66,6 +66,8 @@ build_src_filter = ${rak_wismesh_tag.build_src_filter} [env:RAK_WisMesh_Tag_companion_radio_usb] extends = rak_wismesh_tag +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${rak_wismesh_tag.build_flags} -I examples/companion_radio/ui-orig @@ -83,6 +85,8 @@ lib_deps = [env:RAK_WisMesh_Tag_companion_radio_ble] extends = rak_wismesh_tag +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${rak_wismesh_tag.build_flags} -I examples/companion_radio/ui-orig diff --git a/variants/sensecap_solar/platformio.ini b/variants/sensecap_solar/platformio.ini index 649ace8..0c8d5e1 100644 --- a/variants/sensecap_solar/platformio.ini +++ b/variants/sensecap_solar/platformio.ini @@ -74,6 +74,8 @@ build_src_filter = ${SenseCap_Solar.build_src_filter} [env:SenseCap_Solar_companion_radio_ble] extends = SenseCap_Solar +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${SenseCap_Solar.build_flags} -D MAX_CONTACTS=350 @@ -92,6 +94,8 @@ lib_deps = [env:SenseCap_Solar_companion_radio_usb] extends = SenseCap_Solar +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${SenseCap_Solar.build_flags} -D MAX_CONTACTS=350 diff --git a/variants/t1000-e/platformio.ini b/variants/t1000-e/platformio.ini index 1f7d60d..4f635f4 100644 --- a/variants/t1000-e/platformio.ini +++ b/variants/t1000-e/platformio.ini @@ -68,6 +68,8 @@ lib_deps = ${t1000-e.lib_deps} [env:t1000e_companion_radio_usb] extends = t1000-e +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${t1000-e.build_flags} -I examples/companion_radio/ui-orig -D MAX_CONTACTS=100 @@ -89,6 +91,8 @@ lib_deps = ${t1000-e.lib_deps} [env:t1000e_companion_radio_ble] extends = t1000-e +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${t1000-e.build_flags} -I examples/companion_radio/ui-orig -D MAX_CONTACTS=350 diff --git a/variants/thinknode_m1/platformio.ini b/variants/thinknode_m1/platformio.ini index eeeb692..97f2370 100644 --- a/variants/thinknode_m1/platformio.ini +++ b/variants/thinknode_m1/platformio.ini @@ -67,6 +67,8 @@ lib_deps = [env:ThinkNode_M1_companion_radio_ble] extends = ThinkNode_M1 +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${ThinkNode_M1.build_flags} -I src/helpers/ui @@ -99,6 +101,8 @@ lib_deps = [env:ThinkNode_M1_companion_radio_usb] extends = ThinkNode_M1 +board_build.ldscript = boards/nrf52840_s140_v6_extrafs.ld +board_upload.maximum_size = 712704 build_flags = ${ThinkNode_M1.build_flags} -I src/helpers/ui diff --git a/variants/wio-tracker-l1/platformio.ini b/variants/wio-tracker-l1/platformio.ini index 87670bd..a5debd7 100644 --- a/variants/wio-tracker-l1/platformio.ini +++ b/variants/wio-tracker-l1/platformio.ini @@ -55,6 +55,8 @@ lib_deps = ${WioTrackerL1.lib_deps} [env:WioTrackerL1_companion_radio_usb] extends = WioTrackerL1 +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${WioTrackerL1.build_flags} -I examples/companion_radio/ui-new -D MAX_CONTACTS=100 @@ -77,6 +79,8 @@ lib_deps = ${WioTrackerL1.lib_deps} [env:WioTrackerL1_companion_radio_ble] extends = WioTrackerL1 +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${WioTrackerL1.build_flags} -I examples/companion_radio/ui-new -D MAX_CONTACTS=350 diff --git a/variants/xiao_nrf52/platformio.ini b/variants/xiao_nrf52/platformio.ini index 1080747..1ce7186 100644 --- a/variants/xiao_nrf52/platformio.ini +++ b/variants/xiao_nrf52/platformio.ini @@ -57,6 +57,8 @@ upload_protocol = nrfutil [env:Xiao_nrf52_companion_radio_ble] extends = Xiao_nrf52 +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${Xiao_nrf52.build_flags} -D MAX_CONTACTS=350 @@ -76,6 +78,8 @@ lib_deps = [env:Xiao_nrf52_companion_radio_usb] extends = Xiao_nrf52 +board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld +board_upload.maximum_size = 708608 build_flags = ${Xiao_nrf52.build_flags} -D MAX_CONTACTS=350 From f92bd0db9e9229f6e82add6e9036663f6fdb0977 Mon Sep 17 00:00:00 2001 From: taco Date: Tue, 9 Sep 2025 17:00:29 +1000 Subject: [PATCH 39/50] fix inconsistencies across nrf companion roles --- variants/lilygo_techo/platformio.ini | 1 + variants/nano_g2_ultra/platformio.ini | 1 + variants/t1000-e/platformio.ini | 4 ++-- variants/wio-tracker-l1/platformio.ini | 5 +++-- variants/xiao_nrf52/platformio.ini | 1 + 5 files changed, 8 insertions(+), 4 deletions(-) diff --git a/variants/lilygo_techo/platformio.ini b/variants/lilygo_techo/platformio.ini index fb25326..6a71a7b 100644 --- a/variants/lilygo_techo/platformio.ini +++ b/variants/lilygo_techo/platformio.ini @@ -114,6 +114,7 @@ build_flags = -D OFFLINE_QUEUE_SIZE=256 -D UI_RECENT_LIST_SIZE=9 -D AUTO_SHUTDOWN_MILLIVOLTS=3300 + -D QSPIFLASH=1 build_src_filter = ${LilyGo_T-Echo.build_src_filter} +<../examples/companion_radio/*.cpp> +<../examples/companion_radio/ui-new/*.cpp> diff --git a/variants/nano_g2_ultra/platformio.ini b/variants/nano_g2_ultra/platformio.ini index 1a9a700..116a1f2 100644 --- a/variants/nano_g2_ultra/platformio.ini +++ b/variants/nano_g2_ultra/platformio.ini @@ -72,6 +72,7 @@ build_flags = -I examples/companion_radio/ui-new -D MAX_CONTACTS=350 -D MAX_GROUP_CHANNELS=40 + -D QSPIFLASH=1 -D OFFLINE_QUEUE_SIZE=256 -D DISPLAY_CLASS=SH1106Display -D PIN_BUZZER=4 diff --git a/variants/t1000-e/platformio.ini b/variants/t1000-e/platformio.ini index 4f635f4..69d9dcc 100644 --- a/variants/t1000-e/platformio.ini +++ b/variants/t1000-e/platformio.ini @@ -72,8 +72,8 @@ board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld board_upload.maximum_size = 708608 build_flags = ${t1000-e.build_flags} -I examples/companion_radio/ui-orig - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 -D OFFLINE_QUEUE_SIZE=256 diff --git a/variants/wio-tracker-l1/platformio.ini b/variants/wio-tracker-l1/platformio.ini index a5debd7..585e0ba 100644 --- a/variants/wio-tracker-l1/platformio.ini +++ b/variants/wio-tracker-l1/platformio.ini @@ -59,11 +59,12 @@ board_build.ldscript = boards/nrf52840_s140_v7_extrafs.ld board_upload.maximum_size = 708608 build_flags = ${WioTrackerL1.build_flags} -I examples/companion_radio/ui-new - -D MAX_CONTACTS=100 - -D MAX_GROUP_CHANNELS=8 + -D MAX_CONTACTS=350 + -D MAX_GROUP_CHANNELS=40 -D DISPLAY_CLASS=SH1106Display -D OFFLINE_QUEUE_SIZE=256 -D PIN_BUZZER=12 + -D QSPIFLASH=1 ; NOTE: DO NOT ENABLE --> -D MESH_PACKET_LOGGING=1 ; NOTE: DO NOT ENABLE --> -D MESH_DEBUG=1 build_src_filter = ${WioTrackerL1.build_src_filter} diff --git a/variants/xiao_nrf52/platformio.ini b/variants/xiao_nrf52/platformio.ini index 1ce7186..74ac6a5 100644 --- a/variants/xiao_nrf52/platformio.ini +++ b/variants/xiao_nrf52/platformio.ini @@ -84,6 +84,7 @@ build_flags = ${Xiao_nrf52.build_flags} -D MAX_CONTACTS=350 -D MAX_GROUP_CHANNELS=40 + -D QSPIFLASH=1 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${Xiao_nrf52.build_src_filter} From 5344f04d899cb0fadf5a36ef28b89af312ebd53f Mon Sep 17 00:00:00 2001 From: Scott Powell Date: Tue, 9 Sep 2025 18:46:30 +1000 Subject: [PATCH 40/50] * Repeater: slight refactor of 'bridge' instantiation --- examples/simple_repeater/main.cpp | 31 ++++++++++++++----------------- 1 file changed, 14 insertions(+), 17 deletions(-) diff --git a/examples/simple_repeater/main.cpp b/examples/simple_repeater/main.cpp index 4862d7d..e4d8a45 100644 --- a/examples/simple_repeater/main.cpp +++ b/examples/simple_repeater/main.cpp @@ -124,10 +124,6 @@ struct ClientInfo { #define MAX_CLIENTS 32 #endif -#ifdef WITH_BRIDGE -AbstractBridge* bridge; -#endif - struct NeighbourInfo { mesh::Identity id; uint32_t advert_timestamp; @@ -154,6 +150,11 @@ class MyMesh : public mesh::Mesh, public CommonCLICallbacks { float pending_bw; uint8_t pending_sf; uint8_t pending_cr; +#if defined(WITH_RS232_BRIDGE) + RS232Bridge bridge; +#elif defined(WITH_ESPNOW_BRIDGE) + ESPNowBridge bridge; +#endif ClientInfo* putClient(const mesh::Identity& id) { uint32_t min_time = 0xFFFFFFFF; @@ -315,7 +316,7 @@ protected: } void logTx(mesh::Packet* pkt, int len) override { #ifdef WITH_BRIDGE - bridge->onPacketTransmitted(pkt); + bridge.onPacketTransmitted(pkt); #endif if (_logging) { File f = openAppend(PACKET_LOG_FILE); @@ -581,16 +582,12 @@ public: MyMesh(mesh::MainBoard& board, mesh::Radio& radio, mesh::MillisecondClock& ms, mesh::RNG& rng, mesh::RTCClock& rtc, mesh::MeshTables& tables) : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) - { -#ifdef WITH_BRIDGE #if defined(WITH_RS232_BRIDGE) - bridge = new RS232Bridge(WITH_RS232_BRIDGE, _mgr, &rtc); + , bridge(WITH_RS232_BRIDGE, _mgr, &rtc) #elif defined(WITH_ESPNOW_BRIDGE) - bridge = new ESPNowBridge(_mgr, &rtc); -#else -#error "You must choose either RS232 or ESPNow bridge" -#endif + , bridge(_mgr, &rtc) #endif + { memset(known_clients, 0, sizeof(known_clients)); next_local_advert = next_flood_advert = 0; set_radio_at = revert_radio_at = 0; @@ -626,6 +623,10 @@ public: // load persisted prefs _cli.loadPrefs(_fs); + #ifdef WITH_BRIDGE + bridge.begin(); + #endif + radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); radio_set_tx_power(_prefs.tx_power_dbm); @@ -792,7 +793,7 @@ public: void loop() { #ifdef WITH_BRIDGE - bridge->loop(); + bridge.loop(); #endif mesh::Mesh::loop(); @@ -843,10 +844,6 @@ void setup() { Serial.begin(115200); delay(1000); -#ifdef WITH_BRIDGE - bridge->begin(); -#endif - board.begin(); #ifdef DISPLAY_CLASS From 3666cd72e5f583f2fdf8b5f0e2e41570c5835e2e Mon Sep 17 00:00:00 2001 From: Scott Powell Date: Tue, 9 Sep 2025 20:52:19 +1000 Subject: [PATCH 41/50] * room refactor: extracted MyMesh class --- examples/simple_room_server/MyMesh.cpp | 809 ++++++++++++++++++++ examples/simple_room_server/MyMesh.h | 220 ++++++ examples/simple_room_server/main.cpp | 971 +------------------------ 3 files changed, 1033 insertions(+), 967 deletions(-) create mode 100644 examples/simple_room_server/MyMesh.cpp create mode 100644 examples/simple_room_server/MyMesh.h diff --git a/examples/simple_room_server/MyMesh.cpp b/examples/simple_room_server/MyMesh.cpp new file mode 100644 index 0000000..83d1813 --- /dev/null +++ b/examples/simple_room_server/MyMesh.cpp @@ -0,0 +1,809 @@ +#include "MyMesh.h" + +#define REPLY_DELAY_MILLIS 1500 +#define PUSH_NOTIFY_DELAY_MILLIS 2000 +#define SYNC_PUSH_INTERVAL 1200 + +#define PUSH_ACK_TIMEOUT_FLOOD 12000 +#define PUSH_TIMEOUT_BASE 4000 +#define PUSH_ACK_TIMEOUT_FACTOR 2000 + +#define POST_SYNC_DELAY_SECS 6 + +#define CLIENT_KEEP_ALIVE_SECS 0 // Now Disabled (was 128) + +#define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS +#define REQ_TYPE_KEEP_ALIVE 0x02 +#define REQ_TYPE_GET_TELEMETRY_DATA 0x03 + +#define RESP_SERVER_LOGIN_OK 0 // response to ANON_REQ + +struct ServerStats { + uint16_t batt_milli_volts; + uint16_t curr_tx_queue_len; + int16_t noise_floor; + int16_t last_rssi; + uint32_t n_packets_recv; + uint32_t n_packets_sent; + uint32_t total_air_time_secs; + uint32_t total_up_time_secs; + uint32_t n_sent_flood, n_sent_direct; + uint32_t n_recv_flood, n_recv_direct; + uint16_t err_events; // was 'n_full_events' + int16_t last_snr; // x 4 + uint16_t n_direct_dups, n_flood_dups; + uint16_t n_posted, n_post_push; +}; + +ClientInfo *MyMesh::putClient(const mesh::Identity &id) { + for (int i = 0; i < num_clients; i++) { + if (id.matches(known_clients[i].id)) return &known_clients[i]; // already known + } + ClientInfo *newClient; + if (num_clients < MAX_CLIENTS) { + newClient = &known_clients[num_clients++]; + } else { // table is currently full + // evict least active client + uint32_t oldest_timestamp = 0xFFFFFFFF; + newClient = &known_clients[0]; + for (int i = 0; i < num_clients; i++) { + auto c = &known_clients[i]; + if (c->last_activity < oldest_timestamp) { + oldest_timestamp = c->last_activity; + newClient = c; + } + } + } + newClient->id = id; + newClient->out_path_len = -1; // initially out_path is unknown + newClient->last_timestamp = 0; + return newClient; +} + +void MyMesh::evict(ClientInfo *client) { + client->last_activity = 0; // this slot will now be re-used (will be oldest) + memset(client->id.pub_key, 0, sizeof(client->id.pub_key)); + memset(client->secret, 0, sizeof(client->secret)); + client->pending_ack = 0; +} + +void MyMesh::addPost(ClientInfo *client, const char *postData) { + // TODO: suggested postData format: /<descrption> + posts[next_post_idx].author = client->id; // add to cyclic queue + StrHelper::strncpy(posts[next_post_idx].text, postData, MAX_POST_TEXT_LEN); + + posts[next_post_idx].post_timestamp = getRTCClock()->getCurrentTimeUnique(); + next_post_idx = (next_post_idx + 1) % MAX_UNSYNCED_POSTS; + + next_push = futureMillis(PUSH_NOTIFY_DELAY_MILLIS); + _num_posted++; // stats +} + +void MyMesh::pushPostToClient(ClientInfo *client, PostInfo &post) { + int len = 0; + memcpy(&reply_data[len], &post.post_timestamp, 4); + len += 4; // this is a PAST timestamp... but should be accepted by client + + uint8_t attempt; + getRNG()->random(&attempt, 1); // need this for re-tries, so packet hash (and ACK) will be different + reply_data[len++] = (TXT_TYPE_SIGNED_PLAIN << 2) | (attempt & 3); // 'signed' plain text + + // encode prefix of post.author.pub_key + memcpy(&reply_data[len], post.author.pub_key, 4); + len += 4; // just first 4 bytes + + int text_len = strlen(post.text); + memcpy(&reply_data[len], post.text, text_len); + len += text_len; + + // calc expected ACK reply + mesh::Utils::sha256((uint8_t *)&client->pending_ack, 4, reply_data, len, client->id.pub_key, PUB_KEY_SIZE); + client->push_post_timestamp = post.post_timestamp; + + auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, client->secret, reply_data, len); + if (reply) { + if (client->out_path_len < 0) { + sendFlood(reply); + client->ack_timeout = futureMillis(PUSH_ACK_TIMEOUT_FLOOD); + } else { + sendDirect(reply, client->out_path, client->out_path_len); + client->ack_timeout = + futureMillis(PUSH_TIMEOUT_BASE + PUSH_ACK_TIMEOUT_FACTOR * (client->out_path_len + 1)); + } + _num_post_pushes++; // stats + } else { + client->pending_ack = 0; + MESH_DEBUG_PRINTLN("Unable to push post to client"); + } +} + +uint8_t MyMesh::getUnsyncedCount(ClientInfo *client) { + uint8_t count = 0; + for (int k = 0; k < MAX_UNSYNCED_POSTS; k++) { + if (posts[k].post_timestamp > client->sync_since // is new post for this Client? + && !posts[k].author.matches(client->id)) { // don't push posts to the author + count++; + } + } + return count; +} + +bool MyMesh::processAck(const uint8_t *data) { + for (int i = 0; i < num_clients; i++) { + auto client = &known_clients[i]; + if (client->pending_ack && memcmp(data, &client->pending_ack, 4) == 0) { // got an ACK from Client! + client->pending_ack = 0; // clear this, so next push can happen + client->push_failures = 0; + client->sync_since = client->push_post_timestamp; // advance Client's SINCE timestamp, to sync next post + return true; + } + } + return false; +} + +mesh::Packet *MyMesh::createSelfAdvert() { + uint8_t app_data[MAX_ADVERT_DATA_SIZE]; + uint8_t app_data_len; + { + AdvertDataBuilder builder(ADV_TYPE_ROOM, _prefs.node_name, _prefs.node_lat, _prefs.node_lon); + app_data_len = builder.encodeTo(app_data); + } + + return createAdvert(self_id, app_data, app_data_len); +} + +File MyMesh::openAppend(const char *fname) { +#if defined(NRF52_PLATFORM) + return _fs->open(fname, FILE_O_WRITE); +#elif defined(RP2040_PLATFORM) + return _fs->open(fname, "a"); +#else + return _fs->open(fname, "a", true); +#endif +} + +int MyMesh::handleRequest(ClientInfo *sender, uint32_t sender_timestamp, uint8_t *payload, + size_t payload_len) { + // uint32_t now = getRTCClock()->getCurrentTimeUnique(); + // memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp + memcpy(reply_data, &sender_timestamp, 4); // reflect sender_timestamp back in response packet (kind of like a 'tag') + + switch (payload[0]) { + case REQ_TYPE_GET_STATUS: { + ServerStats stats; + stats.batt_milli_volts = board.getBattMilliVolts(); + stats.curr_tx_queue_len = _mgr->getOutboundCount(0xFFFFFFFF); + stats.noise_floor = (int16_t)_radio->getNoiseFloor(); + stats.last_rssi = (int16_t)radio_driver.getLastRSSI(); + stats.n_packets_recv = radio_driver.getPacketsRecv(); + stats.n_packets_sent = radio_driver.getPacketsSent(); + stats.total_air_time_secs = getTotalAirTime() / 1000; + stats.total_up_time_secs = _ms->getMillis() / 1000; + stats.n_sent_flood = getNumSentFlood(); + stats.n_sent_direct = getNumSentDirect(); + stats.n_recv_flood = getNumRecvFlood(); + stats.n_recv_direct = getNumRecvDirect(); + stats.err_events = _err_flags; + stats.last_snr = (int16_t)(radio_driver.getLastSNR() * 4); + stats.n_direct_dups = ((SimpleMeshTables *)getTables())->getNumDirectDups(); + stats.n_flood_dups = ((SimpleMeshTables *)getTables())->getNumFloodDups(); + stats.n_posted = _num_posted; + stats.n_post_push = _num_post_pushes; + + memcpy(&reply_data[4], &stats, sizeof(stats)); + return 4 + sizeof(stats); + } + + case REQ_TYPE_GET_TELEMETRY_DATA: { + uint8_t perm_mask = ~(payload[1]); // NEW: first reserved byte (of 4), is now inverse mask to apply to permissions + + telemetry.reset(); + telemetry.addVoltage(TELEM_CHANNEL_SELF, (float)board.getBattMilliVolts() / 1000.0f); + // query other sensors -- target specific + sensors.querySensors((sender->permission == RoomPermission::ADMIN ? 0xFF : 0x00) & perm_mask, telemetry); + + uint8_t tlen = telemetry.getSize(); + memcpy(&reply_data[4], telemetry.getBuffer(), tlen); + return 4 + tlen; // reply_len + } + } + return 0; // unknown command +} + +void MyMesh::logRxRaw(float snr, float rssi, const uint8_t raw[], int len) { +#if MESH_PACKET_LOGGING + Serial.print(getLogDateTime()); + Serial.print(" RAW: "); + mesh::Utils::printHex(Serial, raw, len); + Serial.println(); +#endif +} + +void MyMesh::logRx(mesh::Packet *pkt, int len, float score) { + if (_logging) { + File f = openAppend(PACKET_LOG_FILE); + if (f) { + f.print(getLogDateTime()); + f.printf(": RX, len=%d (type=%d, route=%s, payload_len=%d) SNR=%d RSSI=%d score=%d", len, + pkt->getPayloadType(), pkt->isRouteDirect() ? "D" : "F", pkt->payload_len, + (int)_radio->getLastSNR(), (int)_radio->getLastRSSI(), (int)(score * 1000)); + + if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH || pkt->getPayloadType() == PAYLOAD_TYPE_REQ || + pkt->getPayloadType() == PAYLOAD_TYPE_RESPONSE || pkt->getPayloadType() == PAYLOAD_TYPE_TXT_MSG) { + f.printf(" [%02X -> %02X]\n", (uint32_t)pkt->payload[1], (uint32_t)pkt->payload[0]); + } else { + f.printf("\n"); + } + f.close(); + } + } +} +void MyMesh::logTx(mesh::Packet *pkt, int len) { + if (_logging) { + File f = openAppend(PACKET_LOG_FILE); + if (f) { + f.print(getLogDateTime()); + f.printf(": TX, len=%d (type=%d, route=%s, payload_len=%d)", len, pkt->getPayloadType(), + pkt->isRouteDirect() ? "D" : "F", pkt->payload_len); + + if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH || pkt->getPayloadType() == PAYLOAD_TYPE_REQ || + pkt->getPayloadType() == PAYLOAD_TYPE_RESPONSE || pkt->getPayloadType() == PAYLOAD_TYPE_TXT_MSG) { + f.printf(" [%02X -> %02X]\n", (uint32_t)pkt->payload[1], (uint32_t)pkt->payload[0]); + } else { + f.printf("\n"); + } + f.close(); + } + } +} +void MyMesh::logTxFail(mesh::Packet *pkt, int len) { + if (_logging) { + File f = openAppend(PACKET_LOG_FILE); + if (f) { + f.print(getLogDateTime()); + f.printf(": TX FAIL!, len=%d (type=%d, route=%s, payload_len=%d)\n", len, pkt->getPayloadType(), + pkt->isRouteDirect() ? "D" : "F", pkt->payload_len); + f.close(); + } + } +} + +int MyMesh::calcRxDelay(float score, uint32_t air_time) const { + if (_prefs.rx_delay_base <= 0.0f) return 0; + return (int)((pow(_prefs.rx_delay_base, 0.85f - score) - 1.0) * air_time); +} + +const char *MyMesh::getLogDateTime() { + static char tmp[32]; + uint32_t now = getRTCClock()->getCurrentTime(); + DateTime dt = DateTime(now); + sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), + dt.year()); + return tmp; +} + +uint32_t MyMesh::getRetransmitDelay(const mesh::Packet *packet) { + uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.tx_delay_factor); + return getRNG()->nextInt(0, 6) * t; +} +uint32_t MyMesh::getDirectRetransmitDelay(const mesh::Packet *packet) { + uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.direct_tx_delay_factor); + return getRNG()->nextInt(0, 6) * t; +} + +bool MyMesh::allowPacketForward(const mesh::Packet *packet) { + if (_prefs.disable_fwd) return false; + if (packet->isRouteFlood() && packet->path_len >= _prefs.flood_max) return false; + return true; +} + +void MyMesh::onAnonDataRecv(mesh::Packet *packet, const uint8_t *secret, const mesh::Identity &sender, + uint8_t *data, size_t len) { + if (packet->getPayloadType() == PAYLOAD_TYPE_ANON_REQ) { // received an initial request by a possible admin + // client (unknown at this stage) + uint32_t sender_timestamp, sender_sync_since; + memcpy(&sender_timestamp, data, 4); + memcpy(&sender_sync_since, &data[4], 4); // sender's "sync messags SINCE x" timestamp + + RoomPermission perm; + data[len] = 0; // ensure null terminator + if (strcmp((char *)&data[8], _prefs.password) == 0) { // check for valid admin password + perm = RoomPermission::ADMIN; + } else { + if (strcmp((char *)&data[8], _prefs.guest_password) == 0) { // check the room/public password + perm = RoomPermission::GUEST; + } else if (_prefs.allow_read_only) { + perm = RoomPermission::READ_ONLY; + } else { + MESH_DEBUG_PRINTLN("Incorrect room password"); + return; // no response. Client will timeout + } + } + + auto client = putClient(sender); // add to known clients (if not already known) + if (sender_timestamp <= client->last_timestamp) { + MESH_DEBUG_PRINTLN("possible replay attack!"); + return; + } + + MESH_DEBUG_PRINTLN("Login success!"); + client->permission = perm; + client->last_timestamp = sender_timestamp; + client->sync_since = sender_sync_since; + client->pending_ack = 0; + client->push_failures = 0; + memcpy(client->secret, secret, PUB_KEY_SIZE); + + uint32_t now = getRTCClock()->getCurrentTime(); + client->last_activity = now; + + now = getRTCClock()->getCurrentTimeUnique(); + memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp + // TODO: maybe reply with count of messages waiting to be synced for THIS client? + reply_data[4] = RESP_SERVER_LOGIN_OK; + reply_data[5] = (CLIENT_KEEP_ALIVE_SECS >> 4); // NEW: recommended keep-alive interval (secs / 16) + reply_data[6] = (perm == RoomPermission::ADMIN ? 1 : (perm == RoomPermission::GUEST ? 0 : 2)); + reply_data[7] = getUnsyncedCount(client); // NEW + memcpy(&reply_data[8], "OK", 2); // REVISIT: not really needed + + next_push = futureMillis(PUSH_NOTIFY_DELAY_MILLIS); // delay next push, give RESPONSE packet time to arrive first + + if (packet->isRouteFlood()) { + // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response + mesh::Packet *path = createPathReturn(sender, client->secret, packet->path, packet->path_len, + PAYLOAD_TYPE_RESPONSE, reply_data, 8 + 2); + if (path) sendFlood(path, SERVER_RESPONSE_DELAY); + } else { + mesh::Packet *reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, client->secret, reply_data, 8 + 2); + if (reply) { + if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT + sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); + } else { + sendFlood(reply, SERVER_RESPONSE_DELAY); + } + } + } + } +} + +int MyMesh::searchPeersByHash(const uint8_t *hash) { + int n = 0; + for (int i = 0; i < num_clients; i++) { + if (known_clients[i].id.isHashMatch(hash)) { + matching_peer_indexes[n++] = i; // store the INDEXES of matching contacts (for subsequent 'peer' methods) + } + } + return n; +} + +void MyMesh::getPeerSharedSecret(uint8_t *dest_secret, int peer_idx) { + int i = matching_peer_indexes[peer_idx]; + if (i >= 0 && i < num_clients) { + // lookup pre-calculated shared_secret + memcpy(dest_secret, known_clients[i].secret, PUB_KEY_SIZE); + } else { + MESH_DEBUG_PRINTLN("getPeerSharedSecret: Invalid peer idx: %d", i); + } +} + +void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx, const uint8_t *secret, + uint8_t *data, size_t len) { + int i = matching_peer_indexes[sender_idx]; + if (i < 0 || i >= num_clients) { // get from our known_clients table (sender SHOULD already be known in this context) + MESH_DEBUG_PRINTLN("onPeerDataRecv: invalid peer idx: %d", i); + return; + } + auto client = &known_clients[i]; + if (type == PAYLOAD_TYPE_TXT_MSG && len > 5) { // a CLI command or new Post + uint32_t sender_timestamp; + memcpy(&sender_timestamp, data, 4); // timestamp (by sender's RTC clock - which could be wrong) + uint flags = (data[4] >> 2); // message attempt number, and other flags + + if (!(flags == TXT_TYPE_PLAIN || flags == TXT_TYPE_CLI_DATA)) { + MESH_DEBUG_PRINTLN("onPeerDataRecv: unsupported command flags received: flags=%02x", (uint32_t)flags); + } else if (sender_timestamp >= client->last_timestamp) { // prevent replay attacks, but send Acks for retries + bool is_retry = (sender_timestamp == client->last_timestamp); + client->last_timestamp = sender_timestamp; + + uint32_t now = getRTCClock()->getCurrentTimeUnique(); + client->last_activity = now; + client->push_failures = 0; // reset so push can resume (if prev failed) + + // len can be > original length, but 'text' will be padded with zeroes + data[len] = 0; // need to make a C string again, with null terminator + + uint32_t ack_hash; // calc truncated hash of the message timestamp + text + sender pub_key, to prove to + // sender that we got it + mesh::Utils::sha256((uint8_t *)&ack_hash, 4, data, 5 + strlen((char *)&data[5]), client->id.pub_key, + PUB_KEY_SIZE); + + uint8_t temp[166]; + bool send_ack; + if (flags == TXT_TYPE_CLI_DATA) { + if (client->permission == RoomPermission::ADMIN) { + if (is_retry) { + temp[5] = 0; // no reply + } else { + handleCommand(sender_timestamp, (char *)&data[5], (char *)&temp[5]); + temp[4] = (TXT_TYPE_CLI_DATA << 2); // attempt and flags, (NOTE: legacy was: TXT_TYPE_PLAIN) + } + send_ack = false; + } else { + temp[5] = 0; // no reply + send_ack = false; // and no ACK... user shoudn't be sending these + } + } else { // TXT_TYPE_PLAIN + if (client->permission == RoomPermission::READ_ONLY) { + temp[5] = 0; // no reply + send_ack = false; // no ACK + } else { + if (!is_retry) { + addPost(client, (const char *)&data[5]); + } + temp[5] = 0; // no reply (ACK is enough) + send_ack = true; + } + } + + uint32_t delay_millis; + if (send_ack) { + if (client->out_path_len < 0) { + mesh::Packet *ack = createAck(ack_hash); + if (ack) sendFlood(ack, TXT_ACK_DELAY); + delay_millis = TXT_ACK_DELAY + REPLY_DELAY_MILLIS; + } else { + uint32_t d = TXT_ACK_DELAY; + if (getExtraAckTransmitCount() > 0) { + mesh::Packet *a1 = createMultiAck(ack_hash, 1); + if (a1) sendDirect(a1, client->out_path, client->out_path_len, d); + d += 300; + } + + mesh::Packet *a2 = createAck(ack_hash); + if (a2) sendDirect(a2, client->out_path, client->out_path_len, d); + delay_millis = d + REPLY_DELAY_MILLIS; + } + } else { + delay_millis = 0; + } + + int text_len = strlen((char *)&temp[5]); + if (text_len > 0) { + if (now == sender_timestamp) { + // WORKAROUND: the two timestamps need to be different, in the CLI view + now++; + } + memcpy(temp, &now, 4); // mostly an extra blob to help make packet_hash unique + + // calc expected ACK reply + // mesh::Utils::sha256((uint8_t *)&expected_ack_crc, 4, temp, 5 + text_len, self_id.pub_key, + // PUB_KEY_SIZE); + + auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, secret, temp, 5 + text_len); + if (reply) { + if (client->out_path_len < 0) { + sendFlood(reply, delay_millis + SERVER_RESPONSE_DELAY); + } else { + sendDirect(reply, client->out_path, client->out_path_len, delay_millis + SERVER_RESPONSE_DELAY); + } + } + } + } else { + MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); + } + } else if (type == PAYLOAD_TYPE_REQ && len >= 5) { + uint32_t sender_timestamp; + memcpy(&sender_timestamp, data, 4); // timestamp (by sender's RTC clock - which could be wrong) + if (sender_timestamp < client->last_timestamp) { // prevent replay attacks + MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); + } else { + client->last_timestamp = sender_timestamp; + + uint32_t now = getRTCClock()->getCurrentTime(); + client->last_activity = now; // <-- THIS will keep client connection alive + client->push_failures = 0; // reset so push can resume (if prev failed) + + if (data[4] == REQ_TYPE_KEEP_ALIVE && packet->isRouteDirect()) { // request type + uint32_t forceSince = 0; + if (len >= 9) { // optional - last post_timestamp client received + memcpy(&forceSince, &data[5], 4); // NOTE: this may be 0, if part of decrypted PADDING! + } else { + memcpy(&data[5], &forceSince, 4); // make sure there are zeroes in payload (for ack_hash calc below) + } + if (forceSince > 0) { + client->sync_since = forceSince; // force-update the 'sync since' + } + + client->pending_ack = 0; + + // TODO: Throttle KEEP_ALIVE requests! + // if client sends too quickly, evict() + + // RULE: only send keep_alive response DIRECT! + if (client->out_path_len >= 0) { + uint32_t ack_hash; // calc ACK to prove to sender that we got request + mesh::Utils::sha256((uint8_t *)&ack_hash, 4, data, 9, client->id.pub_key, PUB_KEY_SIZE); + + auto reply = createAck(ack_hash); + if (reply) { + reply->payload[reply->payload_len++] = getUnsyncedCount(client); // NEW: add unsynced counter to end of ACK packet + sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); + } + } + } else { + int reply_len = handleRequest(client, sender_timestamp, &data[4], len - 4); + if (reply_len > 0) { // valid command + if (packet->isRouteFlood()) { + // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response + mesh::Packet *path = createPathReturn(client->id, secret, packet->path, packet->path_len, + PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); + if (path) sendFlood(path, SERVER_RESPONSE_DELAY); + } else { + mesh::Packet *reply = createDatagram(PAYLOAD_TYPE_RESPONSE, client->id, secret, reply_data, reply_len); + if (reply) { + if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT + sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); + } else { + sendFlood(reply, SERVER_RESPONSE_DELAY); + } + } + } + } + } + } + } +} + +bool MyMesh::onPeerPathRecv(mesh::Packet *packet, int sender_idx, const uint8_t *secret, uint8_t *path, + uint8_t path_len, uint8_t extra_type, uint8_t *extra, uint8_t extra_len) { + // TODO: prevent replay attacks + int i = matching_peer_indexes[sender_idx]; + + if (i >= 0 && i < num_clients) { // get from our known_clients table (sender SHOULD already be known in this context) + MESH_DEBUG_PRINTLN("PATH to client, path_len=%d", (uint32_t)path_len); + auto client = &known_clients[i]; + memcpy(client->out_path, path, client->out_path_len = path_len); // store a copy of path, for sendDirect() + } else { + MESH_DEBUG_PRINTLN("onPeerPathRecv: invalid peer idx: %d", i); + } + + if (extra_type == PAYLOAD_TYPE_ACK && extra_len >= 4) { + // also got an encoded ACK! + processAck(extra); + } + + // NOTE: no reciprocal path send!! + return false; +} + +void MyMesh::onAckRecv(mesh::Packet *packet, uint32_t ack_crc) { + if (processAck((uint8_t *)&ack_crc)) { + packet->markDoNotRetransmit(); // ACK was for this node, so don't retransmit + } +} + +MyMesh::MyMesh(mesh::MainBoard &board, mesh::Radio &radio, mesh::MillisecondClock &ms, mesh::RNG &rng, + mesh::RTCClock &rtc, mesh::MeshTables &tables) + : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), + _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) { + next_local_advert = next_flood_advert = 0; + _logging = false; + set_radio_at = revert_radio_at = 0; + + // defaults + memset(&_prefs, 0, sizeof(_prefs)); + _prefs.airtime_factor = 1.0; // one half + _prefs.rx_delay_base = 0.0f; // off by default, was 10.0 + _prefs.tx_delay_factor = 0.5f; // was 0.25f; + StrHelper::strncpy(_prefs.node_name, ADVERT_NAME, sizeof(_prefs.node_name)); + _prefs.node_lat = ADVERT_LAT; + _prefs.node_lon = ADVERT_LON; + StrHelper::strncpy(_prefs.password, ADMIN_PASSWORD, sizeof(_prefs.password)); + _prefs.freq = LORA_FREQ; + _prefs.sf = LORA_SF; + _prefs.bw = LORA_BW; + _prefs.cr = LORA_CR; + _prefs.tx_power_dbm = LORA_TX_POWER; + _prefs.disable_fwd = 1; + _prefs.advert_interval = 1; // default to 2 minutes for NEW installs + _prefs.flood_advert_interval = 12; // 12 hours + _prefs.flood_max = 64; + _prefs.interference_threshold = 0; // disabled +#ifdef ROOM_PASSWORD + StrHelper::strncpy(_prefs.guest_password, ROOM_PASSWORD, sizeof(_prefs.guest_password)); +#endif + + num_clients = 0; + next_post_idx = 0; + next_client_idx = 0; + next_push = 0; + memset(posts, 0, sizeof(posts)); + _num_posted = _num_post_pushes = 0; +} + +void MyMesh::begin(FILESYSTEM *fs) { + mesh::Mesh::begin(); + _fs = fs; + // load persisted prefs + _cli.loadPrefs(_fs); + + radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); + radio_set_tx_power(_prefs.tx_power_dbm); + + updateAdvertTimer(); + updateFloodAdvertTimer(); +} + +void MyMesh::applyTempRadioParams(float freq, float bw, uint8_t sf, uint8_t cr, int timeout_mins) { + set_radio_at = futureMillis(2000); // give CLI reply some time to be sent back, before applying temp radio params + pending_freq = freq; + pending_bw = bw; + pending_sf = sf; + pending_cr = cr; + + revert_radio_at = futureMillis(2000 + timeout_mins * 60 * 1000); // schedule when to revert radio params +} + +bool MyMesh::formatFileSystem() { +#if defined(NRF52_PLATFORM) + return InternalFS.format(); +#elif defined(RP2040_PLATFORM) + return LittleFS.format(); +#elif defined(ESP32) + return SPIFFS.format(); +#else +#error "need to implement file system erase" + return false; +#endif +} + +void MyMesh::sendSelfAdvertisement(int delay_millis) { + mesh::Packet *pkt = createSelfAdvert(); + if (pkt) { + sendFlood(pkt, delay_millis); + } else { + MESH_DEBUG_PRINTLN("ERROR: unable to create advertisement packet!"); + } +} + +void MyMesh::updateAdvertTimer() { + if (_prefs.advert_interval > 0) { // schedule local advert timer + next_local_advert = futureMillis((uint32_t)_prefs.advert_interval * 2 * 60 * 1000); + } else { + next_local_advert = 0; // stop the timer + } +} +void MyMesh::updateFloodAdvertTimer() { + if (_prefs.flood_advert_interval > 0) { // schedule flood advert timer + next_flood_advert = futureMillis(((uint32_t)_prefs.flood_advert_interval) * 60 * 60 * 1000); + } else { + next_flood_advert = 0; // stop the timer + } +} + +void MyMesh::dumpLogFile() { +#if defined(RP2040_PLATFORM) + File f = _fs->open(PACKET_LOG_FILE, "r"); +#else + File f = _fs->open(PACKET_LOG_FILE); +#endif + if (f) { + while (f.available()) { + int c = f.read(); + if (c < 0) break; + Serial.print((char)c); + } + f.close(); + } +} + +void MyMesh::setTxPower(uint8_t power_dbm) { + radio_set_tx_power(power_dbm); +} + +void MyMesh::saveIdentity(const mesh::LocalIdentity &new_id) { + self_id = new_id; +#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) + IdentityStore store(*_fs, ""); +#elif defined(ESP32) + IdentityStore store(*_fs, "/identity"); +#elif defined(RP2040_PLATFORM) + IdentityStore store(*_fs, "/identity"); +#else +#error "need to define saveIdentity()" +#endif + store.save("_main", self_id); +} + +void MyMesh::clearStats() { + radio_driver.resetStats(); + resetStats(); + ((SimpleMeshTables *)getTables())->resetStats(); +} + +void MyMesh::handleCommand(uint32_t sender_timestamp, char *command, char *reply) { + while (*command == ' ') + command++; // skip leading spaces + + if (strlen(command) > 4 && command[2] == '|') { // optional prefix (for companion radio CLI) + memcpy(reply, command, 3); // reflect the prefix back + reply += 3; + command += 3; + } + + _cli.handleCommand(sender_timestamp, command, reply); // common CLI commands +} + +void MyMesh::loop() { + mesh::Mesh::loop(); + + if (millisHasNowPassed(next_push) && num_clients > 0) { + // check for ACK timeouts + for (int i = 0; i < num_clients; i++) { + auto c = &known_clients[i]; + if (c->pending_ack && millisHasNowPassed(c->ack_timeout)) { + c->push_failures++; + c->pending_ack = 0; // reset (TODO: keep prev expected_ack's in a list, incase they arrive LATER, after we retry) + MESH_DEBUG_PRINTLN("pending ACK timed out: push_failures: %d", (uint32_t)c->push_failures); + } + } + // check next Round-Robin client, and sync next new post + auto client = &known_clients[next_client_idx]; + bool did_push = false; + if (client->pending_ack == 0 && client->last_activity != 0 && + client->push_failures < 3) { // not already waiting for ACK, AND not evicted, AND retries not max + MESH_DEBUG_PRINTLN("loop - checking for client %02X", (uint32_t)client->id.pub_key[0]); + uint32_t now = getRTCClock()->getCurrentTime(); + for (int k = 0, idx = next_post_idx; k < MAX_UNSYNCED_POSTS; k++) { + auto p = &posts[idx]; + if (now >= p->post_timestamp + POST_SYNC_DELAY_SECS && + p->post_timestamp > client->sync_since // is new post for this Client? + && !p->author.matches(client->id)) { // don't push posts to the author + // push this post to Client, then wait for ACK + pushPostToClient(client, *p); + did_push = true; + MESH_DEBUG_PRINTLN("loop - pushed to client %02X: %s", (uint32_t)client->id.pub_key[0], p->text); + break; + } + idx = (idx + 1) % MAX_UNSYNCED_POSTS; // wrap to start of cyclic queue + } + } else { + MESH_DEBUG_PRINTLN("loop - skipping busy (or evicted) client %02X", (uint32_t)client->id.pub_key[0]); + } + next_client_idx = (next_client_idx + 1) % num_clients; // round robin polling for each client + + if (did_push) { + next_push = futureMillis(SYNC_PUSH_INTERVAL); + } else { + // were no unsynced posts for curr client, so proccess next client much quicker! (in next loop()) + next_push = futureMillis(SYNC_PUSH_INTERVAL / 8); + } + } + + if (next_flood_advert && millisHasNowPassed(next_flood_advert)) { + mesh::Packet *pkt = createSelfAdvert(); + if (pkt) sendFlood(pkt); + + updateFloodAdvertTimer(); // schedule next flood advert + updateAdvertTimer(); // also schedule local advert (so they don't overlap) + } else if (next_local_advert && millisHasNowPassed(next_local_advert)) { + mesh::Packet *pkt = createSelfAdvert(); + if (pkt) sendZeroHop(pkt); + + updateAdvertTimer(); // schedule next local advert + } + + if (set_radio_at && millisHasNowPassed(set_radio_at)) { // apply pending (temporary) radio params + set_radio_at = 0; // clear timer + radio_set_params(pending_freq, pending_bw, pending_sf, pending_cr); + MESH_DEBUG_PRINTLN("Temp radio params"); + } + + if (revert_radio_at && millisHasNowPassed(revert_radio_at)) { // revert radio params to orig + revert_radio_at = 0; // clear timer + radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); + MESH_DEBUG_PRINTLN("Radio params restored"); + } + + // TODO: periodically check for OLD/inactive entries in known_clients[], and evict +} diff --git a/examples/simple_room_server/MyMesh.h b/examples/simple_room_server/MyMesh.h new file mode 100644 index 0000000..945cca7 --- /dev/null +++ b/examples/simple_room_server/MyMesh.h @@ -0,0 +1,220 @@ +#pragma once + +#include <Arduino.h> // needed for PlatformIO +#include <Mesh.h> + +#if defined(NRF52_PLATFORM) + #include <InternalFileSystem.h> +#elif defined(RP2040_PLATFORM) + #include <LittleFS.h> +#elif defined(ESP32) + #include <SPIFFS.h> +#endif + +#include <helpers/ArduinoHelpers.h> +#include <helpers/StaticPoolPacketManager.h> +#include <helpers/SimpleMeshTables.h> +#include <helpers/IdentityStore.h> +#include <helpers/AdvertDataHelpers.h> +#include <helpers/TxtDataHelpers.h> +#include <helpers/CommonCLI.h> +#include <RTClib.h> +#include <target.h> + +/* ------------------------------ Config -------------------------------- */ + +#ifndef FIRMWARE_BUILD_DATE + #define FIRMWARE_BUILD_DATE "1 Sep 2025" +#endif + +#ifndef FIRMWARE_VERSION + #define FIRMWARE_VERSION "v1.8.1" +#endif + +#ifndef LORA_FREQ + #define LORA_FREQ 915.0 +#endif +#ifndef LORA_BW + #define LORA_BW 250 +#endif +#ifndef LORA_SF + #define LORA_SF 10 +#endif +#ifndef LORA_CR + #define LORA_CR 5 +#endif +#ifndef LORA_TX_POWER + #define LORA_TX_POWER 20 +#endif + +#ifndef ADVERT_NAME + #define ADVERT_NAME "Test BBS" +#endif +#ifndef ADVERT_LAT + #define ADVERT_LAT 0.0 +#endif +#ifndef ADVERT_LON + #define ADVERT_LON 0.0 +#endif + +#ifndef ADMIN_PASSWORD + #define ADMIN_PASSWORD "password" +#endif + +#ifndef MAX_CLIENTS + #define MAX_CLIENTS 32 +#endif + +#ifndef MAX_UNSYNCED_POSTS + #define MAX_UNSYNCED_POSTS 32 +#endif + +#ifndef SERVER_RESPONSE_DELAY + #define SERVER_RESPONSE_DELAY 300 +#endif + +#ifndef TXT_ACK_DELAY + #define TXT_ACK_DELAY 200 +#endif + +#define FIRMWARE_ROLE "room_server" + +#define PACKET_LOG_FILE "/packet_log" + +enum RoomPermission { + ADMIN, + GUEST, + READ_ONLY +}; + +struct ClientInfo { + mesh::Identity id; + uint32_t last_timestamp; // by THEIR clock + uint32_t last_activity; // by OUR clock + uint32_t sync_since; // sync messages SINCE this timestamp (by OUR clock) + uint32_t pending_ack; + uint32_t push_post_timestamp; + unsigned long ack_timeout; + RoomPermission permission; + uint8_t push_failures; + uint8_t secret[PUB_KEY_SIZE]; + int out_path_len; + uint8_t out_path[MAX_PATH_SIZE]; +}; + +#define MAX_POST_TEXT_LEN (160-9) + +struct PostInfo { + mesh::Identity author; + uint32_t post_timestamp; // by OUR clock + char text[MAX_POST_TEXT_LEN+1]; +}; + +class MyMesh : public mesh::Mesh, public CommonCLICallbacks { + FILESYSTEM* _fs; + unsigned long next_local_advert, next_flood_advert; + bool _logging; + NodePrefs _prefs; + CommonCLI _cli; + uint8_t reply_data[MAX_PACKET_PAYLOAD]; + int num_clients; + ClientInfo known_clients[MAX_CLIENTS]; + unsigned long next_push; + uint16_t _num_posted, _num_post_pushes; + int next_client_idx; // for round-robin polling + int next_post_idx; + PostInfo posts[MAX_UNSYNCED_POSTS]; // cyclic queue + CayenneLPP telemetry; + unsigned long set_radio_at, revert_radio_at; + float pending_freq; + float pending_bw; + uint8_t pending_sf; + uint8_t pending_cr; + int matching_peer_indexes[MAX_CLIENTS]; + + ClientInfo* putClient(const mesh::Identity& id); + void evict(ClientInfo* client); + void addPost(ClientInfo* client, const char* postData); + void pushPostToClient(ClientInfo* client, PostInfo& post); + uint8_t getUnsyncedCount(ClientInfo* client); + bool processAck(const uint8_t *data); + mesh::Packet* createSelfAdvert(); + File openAppend(const char* fname); + int handleRequest(ClientInfo* sender, uint32_t sender_timestamp, uint8_t* payload, size_t payload_len); + +protected: + float getAirtimeBudgetFactor() const override { + return _prefs.airtime_factor; + } + + void logRxRaw(float snr, float rssi, const uint8_t raw[], int len) override; + void logRx(mesh::Packet* pkt, int len, float score) override; + void logTx(mesh::Packet* pkt, int len) override; + void logTxFail(mesh::Packet* pkt, int len) override; + + int calcRxDelay(float score, uint32_t air_time) const override; + const char* getLogDateTime() override; + uint32_t getRetransmitDelay(const mesh::Packet* packet) override; + uint32_t getDirectRetransmitDelay(const mesh::Packet* packet) override; + + int getInterferenceThreshold() const override { + return _prefs.interference_threshold; + } + int getAGCResetInterval() const override { + return ((int)_prefs.agc_reset_interval) * 4000; // milliseconds + } + uint8_t getExtraAckTransmitCount() const override { + return _prefs.multi_acks; + } + + bool allowPacketForward(const mesh::Packet* packet) override; + void onAnonDataRecv(mesh::Packet* packet, const uint8_t* secret, const mesh::Identity& sender, uint8_t* data, size_t len) override; + int searchPeersByHash(const uint8_t* hash) override ; + void getPeerSharedSecret(uint8_t* dest_secret, int peer_idx) override; + void onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_idx, const uint8_t* secret, uint8_t* data, size_t len) override; + bool onPeerPathRecv(mesh::Packet* packet, int sender_idx, const uint8_t* secret, uint8_t* path, uint8_t path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) override; + void onAckRecv(mesh::Packet* packet, uint32_t ack_crc) override; + +public: + MyMesh(mesh::MainBoard& board, mesh::Radio& radio, mesh::MillisecondClock& ms, mesh::RNG& rng, mesh::RTCClock& rtc, mesh::MeshTables& tables); + + void begin(FILESYSTEM* fs); + + const char* getFirmwareVer() override { return FIRMWARE_VERSION; } + const char* getBuildDate() override { return FIRMWARE_BUILD_DATE; } + const char* getRole() override { return FIRMWARE_ROLE; } + const char* getNodeName() { return _prefs.node_name; } + NodePrefs* getNodePrefs() { + return &_prefs; + } + + void savePrefs() override { + _cli.savePrefs(_fs); + } + + void applyTempRadioParams(float freq, float bw, uint8_t sf, uint8_t cr, int timeout_mins) override; + bool formatFileSystem() override; + void sendSelfAdvertisement(int delay_millis) override; + void updateAdvertTimer() override; + void updateFloodAdvertTimer() override; + + void setLoggingOn(bool enable) override { _logging = enable; } + + void eraseLogFile() override { + _fs->remove(PACKET_LOG_FILE); + } + + void dumpLogFile() override; + void setTxPower(uint8_t power_dbm) override; + + void formatNeighborsReply(char *reply) override { + strcpy(reply, "not supported"); + } + + mesh::LocalIdentity& getSelfId() override { return self_id; } + + void saveIdentity(const mesh::LocalIdentity& new_id) override; + void clearStats() override; + void handleCommand(uint32_t sender_timestamp, char* command, char* reply); + void loop(); +}; diff --git a/examples/simple_room_server/main.cpp b/examples/simple_room_server/main.cpp index aa9c8e3..8f6b6d5 100644 --- a/examples/simple_room_server/main.cpp +++ b/examples/simple_room_server/main.cpp @@ -1,979 +1,13 @@ #include <Arduino.h> // needed for PlatformIO #include <Mesh.h> -#if defined(NRF52_PLATFORM) - #include <InternalFileSystem.h> -#elif defined(RP2040_PLATFORM) - #include <LittleFS.h> -#elif defined(ESP32) - #include <SPIFFS.h> -#endif - -#include <helpers/ArduinoHelpers.h> -#include <helpers/StaticPoolPacketManager.h> -#include <helpers/SimpleMeshTables.h> -#include <helpers/IdentityStore.h> -#include <helpers/AdvertDataHelpers.h> -#include <helpers/TxtDataHelpers.h> -#include <helpers/CommonCLI.h> -#include <RTClib.h> -#include <target.h> - -/* ------------------------------ Config -------------------------------- */ - -#ifndef FIRMWARE_BUILD_DATE - #define FIRMWARE_BUILD_DATE "1 Sep 2025" -#endif - -#ifndef FIRMWARE_VERSION - #define FIRMWARE_VERSION "v1.8.1" -#endif - -#ifndef LORA_FREQ - #define LORA_FREQ 915.0 -#endif -#ifndef LORA_BW - #define LORA_BW 250 -#endif -#ifndef LORA_SF - #define LORA_SF 10 -#endif -#ifndef LORA_CR - #define LORA_CR 5 -#endif -#ifndef LORA_TX_POWER - #define LORA_TX_POWER 20 -#endif - -#ifndef ADVERT_NAME - #define ADVERT_NAME "Test BBS" -#endif -#ifndef ADVERT_LAT - #define ADVERT_LAT 0.0 -#endif -#ifndef ADVERT_LON - #define ADVERT_LON 0.0 -#endif - -#ifndef ADMIN_PASSWORD - #define ADMIN_PASSWORD "password" -#endif - -#ifndef MAX_CLIENTS - #define MAX_CLIENTS 32 -#endif - -#ifndef MAX_UNSYNCED_POSTS - #define MAX_UNSYNCED_POSTS 32 -#endif - -#ifndef SERVER_RESPONSE_DELAY - #define SERVER_RESPONSE_DELAY 300 -#endif - -#ifndef TXT_ACK_DELAY - #define TXT_ACK_DELAY 200 -#endif +#include "MyMesh.h" #ifdef DISPLAY_CLASS #include "UITask.h" static UITask ui_task(display); #endif -#define FIRMWARE_ROLE "room_server" - -#define PACKET_LOG_FILE "/packet_log" - -/* ------------------------------ Code -------------------------------- */ - -enum RoomPermission { - ADMIN, - GUEST, - READ_ONLY -}; - -struct ClientInfo { - mesh::Identity id; - uint32_t last_timestamp; // by THEIR clock - uint32_t last_activity; // by OUR clock - uint32_t sync_since; // sync messages SINCE this timestamp (by OUR clock) - uint32_t pending_ack; - uint32_t push_post_timestamp; - unsigned long ack_timeout; - RoomPermission permission; - uint8_t push_failures; - uint8_t secret[PUB_KEY_SIZE]; - int out_path_len; - uint8_t out_path[MAX_PATH_SIZE]; -}; - -#define MAX_POST_TEXT_LEN (160-9) - -struct PostInfo { - mesh::Identity author; - uint32_t post_timestamp; // by OUR clock - char text[MAX_POST_TEXT_LEN+1]; -}; - -#define REPLY_DELAY_MILLIS 1500 -#define PUSH_NOTIFY_DELAY_MILLIS 2000 -#define SYNC_PUSH_INTERVAL 1200 - -#define PUSH_ACK_TIMEOUT_FLOOD 12000 -#define PUSH_TIMEOUT_BASE 4000 -#define PUSH_ACK_TIMEOUT_FACTOR 2000 - -#define POST_SYNC_DELAY_SECS 6 - -#define CLIENT_KEEP_ALIVE_SECS 0 // Now Disabled (was 128) - -#define REQ_TYPE_GET_STATUS 0x01 // same as _GET_STATS -#define REQ_TYPE_KEEP_ALIVE 0x02 -#define REQ_TYPE_GET_TELEMETRY_DATA 0x03 - -#define RESP_SERVER_LOGIN_OK 0 // response to ANON_REQ - -struct ServerStats { - uint16_t batt_milli_volts; - uint16_t curr_tx_queue_len; - int16_t noise_floor; - int16_t last_rssi; - uint32_t n_packets_recv; - uint32_t n_packets_sent; - uint32_t total_air_time_secs; - uint32_t total_up_time_secs; - uint32_t n_sent_flood, n_sent_direct; - uint32_t n_recv_flood, n_recv_direct; - uint16_t err_events; // was 'n_full_events' - int16_t last_snr; // x 4 - uint16_t n_direct_dups, n_flood_dups; - uint16_t n_posted, n_post_push; -}; - -class MyMesh : public mesh::Mesh, public CommonCLICallbacks { - FILESYSTEM* _fs; - unsigned long next_local_advert, next_flood_advert; - bool _logging; - NodePrefs _prefs; - CommonCLI _cli; - uint8_t reply_data[MAX_PACKET_PAYLOAD]; - int num_clients; - ClientInfo known_clients[MAX_CLIENTS]; - unsigned long next_push; - uint16_t _num_posted, _num_post_pushes; - int next_client_idx; // for round-robin polling - int next_post_idx; - PostInfo posts[MAX_UNSYNCED_POSTS]; // cyclic queue - CayenneLPP telemetry; - unsigned long set_radio_at, revert_radio_at; - float pending_freq; - float pending_bw; - uint8_t pending_sf; - uint8_t pending_cr; - - ClientInfo* putClient(const mesh::Identity& id) { - for (int i = 0; i < num_clients; i++) { - if (id.matches(known_clients[i].id)) return &known_clients[i]; // already known - } - ClientInfo* newClient; - if (num_clients < MAX_CLIENTS) { - newClient = &known_clients[num_clients++]; - } else { // table is currently full - // evict least active client - uint32_t oldest_timestamp = 0xFFFFFFFF; - newClient = &known_clients[0]; - for (int i = 0; i < num_clients; i++) { - auto c = &known_clients[i]; - if (c->last_activity < oldest_timestamp) { - oldest_timestamp = c->last_activity; - newClient = c; - } - } - } - newClient->id = id; - newClient->out_path_len = -1; // initially out_path is unknown - newClient->last_timestamp = 0; - return newClient; - } - - void evict(ClientInfo* client) { - client->last_activity = 0; // this slot will now be re-used (will be oldest) - memset(client->id.pub_key, 0, sizeof(client->id.pub_key)); - memset(client->secret, 0, sizeof(client->secret)); - client->pending_ack = 0; - } - - void addPost(ClientInfo* client, const char* postData) { - // TODO: suggested postData format: <title>/<descrption> - posts[next_post_idx].author = client->id; // add to cyclic queue - StrHelper::strncpy(posts[next_post_idx].text, postData, MAX_POST_TEXT_LEN); - - posts[next_post_idx].post_timestamp = getRTCClock()->getCurrentTimeUnique(); - next_post_idx = (next_post_idx + 1) % MAX_UNSYNCED_POSTS; - - next_push = futureMillis(PUSH_NOTIFY_DELAY_MILLIS); - _num_posted++; // stats - } - - void pushPostToClient(ClientInfo* client, PostInfo& post) { - int len = 0; - memcpy(&reply_data[len], &post.post_timestamp, 4); len += 4; // this is a PAST timestamp... but should be accepted by client - - uint8_t attempt; - getRNG()->random(&attempt, 1); // need this for re-tries, so packet hash (and ACK) will be different - reply_data[len++] = (TXT_TYPE_SIGNED_PLAIN << 2) | (attempt & 3); // 'signed' plain text - - // encode prefix of post.author.pub_key - memcpy(&reply_data[len], post.author.pub_key, 4); len += 4; // just first 4 bytes - - int text_len = strlen(post.text); - memcpy(&reply_data[len], post.text, text_len); len += text_len; - - // calc expected ACK reply - mesh::Utils::sha256((uint8_t *)&client->pending_ack, 4, reply_data, len, client->id.pub_key, PUB_KEY_SIZE); - client->push_post_timestamp = post.post_timestamp; - - auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, client->secret, reply_data, len); - if (reply) { - if (client->out_path_len < 0) { - sendFlood(reply); - client->ack_timeout = futureMillis(PUSH_ACK_TIMEOUT_FLOOD); - } else { - sendDirect(reply, client->out_path, client->out_path_len); - client->ack_timeout = futureMillis(PUSH_TIMEOUT_BASE + PUSH_ACK_TIMEOUT_FACTOR * (client->out_path_len + 1)); - } - _num_post_pushes++; // stats - } else { - client->pending_ack = 0; - MESH_DEBUG_PRINTLN("Unable to push post to client"); - } - } - - uint8_t getUnsyncedCount(ClientInfo* client) { - uint8_t count = 0; - for (int k = 0; k < MAX_UNSYNCED_POSTS; k++) { - if (posts[k].post_timestamp > client->sync_since // is new post for this Client? - && !posts[k].author.matches(client->id)) { // don't push posts to the author - count++; - } - } - return count; - } - - bool processAck(const uint8_t *data) { - for (int i = 0; i < num_clients; i++) { - auto client = &known_clients[i]; - if (client->pending_ack && memcmp(data, &client->pending_ack, 4) == 0) { // got an ACK from Client! - client->pending_ack = 0; // clear this, so next push can happen - client->push_failures = 0; - client->sync_since = client->push_post_timestamp; // advance Client's SINCE timestamp, to sync next post - return true; - } - } - return false; - } - - mesh::Packet* createSelfAdvert() { - uint8_t app_data[MAX_ADVERT_DATA_SIZE]; - uint8_t app_data_len; - { - AdvertDataBuilder builder(ADV_TYPE_ROOM, _prefs.node_name, _prefs.node_lat, _prefs.node_lon); - app_data_len = builder.encodeTo(app_data); - } - - return createAdvert(self_id, app_data, app_data_len); - } - - File openAppend(const char* fname) { - #if defined(NRF52_PLATFORM) - return _fs->open(fname, FILE_O_WRITE); - #elif defined(RP2040_PLATFORM) - return _fs->open(fname, "a"); - #else - return _fs->open(fname, "a", true); - #endif - } - - int handleRequest(ClientInfo* sender, uint32_t sender_timestamp, uint8_t* payload, size_t payload_len) { - // uint32_t now = getRTCClock()->getCurrentTimeUnique(); - // memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp - memcpy(reply_data, &sender_timestamp, 4); // reflect sender_timestamp back in response packet (kind of like a 'tag') - - switch (payload[0]) { - case REQ_TYPE_GET_STATUS: { - ServerStats stats; - stats.batt_milli_volts = board.getBattMilliVolts(); - stats.curr_tx_queue_len = _mgr->getOutboundCount(0xFFFFFFFF); - stats.noise_floor = (int16_t)_radio->getNoiseFloor(); - stats.last_rssi = (int16_t) radio_driver.getLastRSSI(); - stats.n_packets_recv = radio_driver.getPacketsRecv(); - stats.n_packets_sent = radio_driver.getPacketsSent(); - stats.total_air_time_secs = getTotalAirTime() / 1000; - stats.total_up_time_secs = _ms->getMillis() / 1000; - stats.n_sent_flood = getNumSentFlood(); - stats.n_sent_direct = getNumSentDirect(); - stats.n_recv_flood = getNumRecvFlood(); - stats.n_recv_direct = getNumRecvDirect(); - stats.err_events = _err_flags; - stats.last_snr = (int16_t)(radio_driver.getLastSNR() * 4); - stats.n_direct_dups = ((SimpleMeshTables *)getTables())->getNumDirectDups(); - stats.n_flood_dups = ((SimpleMeshTables *)getTables())->getNumFloodDups(); - stats.n_posted = _num_posted; - stats.n_post_push = _num_post_pushes; - - memcpy(&reply_data[4], &stats, sizeof(stats)); - return 4 + sizeof(stats); - } - - case REQ_TYPE_GET_TELEMETRY_DATA: { - uint8_t perm_mask = ~(payload[1]); // NEW: first reserved byte (of 4), is now inverse mask to apply to permissions - - telemetry.reset(); - telemetry.addVoltage(TELEM_CHANNEL_SELF, (float)board.getBattMilliVolts() / 1000.0f); - // query other sensors -- target specific - sensors.querySensors((sender->permission == RoomPermission::ADMIN ? 0xFF : 0x00) & perm_mask, telemetry); - - uint8_t tlen = telemetry.getSize(); - memcpy(&reply_data[4], telemetry.getBuffer(), tlen); - return 4 + tlen; // reply_len - } - } - return 0; // unknown command - } - -protected: - float getAirtimeBudgetFactor() const override { - return _prefs.airtime_factor; - } - - void logRxRaw(float snr, float rssi, const uint8_t raw[], int len) override { - #if MESH_PACKET_LOGGING - Serial.print(getLogDateTime()); - Serial.print(" RAW: "); - mesh::Utils::printHex(Serial, raw, len); - Serial.println(); - #endif - } - - void logRx(mesh::Packet* pkt, int len, float score) override { - if (_logging) { - File f = openAppend(PACKET_LOG_FILE); - if (f) { - f.print(getLogDateTime()); - f.printf(": RX, len=%d (type=%d, route=%s, payload_len=%d) SNR=%d RSSI=%d score=%d", - len, pkt->getPayloadType(), pkt->isRouteDirect() ? "D" : "F", pkt->payload_len, - (int)_radio->getLastSNR(), (int)_radio->getLastRSSI(), (int)(score*1000)); - - if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH || pkt->getPayloadType() == PAYLOAD_TYPE_REQ - || pkt->getPayloadType() == PAYLOAD_TYPE_RESPONSE || pkt->getPayloadType() == PAYLOAD_TYPE_TXT_MSG) { - f.printf(" [%02X -> %02X]\n", (uint32_t)pkt->payload[1], (uint32_t)pkt->payload[0]); - } else { - f.printf("\n"); - } - f.close(); - } - } - } - void logTx(mesh::Packet* pkt, int len) override { - if (_logging) { - File f = openAppend(PACKET_LOG_FILE); - if (f) { - f.print(getLogDateTime()); - f.printf(": TX, len=%d (type=%d, route=%s, payload_len=%d)", - len, pkt->getPayloadType(), pkt->isRouteDirect() ? "D" : "F", pkt->payload_len); - - if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH || pkt->getPayloadType() == PAYLOAD_TYPE_REQ - || pkt->getPayloadType() == PAYLOAD_TYPE_RESPONSE || pkt->getPayloadType() == PAYLOAD_TYPE_TXT_MSG) { - f.printf(" [%02X -> %02X]\n", (uint32_t)pkt->payload[1], (uint32_t)pkt->payload[0]); - } else { - f.printf("\n"); - } - f.close(); - } - } - } - void logTxFail(mesh::Packet* pkt, int len) override { - if (_logging) { - File f = openAppend(PACKET_LOG_FILE); - if (f) { - f.print(getLogDateTime()); - f.printf(": TX FAIL!, len=%d (type=%d, route=%s, payload_len=%d)\n", - len, pkt->getPayloadType(), pkt->isRouteDirect() ? "D" : "F", pkt->payload_len); - f.close(); - } - } - } - - int calcRxDelay(float score, uint32_t air_time) const override { - if (_prefs.rx_delay_base <= 0.0f) return 0; - return (int) ((pow(_prefs.rx_delay_base, 0.85f - score) - 1.0) * air_time); - } - - const char* getLogDateTime() override { - static char tmp[32]; - uint32_t now = getRTCClock()->getCurrentTime(); - DateTime dt = DateTime(now); - sprintf(tmp, "%02d:%02d:%02d - %d/%d/%d U", dt.hour(), dt.minute(), dt.second(), dt.day(), dt.month(), dt.year()); - return tmp; - } - - uint32_t getRetransmitDelay(const mesh::Packet* packet) override { - uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.tx_delay_factor); - return getRNG()->nextInt(0, 6)*t; - } - uint32_t getDirectRetransmitDelay(const mesh::Packet* packet) override { - uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.direct_tx_delay_factor); - return getRNG()->nextInt(0, 6)*t; - } - int getInterferenceThreshold() const override { - return _prefs.interference_threshold; - } - int getAGCResetInterval() const override { - return ((int)_prefs.agc_reset_interval) * 4000; // milliseconds - } - uint8_t getExtraAckTransmitCount() const override { - return _prefs.multi_acks; - } - - bool allowPacketForward(const mesh::Packet* packet) override { - if (_prefs.disable_fwd) return false; - if (packet->isRouteFlood() && packet->path_len >= _prefs.flood_max) return false; - return true; - } - - void onAnonDataRecv(mesh::Packet* packet, const uint8_t* secret, const mesh::Identity& sender, uint8_t* data, size_t len) override { - if (packet->getPayloadType() == PAYLOAD_TYPE_ANON_REQ) { // received an initial request by a possible admin client (unknown at this stage) - uint32_t sender_timestamp, sender_sync_since; - memcpy(&sender_timestamp, data, 4); - memcpy(&sender_sync_since, &data[4], 4); // sender's "sync messags SINCE x" timestamp - - RoomPermission perm; - data[len] = 0; // ensure null terminator - if (strcmp((char *) &data[8], _prefs.password) == 0) { // check for valid admin password - perm = RoomPermission::ADMIN; - } else { - if (strcmp((char *) &data[8], _prefs.guest_password) == 0) { // check the room/public password - perm = RoomPermission::GUEST; - } else if (_prefs.allow_read_only) { - perm = RoomPermission::READ_ONLY; - } else { - MESH_DEBUG_PRINTLN("Incorrect room password"); - return; // no response. Client will timeout - } - } - - auto client = putClient(sender); // add to known clients (if not already known) - if (sender_timestamp <= client->last_timestamp) { - MESH_DEBUG_PRINTLN("possible replay attack!"); - return; - } - - MESH_DEBUG_PRINTLN("Login success!"); - client->permission = perm; - client->last_timestamp = sender_timestamp; - client->sync_since = sender_sync_since; - client->pending_ack = 0; - client->push_failures = 0; - memcpy(client->secret, secret, PUB_KEY_SIZE); - - uint32_t now = getRTCClock()->getCurrentTime(); - client->last_activity = now; - - now = getRTCClock()->getCurrentTimeUnique(); - memcpy(reply_data, &now, 4); // response packets always prefixed with timestamp - // TODO: maybe reply with count of messages waiting to be synced for THIS client? - reply_data[4] = RESP_SERVER_LOGIN_OK; - reply_data[5] = (CLIENT_KEEP_ALIVE_SECS >> 4); // NEW: recommended keep-alive interval (secs / 16) - reply_data[6] = (perm == RoomPermission::ADMIN ? 1 : (perm == RoomPermission::GUEST ? 0 : 2)); - reply_data[7] = getUnsyncedCount(client); // NEW - memcpy(&reply_data[8], "OK", 2); // REVISIT: not really needed - - next_push = futureMillis(PUSH_NOTIFY_DELAY_MILLIS); // delay next push, give RESPONSE packet time to arrive first - - if (packet->isRouteFlood()) { - // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response - mesh::Packet* path = createPathReturn(sender, client->secret, packet->path, packet->path_len, - PAYLOAD_TYPE_RESPONSE, reply_data, 8 + 2); - if (path) sendFlood(path, SERVER_RESPONSE_DELAY); - } else { - mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, client->secret, reply_data, 8 + 2); - if (reply) { - if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT - sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); - } else { - sendFlood(reply, SERVER_RESPONSE_DELAY); - } - } - } - } - } - - int matching_peer_indexes[MAX_CLIENTS]; - - int searchPeersByHash(const uint8_t* hash) override { - int n = 0; - for (int i = 0; i < num_clients; i++) { - if (known_clients[i].id.isHashMatch(hash)) { - matching_peer_indexes[n++] = i; // store the INDEXES of matching contacts (for subsequent 'peer' methods) - } - } - return n; - } - - void getPeerSharedSecret(uint8_t* dest_secret, int peer_idx) override { - int i = matching_peer_indexes[peer_idx]; - if (i >= 0 && i < num_clients) { - // lookup pre-calculated shared_secret - memcpy(dest_secret, known_clients[i].secret, PUB_KEY_SIZE); - } else { - MESH_DEBUG_PRINTLN("getPeerSharedSecret: Invalid peer idx: %d", i); - } - } - - void onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_idx, const uint8_t* secret, uint8_t* data, size_t len) override { - int i = matching_peer_indexes[sender_idx]; - if (i < 0 || i >= num_clients) { // get from our known_clients table (sender SHOULD already be known in this context) - MESH_DEBUG_PRINTLN("onPeerDataRecv: invalid peer idx: %d", i); - return; - } - auto client = &known_clients[i]; - if (type == PAYLOAD_TYPE_TXT_MSG && len > 5) { // a CLI command or new Post - uint32_t sender_timestamp; - memcpy(&sender_timestamp, data, 4); // timestamp (by sender's RTC clock - which could be wrong) - uint flags = (data[4] >> 2); // message attempt number, and other flags - - if (!(flags == TXT_TYPE_PLAIN || flags == TXT_TYPE_CLI_DATA)) { - MESH_DEBUG_PRINTLN("onPeerDataRecv: unsupported command flags received: flags=%02x", (uint32_t)flags); - } else if (sender_timestamp >= client->last_timestamp) { // prevent replay attacks, but send Acks for retries - bool is_retry = (sender_timestamp == client->last_timestamp); - client->last_timestamp = sender_timestamp; - - uint32_t now = getRTCClock()->getCurrentTimeUnique(); - client->last_activity = now; - client->push_failures = 0; // reset so push can resume (if prev failed) - - // len can be > original length, but 'text' will be padded with zeroes - data[len] = 0; // need to make a C string again, with null terminator - - uint32_t ack_hash; // calc truncated hash of the message timestamp + text + sender pub_key, to prove to sender that we got it - mesh::Utils::sha256((uint8_t *) &ack_hash, 4, data, 5 + strlen((char *)&data[5]), client->id.pub_key, PUB_KEY_SIZE); - - uint8_t temp[166]; - bool send_ack; - if (flags == TXT_TYPE_CLI_DATA) { - if (client->permission == RoomPermission::ADMIN) { - if (is_retry) { - temp[5] = 0; // no reply - } else { - handleCommand(sender_timestamp, (char *) &data[5], (char *) &temp[5]); - temp[4] = (TXT_TYPE_CLI_DATA << 2); // attempt and flags, (NOTE: legacy was: TXT_TYPE_PLAIN) - } - send_ack = false; - } else { - temp[5] = 0; // no reply - send_ack = false; // and no ACK... user shoudn't be sending these - } - } else { // TXT_TYPE_PLAIN - if (client->permission == RoomPermission::READ_ONLY) { - temp[5] = 0; // no reply - send_ack = false; // no ACK - } else { - if (!is_retry) { - addPost(client, (const char *) &data[5]); - } - temp[5] = 0; // no reply (ACK is enough) - send_ack = true; - } - } - - uint32_t delay_millis; - if (send_ack) { - if (client->out_path_len < 0) { - mesh::Packet* ack = createAck(ack_hash); - if (ack) sendFlood(ack, TXT_ACK_DELAY); - delay_millis = TXT_ACK_DELAY + REPLY_DELAY_MILLIS; - } else { - uint32_t d = TXT_ACK_DELAY; - if (getExtraAckTransmitCount() > 0) { - mesh::Packet* a1 = createMultiAck(ack_hash, 1); - if (a1) sendDirect(a1, client->out_path, client->out_path_len, d); - d += 300; - } - - mesh::Packet* a2 = createAck(ack_hash); - if (a2) sendDirect(a2, client->out_path, client->out_path_len, d); - delay_millis = d + REPLY_DELAY_MILLIS; - } - } else { - delay_millis = 0; - } - - int text_len = strlen((char *) &temp[5]); - if (text_len > 0) { - if (now == sender_timestamp) { - // WORKAROUND: the two timestamps need to be different, in the CLI view - now++; - } - memcpy(temp, &now, 4); // mostly an extra blob to help make packet_hash unique - - // calc expected ACK reply - //mesh::Utils::sha256((uint8_t *)&expected_ack_crc, 4, temp, 5 + text_len, self_id.pub_key, PUB_KEY_SIZE); - - auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, secret, temp, 5 + text_len); - if (reply) { - if (client->out_path_len < 0) { - sendFlood(reply, delay_millis + SERVER_RESPONSE_DELAY); - } else { - sendDirect(reply, client->out_path, client->out_path_len, delay_millis + SERVER_RESPONSE_DELAY); - } - } - } - } else { - MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); - } - } else if (type == PAYLOAD_TYPE_REQ && len >= 5) { - uint32_t sender_timestamp; - memcpy(&sender_timestamp, data, 4); // timestamp (by sender's RTC clock - which could be wrong) - if (sender_timestamp < client->last_timestamp) { // prevent replay attacks - MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); - } else { - client->last_timestamp = sender_timestamp; - - uint32_t now = getRTCClock()->getCurrentTime(); - client->last_activity = now; // <-- THIS will keep client connection alive - client->push_failures = 0; // reset so push can resume (if prev failed) - - if (data[4] == REQ_TYPE_KEEP_ALIVE && packet->isRouteDirect()) { // request type - uint32_t forceSince = 0; - if (len >= 9) { // optional - last post_timestamp client received - memcpy(&forceSince, &data[5], 4); // NOTE: this may be 0, if part of decrypted PADDING! - } else { - memcpy(&data[5], &forceSince, 4); // make sure there are zeroes in payload (for ack_hash calc below) - } - if (forceSince > 0) { - client->sync_since = forceSince; // force-update the 'sync since' - } - - client->pending_ack = 0; - - // TODO: Throttle KEEP_ALIVE requests! - // if client sends too quickly, evict() - - // RULE: only send keep_alive response DIRECT! - if (client->out_path_len >= 0) { - uint32_t ack_hash; // calc ACK to prove to sender that we got request - mesh::Utils::sha256((uint8_t *) &ack_hash, 4, data, 9, client->id.pub_key, PUB_KEY_SIZE); - - auto reply = createAck(ack_hash); - if (reply) { - reply->payload[reply->payload_len++] = getUnsyncedCount(client); // NEW: add unsynced counter to end of ACK packet - sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); - } - } - } else { - int reply_len = handleRequest(client, sender_timestamp, &data[4], len - 4); - if (reply_len > 0) { // valid command - if (packet->isRouteFlood()) { - // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response - mesh::Packet* path = createPathReturn(client->id, secret, packet->path, packet->path_len, - PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); - if (path) sendFlood(path, SERVER_RESPONSE_DELAY); - } else { - mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, client->id, secret, reply_data, reply_len); - if (reply) { - if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT - sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); - } else { - sendFlood(reply, SERVER_RESPONSE_DELAY); - } - } - } - } - } - } - } - } - - bool onPeerPathRecv(mesh::Packet* packet, int sender_idx, const uint8_t* secret, uint8_t* path, uint8_t path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) override { - // TODO: prevent replay attacks - int i = matching_peer_indexes[sender_idx]; - - if (i >= 0 && i < num_clients) { // get from our known_clients table (sender SHOULD already be known in this context) - MESH_DEBUG_PRINTLN("PATH to client, path_len=%d", (uint32_t) path_len); - auto client = &known_clients[i]; - memcpy(client->out_path, path, client->out_path_len = path_len); // store a copy of path, for sendDirect() - } else { - MESH_DEBUG_PRINTLN("onPeerPathRecv: invalid peer idx: %d", i); - } - - if (extra_type == PAYLOAD_TYPE_ACK && extra_len >= 4) { - // also got an encoded ACK! - processAck(extra); - } - - // NOTE: no reciprocal path send!! - return false; - } - - void onAckRecv(mesh::Packet* packet, uint32_t ack_crc) override { - if (processAck((uint8_t *)&ack_crc)) { - packet->markDoNotRetransmit(); // ACK was for this node, so don't retransmit - } - } - -public: - MyMesh(mesh::MainBoard& board, mesh::Radio& radio, mesh::MillisecondClock& ms, mesh::RNG& rng, mesh::RTCClock& rtc, mesh::MeshTables& tables) - : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), - _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) - { - next_local_advert = next_flood_advert = 0; - _logging = false; - set_radio_at = revert_radio_at = 0; - - // defaults - memset(&_prefs, 0, sizeof(_prefs)); - _prefs.airtime_factor = 1.0; // one half - _prefs.rx_delay_base = 0.0f; // off by default, was 10.0 - _prefs.tx_delay_factor = 0.5f; // was 0.25f; - StrHelper::strncpy(_prefs.node_name, ADVERT_NAME, sizeof(_prefs.node_name)); - _prefs.node_lat = ADVERT_LAT; - _prefs.node_lon = ADVERT_LON; - StrHelper::strncpy(_prefs.password, ADMIN_PASSWORD, sizeof(_prefs.password)); - _prefs.freq = LORA_FREQ; - _prefs.sf = LORA_SF; - _prefs.bw = LORA_BW; - _prefs.cr = LORA_CR; - _prefs.tx_power_dbm = LORA_TX_POWER; - _prefs.disable_fwd = 1; - _prefs.advert_interval = 1; // default to 2 minutes for NEW installs - _prefs.flood_advert_interval = 12; // 12 hours - _prefs.flood_max = 64; - _prefs.interference_threshold = 0; // disabled - #ifdef ROOM_PASSWORD - StrHelper::strncpy(_prefs.guest_password, ROOM_PASSWORD, sizeof(_prefs.guest_password)); - #endif - - num_clients = 0; - next_post_idx = 0; - next_client_idx = 0; - next_push = 0; - memset(posts, 0, sizeof(posts)); - _num_posted = _num_post_pushes = 0; - } - - void begin(FILESYSTEM* fs) { - mesh::Mesh::begin(); - _fs = fs; - // load persisted prefs - _cli.loadPrefs(_fs); - - radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); - radio_set_tx_power(_prefs.tx_power_dbm); - - updateAdvertTimer(); - updateFloodAdvertTimer(); - } - - const char* getFirmwareVer() override { return FIRMWARE_VERSION; } - const char* getBuildDate() override { return FIRMWARE_BUILD_DATE; } - const char* getRole() override { return FIRMWARE_ROLE; } - const char* getNodeName() { return _prefs.node_name; } - NodePrefs* getNodePrefs() { - return &_prefs; - } - - void savePrefs() override { - _cli.savePrefs(_fs); - } - - void applyTempRadioParams(float freq, float bw, uint8_t sf, uint8_t cr, int timeout_mins) override { - set_radio_at = futureMillis(2000); // give CLI reply some time to be sent back, before applying temp radio params - pending_freq = freq; - pending_bw = bw; - pending_sf = sf; - pending_cr = cr; - - revert_radio_at = futureMillis(2000 + timeout_mins*60*1000); // schedule when to revert radio params - } - - bool formatFileSystem() override { - #if defined(NRF52_PLATFORM) - return InternalFS.format(); - #elif defined(RP2040_PLATFORM) - return LittleFS.format(); - #elif defined(ESP32) - return SPIFFS.format(); - #else - #error "need to implement file system erase" - return false; - #endif - } - - void sendSelfAdvertisement(int delay_millis) override { - mesh::Packet* pkt = createSelfAdvert(); - if (pkt) { - sendFlood(pkt, delay_millis); - } else { - MESH_DEBUG_PRINTLN("ERROR: unable to create advertisement packet!"); - } - } - - void updateAdvertTimer() override { - if (_prefs.advert_interval > 0) { // schedule local advert timer - next_local_advert = futureMillis((uint32_t)_prefs.advert_interval * 2 * 60 * 1000); - } else { - next_local_advert = 0; // stop the timer - } - } - void updateFloodAdvertTimer() override { - if (_prefs.flood_advert_interval > 0) { // schedule flood advert timer - next_flood_advert = futureMillis( ((uint32_t)_prefs.flood_advert_interval) * 60 * 60 * 1000); - } else { - next_flood_advert = 0; // stop the timer - } - } - - void setLoggingOn(bool enable) override { _logging = enable; } - - void eraseLogFile() override { - _fs->remove(PACKET_LOG_FILE); - } - - void dumpLogFile() override { - #if defined(RP2040_PLATFORM) - File f = _fs->open(PACKET_LOG_FILE, "r"); - #else - File f = _fs->open(PACKET_LOG_FILE); - #endif - if (f) { - while (f.available()) { - int c = f.read(); - if (c < 0) break; - Serial.print((char)c); - } - f.close(); - } - } - - void setTxPower(uint8_t power_dbm) override { - radio_set_tx_power(power_dbm); - } - - void formatNeighborsReply(char *reply) override { - strcpy(reply, "not supported"); - } - - mesh::LocalIdentity& getSelfId() override { return self_id; } - - void saveIdentity(const mesh::LocalIdentity& new_id) override { - self_id = new_id; -#if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) - IdentityStore store(*_fs, ""); -#elif defined(ESP32) - IdentityStore store(*_fs, "/identity"); -#elif defined(RP2040_PLATFORM) - IdentityStore store(*_fs, "/identity"); -#else - #error "need to define saveIdentity()" -#endif - store.save("_main", self_id); - } - - void clearStats() override { - radio_driver.resetStats(); - resetStats(); - ((SimpleMeshTables *)getTables())->resetStats(); - } - - void handleCommand(uint32_t sender_timestamp, char* command, char* reply) { - while (*command == ' ') command++; // skip leading spaces - - if (strlen(command) > 4 && command[2] == '|') { // optional prefix (for companion radio CLI) - memcpy(reply, command, 3); // reflect the prefix back - reply += 3; - command += 3; - } - - _cli.handleCommand(sender_timestamp, command, reply); // common CLI commands - } - - void loop() { - mesh::Mesh::loop(); - - if (millisHasNowPassed(next_push) && num_clients > 0) { - // check for ACK timeouts - for (int i = 0; i < num_clients; i++) { - auto c = &known_clients[i]; - if (c->pending_ack && millisHasNowPassed(c->ack_timeout)) { - c->push_failures++; - c->pending_ack = 0; // reset (TODO: keep prev expected_ack's in a list, incase they arrive LATER, after we retry) - MESH_DEBUG_PRINTLN("pending ACK timed out: push_failures: %d", (uint32_t)c->push_failures); - } - } - // check next Round-Robin client, and sync next new post - auto client = &known_clients[next_client_idx]; - bool did_push = false; - if (client->pending_ack == 0 && client->last_activity != 0 && client->push_failures < 3) { // not already waiting for ACK, AND not evicted, AND retries not max - MESH_DEBUG_PRINTLN("loop - checking for client %02X", (uint32_t) client->id.pub_key[0]); - uint32_t now = getRTCClock()->getCurrentTime(); - for (int k = 0, idx = next_post_idx; k < MAX_UNSYNCED_POSTS; k++) { - auto p = &posts[idx]; - if (now >= p->post_timestamp + POST_SYNC_DELAY_SECS && p->post_timestamp > client->sync_since // is new post for this Client? - && !p->author.matches(client->id)) { // don't push posts to the author - // push this post to Client, then wait for ACK - pushPostToClient(client, *p); - did_push = true; - MESH_DEBUG_PRINTLN("loop - pushed to client %02X: %s", (uint32_t) client->id.pub_key[0], p->text); - break; - } - idx = (idx + 1) % MAX_UNSYNCED_POSTS; // wrap to start of cyclic queue - } - } else { - MESH_DEBUG_PRINTLN("loop - skipping busy (or evicted) client %02X", (uint32_t) client->id.pub_key[0]); - } - next_client_idx = (next_client_idx + 1) % num_clients; // round robin polling for each client - - if (did_push) { - next_push = futureMillis(SYNC_PUSH_INTERVAL); - } else { - // were no unsynced posts for curr client, so proccess next client much quicker! (in next loop()) - next_push = futureMillis(SYNC_PUSH_INTERVAL / 8); - } - } - - if (next_flood_advert && millisHasNowPassed(next_flood_advert)) { - mesh::Packet* pkt = createSelfAdvert(); - if (pkt) sendFlood(pkt); - - updateFloodAdvertTimer(); // schedule next flood advert - updateAdvertTimer(); // also schedule local advert (so they don't overlap) - } else if (next_local_advert && millisHasNowPassed(next_local_advert)) { - mesh::Packet* pkt = createSelfAdvert(); - if (pkt) sendZeroHop(pkt); - - updateAdvertTimer(); // schedule next local advert - } - - if (set_radio_at && millisHasNowPassed(set_radio_at)) { // apply pending (temporary) radio params - set_radio_at = 0; // clear timer - radio_set_params(pending_freq, pending_bw, pending_sf, pending_cr); - MESH_DEBUG_PRINTLN("Temp radio params"); - } - - if (revert_radio_at && millisHasNowPassed(revert_radio_at)) { // revert radio params to orig - revert_radio_at = 0; // clear timer - radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); - MESH_DEBUG_PRINTLN("Radio params restored"); - } - - #ifdef DISPLAY_CLASS - ui_task.loop(); - #endif - - // TODO: periodically check for OLD/inactive entries in known_clients[], and evict - } -}; - StdRNG fast_rng; SimpleMeshTables tables; MyMesh the_mesh(board, radio_driver, *new ArduinoMillis(), fast_rng, rtc_clock, tables); @@ -1073,4 +107,7 @@ void loop() { the_mesh.loop(); sensors.loop(); +#ifdef DISPLAY_CLASS + ui_task.loop(); +#endif } From cf93109cd5563f10e1b220b20a8b82d723c13405 Mon Sep 17 00:00:00 2001 From: csrutil <keming.cao@gmail.com> Date: Tue, 9 Sep 2025 19:20:39 +0800 Subject: [PATCH 42/50] =?UTF-8?q?=E2=9C=A8=20feat:=20add=20altitude=20supp?= =?UTF-8?q?ort=20to=20environment=20sensor=20node=20telemetry?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Include actual node altitude in GPS telemetry instead of hardcoded 0.0f - Extract altitude data from both ublox_GNSS and serial GPS sources - Update debug logging to display altitude alongside lat/lon coordinates --- src/helpers/sensors/EnvironmentSensorManager.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/helpers/sensors/EnvironmentSensorManager.cpp b/src/helpers/sensors/EnvironmentSensorManager.cpp index df08ed7..6b1b9e4 100644 --- a/src/helpers/sensors/EnvironmentSensorManager.cpp +++ b/src/helpers/sensors/EnvironmentSensorManager.cpp @@ -252,7 +252,7 @@ bool EnvironmentSensorManager::querySensors(uint8_t requester_permissions, Cayen next_available_channel = TELEM_CHANNEL_SELF + 1; if (requester_permissions & TELEM_PERM_LOCATION && gps_active) { - telemetry.addGPS(TELEM_CHANNEL_SELF, node_lat, node_lon, 0.0f); // allow lat/lon via telemetry even if no GPS is detected + telemetry.addGPS(TELEM_CHANNEL_SELF, node_lat, node_lon, node_altitude); // allow lat/lon via telemetry even if no GPS is detected } if (requester_permissions & TELEM_PERM_ENVIRONMENT) { @@ -577,17 +577,23 @@ void EnvironmentSensorManager::loop() { node_lat = ((double)ublox_GNSS.getLatitude())/10000000.; node_lon = ((double)ublox_GNSS.getLongitude())/10000000.; MESH_DEBUG_PRINTLN("lat %f lon %f", node_lat, node_lon); + node_altitude = ((double)ublox_GNSS.getAltitude()) / 1000.0; + MESH_DEBUG_PRINTLN("lat %f lon %f alt %f", node_lat, node_lon, node_altitude); } else if (serialGPSFlag && _location->isValid()) { node_lat = ((double)_location->getLatitude())/1000000.; node_lon = ((double)_location->getLongitude())/1000000.; MESH_DEBUG_PRINTLN("lat %f lon %f", node_lat, node_lon); + node_altitude = ((double)_location->getAltitude()) / 1000.0; + MESH_DEBUG_PRINTLN("lat %f lon %f alt %f", node_lat, node_lon, node_altitude); } #else if (_location->isValid()) { node_lat = ((double)_location->getLatitude())/1000000.; node_lon = ((double)_location->getLongitude())/1000000.; MESH_DEBUG_PRINTLN("lat %f lon %f", node_lat, node_lon); + node_altitude = ((double)_location->getAltitude()) / 1000.0; + MESH_DEBUG_PRINTLN("lat %f lon %f alt %f", node_lat, node_lon, node_altitude); } #endif } From d83cdc501f7e38ba9d8e439d28f500eae24ea7e8 Mon Sep 17 00:00:00 2001 From: Florent de Lamotte <florent@frizoncorrea.fr> Date: Tue, 9 Sep 2025 16:32:41 +0200 Subject: [PATCH 43/50] ui: use LPPDataHelper and conditionals for sensors page --- examples/companion_radio/ui-new/UITask.cpp | 105 +++++++--- examples/companion_radio/ui-new/UITask.h | 1 + src/helpers/sensors/LPPDataHelpers.h | 223 +++++++++++++++++++++ variants/lilygo_techo/platformio.ini | 3 + 4 files changed, 306 insertions(+), 26 deletions(-) create mode 100644 src/helpers/sensors/LPPDataHelpers.h diff --git a/examples/companion_radio/ui-new/UITask.cpp b/examples/companion_radio/ui-new/UITask.cpp index 0236a38..1e03f08 100644 --- a/examples/companion_radio/ui-new/UITask.cpp +++ b/examples/companion_radio/ui-new/UITask.cpp @@ -75,7 +75,9 @@ class HomeScreen : public UIScreen { RADIO, BLUETOOTH, ADVERT, +#if UI_SENSORS_PAGE == 1 SENSORS, +#endif SHUTDOWN, Count // keep as last }; @@ -114,20 +116,25 @@ class HomeScreen : public UIScreen { display.fillRect(iconX + 2, iconY + 2, fillWidth, iconHeight - 4); } - DynamicJsonDocument _sensors_doc; - JsonArray _sensors_arr; - bool scroll = false; - int scroll_offset = 0; + CayenneLPP sensors_lpp; + int sensors_nb = 0; + bool sensors_scroll = false; + int sensors_scroll_offset = 0; int next_sensors_refresh = 0; void refresh_sensors() { - CayenneLPP lpp(200); if (millis() > next_sensors_refresh) { - lpp.addVoltage(TELEM_CHANNEL_SELF, (float)board.getBattMilliVolts() / 1000.0f); - sensors.querySensors(0xFF, lpp); - _sensors_arr.clear(); - lpp.decode(lpp.getBuffer(), lpp.getSize(), _sensors_arr); - scroll = _sensors_arr.size() > UI_RECENT_LIST_SIZE; // there is a status line + sensors_lpp.reset(); + sensors_nb = 0; + sensors_lpp.addVoltage(TELEM_CHANNEL_SELF, (float)board.getBattMilliVolts() / 1000.0f); + sensors.querySensors(0xFF, sensors_lpp); + LPPReader reader (sensors_lpp.getBuffer(), sensors_lpp.getSize()); + uint8_t channel, type; + while(reader.readHeader(channel, type)) { + reader.skipData(type); + sensors_nb ++; + } + sensors_scroll = sensors_nb > UI_RECENT_LIST_SIZE; #if AUTO_OFF_MILLIS > 0 next_sensors_refresh = millis() + 5000; // refresh sensor values every 5 sec #else @@ -139,7 +146,7 @@ class HomeScreen : public UIScreen { public: HomeScreen(UITask* task, mesh::RTCClock* rtc, SensorManager* sensors, NodePrefs* node_prefs) : _task(task), _rtc(rtc), _sensors(sensors), _node_prefs(node_prefs), _page(0), - _shutdown_init(false), _sensors_doc(2048) { _sensors_arr=_sensors_doc.to<JsonArray>(); } + _shutdown_init(false), sensors_lpp(200) { } void poll() override { if (_shutdown_init && !_task->isButtonPressed()) { // must wait for USR button to be released @@ -235,34 +242,78 @@ public: display.setColor(DisplayDriver::GREEN); display.drawXbm((display.width() - 32) / 2, 18, advert_icon, 32, 32); display.drawTextCentered(display.width() / 2, 64 - 11, "advert: " PRESS_LABEL); +#if UI_SENSORS_PAGE == 1 } else if (_page == HomePage::SENSORS) { int y = 18; refresh_sensors(); - char buf[100]; - int s_size = _sensors_arr.size(); - for (int i = 0; i < (scroll?UI_RECENT_LIST_SIZE:s_size); i++) { - JsonObject v = _sensors_arr[(i+scroll_offset)%s_size]; + char buf[30]; + char name[30]; + LPPReader r(sensors_lpp.getBuffer(), sensors_lpp.getSize()); + + for (int i = 0; i < sensors_scroll_offset; i++) { + uint8_t channel, type; + r.readHeader(channel, type); + r.skipData(type); + } + + for (int i = 0; i < (sensors_scroll?UI_RECENT_LIST_SIZE:sensors_nb); i++) { + uint8_t channel, type; + if (!r.readHeader(channel, type)) { // reached end, reset + r.reset(); + r.readHeader(channel, type); + } + display.setCursor(0, y); - switch (v["type"].as<int>()) { - case 136: // GPS - sprintf(buf, "%.4f %.4f", - v["value"]["latitude"].as<float>(), - v["value"]["longitude"].as<float>()); + float v; + switch (type) { + case LPP_GPS: // GPS + float lat, lon, alt; + r.readGPS(lat, lon, alt); + strcpy(name, "gps"); sprintf(buf, "%.4f %.4f", lat, lon); break; - default: // will be a float for now - sprintf(buf, "%.02f", - v["value"].as<float>()); + case LPP_VOLTAGE: + r.readVoltage(v); + strcpy(name, "voltage"); sprintf(buf, "%6.2f", v); + break; + case LPP_CURRENT: + r.readCurrent(v); + strcpy(name, "current"); sprintf(buf, "%.3f", v); + break; + case LPP_TEMPERATURE: + r.readTemperature(v); + strcpy(name, "temperature"); sprintf(buf, "%.2f", v); + break; + case LPP_RELATIVE_HUMIDITY: + r.readRelativeHumidity(v); + strcpy(name, "humidity"); sprintf(buf, "%.2f", v); + break; + case LPP_BAROMETRIC_PRESSURE: + r.readPressure(v); + strcpy(name, "pressure"); sprintf(buf, "%.2f", v); + break; + case LPP_ALTITUDE: + r.readAltitude(v); + strcpy(name, "altitude"); sprintf(buf, "%.0f", v); + break; + case LPP_POWER: + r.readPower(v); + strcpy(name, "power"); sprintf(buf, "%6.2f", v); + break; + default: + r.skipData(type); + strcpy(name, "unk"); sprintf(buf, ""); } display.setCursor(0, y); - display.print(v["name"].as<JsonString>().c_str()); + display.print(name); display.setCursor( display.width()-display.getTextWidth(buf)-1, y ); display.print(buf); y = y + 12; } - if (scroll) scroll_offset = (scroll_offset+1)%s_size; - else scroll_offset = 0; + if (sensors_scroll) sensors_scroll_offset = (sensors_scroll_offset+1)%sensors_nb; + else sensors_scroll_offset = 0; +#endif } else if (_page == HomePage::SHUTDOWN) { display.setColor(DisplayDriver::GREEN); display.setTextSize(1); @@ -307,11 +358,13 @@ public: } return true; } +#if UI_SENSORS_PAGE == 1 if (c == KEY_ENTER && _page == HomePage::SENSORS) { _task->toggleGPS(); next_sensors_refresh=0; return true; } +#endif if (c == KEY_ENTER && _page == HomePage::SHUTDOWN) { _shutdown_init = true; // need to wait for button to be released return true; diff --git a/examples/companion_radio/ui-new/UITask.h b/examples/companion_radio/ui-new/UITask.h index 46024b1..769b2c6 100644 --- a/examples/companion_radio/ui-new/UITask.h +++ b/examples/companion_radio/ui-new/UITask.h @@ -6,6 +6,7 @@ #include <helpers/SensorManager.h> #include <helpers/BaseSerialInterface.h> #include <Arduino.h> +#include <helpers/sensors/LPPDataHelpers.h> #ifdef PIN_BUZZER #include <helpers/ui/buzzer.h> diff --git a/src/helpers/sensors/LPPDataHelpers.h b/src/helpers/sensors/LPPDataHelpers.h new file mode 100644 index 0000000..b9025de --- /dev/null +++ b/src/helpers/sensors/LPPDataHelpers.h @@ -0,0 +1,223 @@ +#pragma once + +#include <stdint.h> + +#define LPP_DIGITAL_INPUT 0 // 1 byte +#define LPP_DIGITAL_OUTPUT 1 // 1 byte +#define LPP_ANALOG_INPUT 2 // 2 bytes, 0.01 signed +#define LPP_ANALOG_OUTPUT 3 // 2 bytes, 0.01 signed +#define LPP_GENERIC_SENSOR 100 // 4 bytes, unsigned +#define LPP_LUMINOSITY 101 // 2 bytes, 1 lux unsigned +#define LPP_PRESENCE 102 // 1 byte, bool +#define LPP_TEMPERATURE 103 // 2 bytes, 0.1°C signed +#define LPP_RELATIVE_HUMIDITY 104 // 1 byte, 0.5% unsigned +#define LPP_ACCELEROMETER 113 // 2 bytes per axis, 0.001G +#define LPP_BAROMETRIC_PRESSURE 115 // 2 bytes 0.1hPa unsigned +#define LPP_VOLTAGE 116 // 2 bytes 0.01V unsigned +#define LPP_CURRENT 117 // 2 bytes 0.001A unsigned +#define LPP_FREQUENCY 118 // 4 bytes 1Hz unsigned +#define LPP_PERCENTAGE 120 // 1 byte 1-100% unsigned +#define LPP_ALTITUDE 121 // 2 byte 1m signed +#define LPP_CONCENTRATION 125 // 2 bytes, 1 ppm unsigned +#define LPP_POWER 128 // 2 byte, 1W, unsigned +#define LPP_DISTANCE 130 // 4 byte, 0.001m, unsigned +#define LPP_ENERGY 131 // 4 byte, 0.001kWh, unsigned +#define LPP_DIRECTION 132 // 2 bytes, 1deg, unsigned +#define LPP_UNIXTIME 133 // 4 bytes, unsigned +#define LPP_GYROMETER 134 // 2 bytes per axis, 0.01 °/s +#define LPP_COLOUR 135 // 1 byte per RGB Color +#define LPP_GPS 136 // 3 byte lon/lat 0.0001 °, 3 bytes alt 0.01 meter +#define LPP_SWITCH 142 // 1 byte, 0/1 +#define LPP_POLYLINE 240 // 1 byte size, 1 byte delta factor, 3 byte lon/lat 0.0001° * factor, n (size-8) bytes deltas + +// Multipliers +#define LPP_DIGITAL_INPUT_MULT 1 +#define LPP_DIGITAL_OUTPUT_MULT 1 +#define LPP_ANALOG_INPUT_MULT 100 +#define LPP_ANALOG_OUTPUT_MULT 100 +#define LPP_GENERIC_SENSOR_MULT 1 +#define LPP_LUMINOSITY_MULT 1 +#define LPP_PRESENCE_MULT 1 +#define LPP_TEMPERATURE_MULT 10 +#define LPP_RELATIVE_HUMIDITY_MULT 2 +#define LPP_ACCELEROMETER_MULT 1000 +#define LPP_BAROMETRIC_PRESSURE_MULT 10 +#define LPP_VOLTAGE_MULT 100 +#define LPP_CURRENT_MULT 1000 +#define LPP_FREQUENCY_MULT 1 +#define LPP_PERCENTAGE_MULT 1 +#define LPP_ALTITUDE_MULT 1 +#define LPP_POWER_MULT 1 +#define LPP_DISTANCE_MULT 1000 +#define LPP_ENERGY_MULT 1000 +#define LPP_DIRECTION_MULT 1 +#define LPP_UNIXTIME_MULT 1 +#define LPP_GYROMETER_MULT 100 +#define LPP_GPS_LAT_LON_MULT 10000 +#define LPP_GPS_ALT_MULT 100 +#define LPP_SWITCH_MULT 1 +#define LPP_CONCENTRATION_MULT 1 +#define LPP_COLOUR_MULT 1 + +#define LPP_ERROR_OK 0 +#define LPP_ERROR_OVERFLOW 1 +#define LPP_ERROR_UNKOWN_TYPE 2 + +class LPPReader { + const uint8_t* _buf; + uint8_t _len; + uint8_t _pos; + + float getFloat(const uint8_t * buffer, uint8_t size, uint32_t multiplier, bool is_signed) { + uint32_t value = 0; + for (uint8_t i = 0; i < size; i++) { + value = (value << 8) + buffer[i]; + } + + int sign = 1; + if (is_signed) { + uint32_t bit = 1ul << ((size * 8) - 1); + if ((value & bit) == bit) { + value = (bit << 1) - value; + sign = -1; + } + } + return sign * ((float) value / multiplier); + } + +public: + LPPReader(const uint8_t buf[], uint8_t len) : _buf(buf), _len(len), _pos(0) { } + + void reset() { + _pos = 0; + } + + bool readHeader(uint8_t& channel, uint8_t& type) { + if (_pos + 2 < _len) { + channel = _buf[_pos++]; + type = _buf[_pos++]; + + return channel != 0; // channel 0 is End-of-data + } + return false; // end-of-buffer + } + + bool readGPS(float& lat, float& lon, float& alt) { + lat = getFloat(&_buf[_pos], 3, 10000, true); _pos += 3; + lon = getFloat(&_buf[_pos], 3, 10000, true); _pos += 3; + alt = getFloat(&_buf[_pos], 3, 100, true); _pos += 3; + return _pos <= _len; + } + bool readVoltage(float& voltage) { + voltage = getFloat(&_buf[_pos], 2, 100, false); _pos += 2; + return _pos <= _len; + } + bool readCurrent(float& amps) { + amps = getFloat(&_buf[_pos], 2, 1000, false); _pos += 2; + return _pos <= _len; + } + bool readPower(float& watts) { + watts = getFloat(&_buf[_pos], 2, 1, false); _pos += 2; + return _pos <= _len; + } + bool readTemperature(float& degrees_c) { + degrees_c = getFloat(&_buf[_pos], 2, 10, true); _pos += 2; + return _pos <= _len; + } + bool readPressure(float& pa) { + pa = getFloat(&_buf[_pos], 2, 10, false); _pos += 2; + return _pos <= _len; + } + bool readRelativeHumidity(float& pct) { + pct = getFloat(&_buf[_pos], 1, 2, false); _pos += 1; + return _pos <= _len; + } + bool readAltitude(float& m) { + m = getFloat(&_buf[_pos], 2, 1, true); _pos += 2; + return _pos <= _len; + } + + void skipData(uint8_t type) { + switch (type) { + case LPP_GPS: + _pos += 9; break; + case LPP_POLYLINE: + _pos += 8; break; // TODO: this is MINIMIUM + case LPP_GYROMETER: + case LPP_ACCELEROMETER: + _pos += 6; break; + case LPP_GENERIC_SENSOR: + case LPP_FREQUENCY: + case LPP_DISTANCE: + case LPP_ENERGY: + case LPP_UNIXTIME: + _pos += 4; break; + case LPP_COLOUR: + _pos += 3; break; + case LPP_ANALOG_INPUT: + case LPP_ANALOG_OUTPUT: + case LPP_LUMINOSITY: + case LPP_TEMPERATURE: + case LPP_CONCENTRATION: + case LPP_BAROMETRIC_PRESSURE: + case LPP_ALTITUDE: + case LPP_VOLTAGE: + case LPP_CURRENT: + case LPP_DIRECTION: + case LPP_POWER: + _pos += 2; break; + default: + _pos++; + } + } +}; + +class LPPWriter { + uint8_t* _buf; + uint8_t _max_len; + uint8_t _len; + + void write(uint16_t value) { + _buf[_len++] = (value >> 8) & 0xFF; // MSB + _buf[_len++] = value & 0xFF; // LSB + } + +public: + LPPWriter(uint8_t buf[], uint8_t max_len): _buf(buf), _max_len(max_len), _len(0) { } + + bool writeVoltage(uint8_t channel, float voltage) { + if (_len + 4 <= _max_len) { + _buf[_len++] = channel; + _buf[_len++] = LPP_VOLTAGE; + uint16_t value = voltage * 100; + write(value); + return true; + } + return false; + } + + bool writeGPS(uint8_t channel, float lat, float lon, float alt) { + if (_len + 11 <= _max_len) { + _buf[_len++] = channel; + _buf[_len++] = LPP_GPS; + + int32_t lati = lat * 10000; // we lose some precision :-( + int32_t loni = lon * 10000; + int32_t alti = alt * 100; + + _buf[_len++] = lati >> 16; + _buf[_len++] = lati >> 8; + _buf[_len++] = lati; + _buf[_len++] = loni >> 16; + _buf[_len++] = loni >> 8; + _buf[_len++] = loni; + _buf[_len++] = alti >> 16; + _buf[_len++] = alti >> 8; + _buf[_len++] = alti; + return true; + } + return false; + } + + uint8_t length() { return _len; } +}; diff --git a/variants/lilygo_techo/platformio.ini b/variants/lilygo_techo/platformio.ini index 7d64fad..3661749 100644 --- a/variants/lilygo_techo/platformio.ini +++ b/variants/lilygo_techo/platformio.ini @@ -88,6 +88,8 @@ build_flags = -D BLE_PIN_CODE=123456 ; -D BLE_DEBUG_LOGGING=1 -D OFFLINE_QUEUE_SIZE=256 + -D UI_RECENT_LIST_SIZE=9 + -D UI_SENSORS_PAGE=1 ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 -D AUTO_SHUTDOWN_MILLIVOLTS=3300 @@ -109,6 +111,7 @@ build_flags = -D MAX_GROUP_CHANNELS=40 -D OFFLINE_QUEUE_SIZE=256 -D UI_RECENT_LIST_SIZE=9 + -D UI_SENSORS_PAGE=1 -D AUTO_SHUTDOWN_MILLIVOLTS=3300 build_src_filter = ${LilyGo_T-Echo.build_src_filter} +<../examples/companion_radio/*.cpp> From 80d5e2d8bcabdcdc512e48a239b325ddaa4531c3 Mon Sep 17 00:00:00 2001 From: liamcottle <liam@liamcottle.com> Date: Wed, 10 Sep 2025 17:04:03 +1200 Subject: [PATCH 44/50] fix wismesh tag power off and wake up --- variants/rak_wismesh_tag/RAKWismeshTagBoard.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/variants/rak_wismesh_tag/RAKWismeshTagBoard.h b/variants/rak_wismesh_tag/RAKWismeshTagBoard.h index 22af6f7..e5104a5 100644 --- a/variants/rak_wismesh_tag/RAKWismeshTagBoard.h +++ b/variants/rak_wismesh_tag/RAKWismeshTagBoard.h @@ -62,7 +62,8 @@ public: digitalWrite(LED_PIN, HIGH); #endif #ifdef BUTTON_PIN - while(digitalRead(BUTTON_PIN)); + // wismesh tag uses LOW to indicate button is pressed, wait until it goes HIGH to indicate it was released + while(digitalRead(BUTTON_PIN) == LOW); #endif #ifdef LED_GREEN digitalWrite(LED_GREEN, LOW); @@ -72,7 +73,8 @@ public: #endif #ifdef BUTTON_PIN - nrf_gpio_cfg_sense_input(digitalPinToInterrupt(BUTTON_PIN), NRF_GPIO_PIN_NOPULL, NRF_GPIO_PIN_SENSE_HIGH); + // configure button press to wake up when in powered off state + nrf_gpio_cfg_sense_input(digitalPinToInterrupt(BUTTON_PIN), NRF_GPIO_PIN_PULLUP, NRF_GPIO_PIN_SENSE_LOW); #endif sd_power_system_off(); From 65ef6c2fd0db17a103c9b61708da6ba78f5632a1 Mon Sep 17 00:00:00 2001 From: Scott Powell <sqij@protonmail.com> Date: Wed, 10 Sep 2025 17:04:58 +1000 Subject: [PATCH 45/50] * repeater and room server build_src_filter fixes --- variants/generic-e22/platformio.ini | 12 ++++++------ variants/generic_espnow/platformio.ini | 4 ++-- variants/lilygo_tlora_c6/platformio.ini | 2 +- variants/rak3x72/platformio.ini | 2 +- variants/sensecap_solar/platformio.ini | 4 ++-- variants/tenstar_c3/platformio.ini | 12 ++++++------ variants/thinknode_m1/platformio.ini | 4 ++-- variants/wio-e5-dev/platformio.ini | 2 +- variants/wio-e5-mini/platformio.ini | 2 +- variants/xiao_c3/platformio.ini | 2 +- variants/xiao_c6/platformio.ini | 6 +++--- variants/xiao_nrf52/platformio.ini | 4 ++-- variants/xiao_s3_wio/platformio.ini | 6 +++--- 13 files changed, 31 insertions(+), 31 deletions(-) diff --git a/variants/generic-e22/platformio.ini b/variants/generic-e22/platformio.ini index c9a6722..2f61f41 100644 --- a/variants/generic-e22/platformio.ini +++ b/variants/generic-e22/platformio.ini @@ -30,7 +30,7 @@ lib_deps = [env:Generic_E22_sx1262_repeater] extends = Generic_E22 build_src_filter = ${Generic_E22.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Generic_E22.build_flags} -D RADIO_CLASS=CustomSX1262 @@ -51,7 +51,7 @@ lib_deps = ; extends = Generic_E22 ; build_src_filter = ${Generic_E22.build_src_filter} ; +<helpers/bridges/RS232Bridge.cpp> -; +<../examples/simple_repeater/main.cpp> +; +<../examples/simple_repeater/*.cpp> ; build_flags = ; ${Generic_E22.build_flags} ; -D RADIO_CLASS=CustomSX1262 @@ -75,7 +75,7 @@ lib_deps = extends = Generic_E22 build_src_filter = ${Generic_E22.build_src_filter} +<helpers/bridges/ESPNowBridge.cpp> - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Generic_E22.build_flags} -D RADIO_CLASS=CustomSX1262 @@ -97,7 +97,7 @@ lib_deps = [env:Generic_E22_sx1268_repeater] extends = Generic_E22 build_src_filter = ${Generic_E22.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Generic_E22.build_flags} -D RADIO_CLASS=CustomSX1268 @@ -118,7 +118,7 @@ lib_deps = ; extends = Generic_E22 ; build_src_filter = ${Generic_E22.build_src_filter} ; +<helpers/bridges/RS232Bridge.cpp> -; +<../examples/simple_repeater/main.cpp> +; +<../examples/simple_repeater/*.cpp> ; build_flags = ; ${Generic_E22.build_flags} ; -D RADIO_CLASS=CustomSX1268 @@ -142,7 +142,7 @@ lib_deps = extends = Generic_E22 build_src_filter = ${Generic_E22.build_src_filter} +<helpers/bridges/ESPNowBridge.cpp> - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Generic_E22.build_flags} -D RADIO_CLASS=CustomSX1268 diff --git a/variants/generic_espnow/platformio.ini b/variants/generic_espnow/platformio.ini index 1c14dfe..db87a81 100644 --- a/variants/generic_espnow/platformio.ini +++ b/variants/generic_espnow/platformio.ini @@ -44,7 +44,7 @@ build_flags = -D ADMIN_PASSWORD='"password"' -D MAX_NEIGHBOURS=8 build_src_filter = ${Generic_ESPNOW.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> lib_deps = ${Generic_ESPNOW.lib_deps} ${esp32_ota.lib_deps} @@ -75,7 +75,7 @@ build_flags = -D ADMIN_PASSWORD='"password"' -D ROOM_PASSWORD='"hello"' build_src_filter = ${Generic_ESPNOW.build_src_filter} - +<../examples/simple_room_server/main.cpp> + +<../examples/simple_room_server/*.cpp> lib_deps = ${Generic_ESPNOW.lib_deps} ${esp32_ota.lib_deps} diff --git a/variants/lilygo_tlora_c6/platformio.ini b/variants/lilygo_tlora_c6/platformio.ini index 76a897d..f8a935c 100644 --- a/variants/lilygo_tlora_c6/platformio.ini +++ b/variants/lilygo_tlora_c6/platformio.ini @@ -33,7 +33,7 @@ build_src_filter = ${esp32c6_base.build_src_filter} [env:LilyGo_Tlora_C6_repeater] extends = tlora_c6 build_src_filter = ${tlora_c6.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${tlora_c6.build_flags} -D ADVERT_NAME='"Tlora C6 Repeater"' diff --git a/variants/rak3x72/platformio.ini b/variants/rak3x72/platformio.ini index 2fee1a7..da9b2f2 100644 --- a/variants/rak3x72/platformio.ini +++ b/variants/rak3x72/platformio.ini @@ -19,7 +19,7 @@ build_flags = ${rak3x72.build_flags} -D ADVERT_NAME='"RAK3x72 Repeater"' -D ADMIN_PASSWORD='"password"' build_src_filter = ${rak3x72.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> [env:rak3x72-sensor] extends = rak3x72 diff --git a/variants/sensecap_solar/platformio.ini b/variants/sensecap_solar/platformio.ini index 649ace8..ee9acf0 100644 --- a/variants/sensecap_solar/platformio.ini +++ b/variants/sensecap_solar/platformio.ini @@ -57,7 +57,7 @@ build_flags = ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${SenseCap_Solar.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> [env:SenseCap_Solar_room_server] extends = SenseCap_Solar @@ -70,7 +70,7 @@ build_flags = ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${SenseCap_Solar.build_src_filter} - +<../examples/simple_room_server/main.cpp> + +<../examples/simple_room_server/*.cpp> [env:SenseCap_Solar_companion_radio_ble] extends = SenseCap_Solar diff --git a/variants/tenstar_c3/platformio.ini b/variants/tenstar_c3/platformio.ini index c22b377..25bf671 100644 --- a/variants/tenstar_c3/platformio.ini +++ b/variants/tenstar_c3/platformio.ini @@ -26,7 +26,7 @@ build_src_filter = ${esp32_base.build_src_filter} [env:Tenstar_C3_Repeater_sx1262] extends = Tenstar_esp32_C3 build_src_filter = ${Tenstar_esp32_C3.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Tenstar_esp32_C3.build_flags} -D RADIO_CLASS=CustomSX1262 @@ -48,7 +48,7 @@ lib_deps = ; extends = Tenstar_esp32_C3 ; build_src_filter = ${Tenstar_esp32_C3.build_src_filter} ; +<helpers/bridges/RS232Bridge.cpp> -; +<../examples/simple_repeater/main.cpp> +; +<../examples/simple_repeater/*.cpp> ; build_flags = ; ${Tenstar_esp32_C3.build_flags} ; -D RADIO_CLASS=CustomSX1262 @@ -73,7 +73,7 @@ lib_deps = extends = Tenstar_esp32_C3 build_src_filter = ${Tenstar_esp32_C3.build_src_filter} +<helpers/bridges/ESPNowBridge.cpp> - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Tenstar_esp32_C3.build_flags} -D RADIO_CLASS=CustomSX1262 @@ -96,7 +96,7 @@ lib_deps = [env:Tenstar_C3_Repeater_sx1268] extends = Tenstar_esp32_C3 build_src_filter = ${Tenstar_esp32_C3.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Tenstar_esp32_C3.build_flags} -D RADIO_CLASS=CustomSX1268 @@ -117,7 +117,7 @@ lib_deps = ; extends = Tenstar_esp32_C3 ; build_src_filter = ${Tenstar_esp32_C3.build_src_filter} ; +<helpers/bridges/RS232Bridge.cpp> -; +<../examples/simple_repeater/main.cpp> +; +<../examples/simple_repeater/*.cpp> ; build_flags = ; ${Tenstar_esp32_C3.build_flags} ; -D RADIO_CLASS=CustomSX1268 @@ -141,7 +141,7 @@ lib_deps = extends = Tenstar_esp32_C3 build_src_filter = ${Tenstar_esp32_C3.build_src_filter} +<helpers/bridges/ESPNowBridge.cpp> - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Tenstar_esp32_C3.build_flags} -D RADIO_CLASS=CustomSX1268 diff --git a/variants/thinknode_m1/platformio.ini b/variants/thinknode_m1/platformio.ini index eeeb692..7a8f5a3 100644 --- a/variants/thinknode_m1/platformio.ini +++ b/variants/thinknode_m1/platformio.ini @@ -46,7 +46,7 @@ build_flags = ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${ThinkNode_M1.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> lib_deps = ${ThinkNode_M1.lib_deps} @@ -61,7 +61,7 @@ build_flags = ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${ThinkNode_M1.build_src_filter} - +<../examples/simple_room_server/main.cpp> + +<../examples/simple_room_server/*.cpp> lib_deps = ${ThinkNode_M1.lib_deps} diff --git a/variants/wio-e5-dev/platformio.ini b/variants/wio-e5-dev/platformio.ini index ce96ad2..350d79f 100644 --- a/variants/wio-e5-dev/platformio.ini +++ b/variants/wio-e5-dev/platformio.ini @@ -20,7 +20,7 @@ build_flags = ${lora_e5.build_flags} -D ADVERT_NAME='"WIO-E5 Repeater"' -D ADMIN_PASSWORD='"password"' build_src_filter = ${lora_e5.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> [env:wio-e5_companion_radio_usb] extends = lora_e5 diff --git a/variants/wio-e5-mini/platformio.ini b/variants/wio-e5-mini/platformio.ini index 3d98d93..30c8ef8 100644 --- a/variants/wio-e5-mini/platformio.ini +++ b/variants/wio-e5-mini/platformio.ini @@ -23,7 +23,7 @@ build_flags = ${lora_e5_mini.build_flags} -D ADVERT_NAME='"wio-e5-mini Repeater"' -D ADMIN_PASSWORD='"password"' build_src_filter = ${lora_e5_mini.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> [env:wio-e5-mini-sensor] extends = lora_e5_mini diff --git a/variants/xiao_c3/platformio.ini b/variants/xiao_c3/platformio.ini index de79fb1..e139fef 100644 --- a/variants/xiao_c3/platformio.ini +++ b/variants/xiao_c3/platformio.ini @@ -22,7 +22,7 @@ build_src_filter = ${esp32_base.build_src_filter} [env:Xiao_C3_Repeater_sx1262] extends = Xiao_esp32_C3 build_src_filter = ${Xiao_esp32_C3.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Xiao_esp32_C3.build_flags} -D RADIO_CLASS=CustomSX1262 diff --git a/variants/xiao_c6/platformio.ini b/variants/xiao_c6/platformio.ini index 24a17e0..83698d0 100644 --- a/variants/xiao_c6/platformio.ini +++ b/variants/xiao_c6/platformio.ini @@ -33,7 +33,7 @@ build_src_filter = ${esp32c6_base.build_src_filter} [env:Xiao_C6_Repeater] extends = Xiao_C6 build_src_filter = ${Xiao_C6.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Xiao_C6.build_flags} -D ADVERT_NAME='"Xiao C6 Repeater"' @@ -93,7 +93,7 @@ build_flags = [env:Meshimi_Repeater] extends = Meshimi build_src_filter = ${Meshimi.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Meshimi.build_flags} -D ADVERT_NAME='"Meshimi Repeater"' @@ -150,7 +150,7 @@ build_flags = [env:WHY2025_badge_Repeater] extends = WHY2025_badge build_src_filter = ${WHY2025_badge.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${WHY2025_badge.build_flags} -D ADVERT_NAME='"WHY2025 Badge Repeater"' diff --git a/variants/xiao_nrf52/platformio.ini b/variants/xiao_nrf52/platformio.ini index 1080747..ea1cdd3 100644 --- a/variants/xiao_nrf52/platformio.ini +++ b/variants/xiao_nrf52/platformio.ini @@ -107,7 +107,7 @@ build_flags = ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${Xiao_nrf52.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> [env:Xiao_nrf52_alt_pinout_repeater] extends = env:Xiao_nrf52_repeater @@ -126,4 +126,4 @@ build_flags = ; -D MESH_PACKET_LOGGING=1 ; -D MESH_DEBUG=1 build_src_filter = ${Xiao_nrf52.build_src_filter} - +<../examples/simple_room_server/main.cpp> \ No newline at end of file + +<../examples/simple_room_server/*.cpp> \ No newline at end of file diff --git a/variants/xiao_s3_wio/platformio.ini b/variants/xiao_s3_wio/platformio.ini index 7408f85..e6d2357 100644 --- a/variants/xiao_s3_wio/platformio.ini +++ b/variants/xiao_s3_wio/platformio.ini @@ -30,7 +30,7 @@ build_src_filter = ${esp32_base.build_src_filter} [env:Xiao_S3_WIO_Repeater] extends = Xiao_S3_WIO build_src_filter = ${Xiao_S3_WIO.build_src_filter} - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Xiao_S3_WIO.build_flags} -D ADVERT_NAME='"XiaoS3 Repeater"' @@ -48,7 +48,7 @@ lib_deps = ; extends = Xiao_S3_WIO ; build_src_filter = ${Xiao_S3_WIO.build_src_filter} ; +<helpers/bridges/RS232Bridge.cpp> -; +<../examples/simple_repeater/main.cpp> +; +<../examples/simple_repeater/*.cpp> ; build_flags = ; ${Xiao_S3_WIO.build_flags} ; -D ADVERT_NAME='"RS232 Bridge"' @@ -69,7 +69,7 @@ lib_deps = extends = Xiao_S3_WIO build_src_filter = ${Xiao_S3_WIO.build_src_filter} +<helpers/bridges/ESPNowBridge.cpp> - +<../examples/simple_repeater/main.cpp> + +<../examples/simple_repeater/*.cpp> build_flags = ${Xiao_S3_WIO.build_flags} -D ADVERT_NAME='"ESPNow Bridge"' From c8a10cc3b30814b44658e61eb8f3cd88a7e93818 Mon Sep 17 00:00:00 2001 From: Scott Powell <sqij@protonmail.com> Date: Wed, 10 Sep 2025 17:34:06 +1000 Subject: [PATCH 46/50] * RAK wishmesh tag: build fix --- variants/rak_wismesh_tag/platformio.ini | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/variants/rak_wismesh_tag/platformio.ini b/variants/rak_wismesh_tag/platformio.ini index 572919e..6b50507 100644 --- a/variants/rak_wismesh_tag/platformio.ini +++ b/variants/rak_wismesh_tag/platformio.ini @@ -35,6 +35,7 @@ build_src_filter = ${nrf52_base.build_src_filter} lib_deps = ${nrf52_base.lib_deps} ${sensor_base.lib_deps} + end2endzone/NonBlockingRTTTL@^1.3.0 [env:RAK_WisMesh_Tag_Repeater] extends = rak_wismesh_tag @@ -79,7 +80,6 @@ build_src_filter = ${rak_wismesh_tag.build_src_filter} lib_deps = ${rak_wismesh_tag.lib_deps} densaugeo/base64 @ ~1.4.0 - end2endzone/NonBlockingRTTTL@^1.3.0 [env:RAK_WisMesh_Tag_companion_radio_ble] extends = rak_wismesh_tag @@ -100,7 +100,6 @@ build_src_filter = ${rak_wismesh_tag.build_src_filter} lib_deps = ${rak4631.lib_deps} densaugeo/base64 @ ~1.4.0 - end2endzone/NonBlockingRTTTL@^1.3.0 [env:RAK_WisMesh_Tag_sensor] extends = rak4631 From e42ecc3bb3d0c32570474153575eed584a0c9a0b Mon Sep 17 00:00:00 2001 From: 446564 <robjdev@mailbox.org> Date: Wed, 10 Sep 2025 09:44:58 -0700 Subject: [PATCH 47/50] fix nano g2 notification revert change to disable buzzer before hibernate needs more work as the buzzer pin is a macro and can't be changed at runtime --- variants/nano_g2_ultra/nano-g2.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/variants/nano_g2_ultra/nano-g2.h b/variants/nano_g2_ultra/nano-g2.h index 69df0c6..5cedb0f 100644 --- a/variants/nano_g2_ultra/nano-g2.h +++ b/variants/nano_g2_ultra/nano-g2.h @@ -52,8 +52,8 @@ public: void powerOff() override { // put GPS chip to sleep digitalWrite(PIN_GPS_STANDBY, LOW); -// unset buzzer to prevent notification circuit activating on hibernate -#undef PIN_BUZZER + // TODO: unset buzzer to prevent notification circuit activating on hibernate + // needs to be set as silent or somehow stop using macros for pins nrf_gpio_cfg_sense_input(digitalPinToInterrupt(PIN_USER_BTN), NRF_GPIO_PIN_NOPULL, NRF_GPIO_PIN_SENSE_LOW); From 281591f147444871f429d0c2cfc5d1805b041b93 Mon Sep 17 00:00:00 2001 From: Scott Powell <sqij@protonmail.com> Date: Fri, 12 Sep 2025 15:35:31 +1000 Subject: [PATCH 48/50] * refactor: moved ACL out of SensorMesh -> ClientACL --- examples/simple_sensor/SensorMesh.cpp | 228 ++++++-------------------- examples/simple_sensor/SensorMesh.h | 35 +--- src/Identity.cpp | 2 +- src/Identity.h | 2 +- src/helpers/ClientACL.cpp | 128 +++++++++++++++ src/helpers/ClientACL.h | 47 ++++++ 6 files changed, 232 insertions(+), 210 deletions(-) create mode 100644 src/helpers/ClientACL.cpp create mode 100644 src/helpers/ClientACL.h diff --git a/examples/simple_sensor/SensorMesh.cpp b/examples/simple_sensor/SensorMesh.cpp index 72c0d97..0508713 100644 --- a/examples/simple_sensor/SensorMesh.cpp +++ b/examples/simple_sensor/SensorMesh.cpp @@ -71,78 +71,6 @@ static File openAppend(FILESYSTEM* _fs, const char* fname) { #endif } -static File openWrite(FILESYSTEM* _fs, const char* filename) { - #if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) - _fs->remove(filename); - return _fs->open(filename, FILE_O_WRITE); - #elif defined(RP2040_PLATFORM) - return _fs->open(filename, "w"); - #else - return _fs->open(filename, "w", true); - #endif -} - -void SensorMesh::loadContacts() { - num_contacts = 0; - if (_fs->exists("/s_contacts")) { - #if defined(RP2040_PLATFORM) - File file = _fs->open("/s_contacts", "r"); - #else - File file = _fs->open("/s_contacts"); - #endif - if (file) { - bool full = false; - while (!full) { - ContactInfo c; - uint8_t pub_key[32]; - uint8_t unused[6]; - - bool success = (file.read(pub_key, 32) == 32); - success = success && (file.read((uint8_t *) &c.permissions, 1) == 1); - success = success && (file.read(unused, 6) == 6); - success = success && (file.read((uint8_t *)&c.out_path_len, 1) == 1); - success = success && (file.read(c.out_path, 64) == 64); - success = success && (file.read(c.shared_secret, PUB_KEY_SIZE) == PUB_KEY_SIZE); - c.last_timestamp = 0; // transient - c.last_activity = 0; - - if (!success) break; // EOF - - c.id = mesh::Identity(pub_key); - if (num_contacts < MAX_CONTACTS) { - contacts[num_contacts++] = c; - } else { - full = true; - } - } - file.close(); - } - } -} - -void SensorMesh::saveContacts() { - File file = openWrite(_fs, "/s_contacts"); - if (file) { - uint8_t unused[5]; - memset(unused, 0, sizeof(unused)); - - for (int i = 0; i < num_contacts; i++) { - auto c = &contacts[i]; - if (c->permissions == 0) continue; // skip deleted entries - - bool success = (file.write(c->id.pub_key, 32) == 32); - success = success && (file.write((uint8_t *) &c->permissions, 1) == 1); - success = success && (file.write(unused, 6) == 6); - success = success && (file.write((uint8_t *)&c->out_path_len, 1) == 1); - success = success && (file.write(c->out_path, 64) == 64); - success = success && (file.write(c->shared_secret, PUB_KEY_SIZE) == PUB_KEY_SIZE); - - if (!success) break; // write failed - } - file.close(); - } -} - static uint8_t getDataSize(uint8_t type) { switch (type) { case LPP_GPS: @@ -295,8 +223,8 @@ uint8_t SensorMesh::handleRequest(uint8_t perms, uint32_t sender_timestamp, uint uint8_t res2 = payload[1]; if (res1 == 0 && res2 == 0) { uint8_t ofs = 4; - for (int i = 0; i < num_contacts && ofs + 7 <= sizeof(reply_data) - 4; i++) { - auto c = &contacts[i]; + for (int i = 0; i < acl.getNumClients() && ofs + 7 <= sizeof(reply_data) - 4; i++) { + auto c = acl.getClientByIdx(i); if (c->permissions == 0) continue; // skip deleted entries memcpy(&reply_data[ofs], c->id.pub_key, 6); ofs += 6; // just 6-byte pub_key prefix reply_data[ofs++] = c->permissions; @@ -318,63 +246,7 @@ mesh::Packet* SensorMesh::createSelfAdvert() { return createAdvert(self_id, app_data, app_data_len); } -ContactInfo* SensorMesh::getContact(const uint8_t* pubkey, int key_len) { - for (int i = 0; i < num_contacts; i++) { - if (memcmp(pubkey, contacts[i].id.pub_key, key_len) == 0) return &contacts[i]; // already known - } - return NULL; // not found -} - -ContactInfo* SensorMesh::putContact(const mesh::Identity& id, uint8_t init_perms) { - uint32_t min_time = 0xFFFFFFFF; - ContactInfo* oldest = &contacts[MAX_CONTACTS - 1]; - for (int i = 0; i < num_contacts; i++) { - if (id.matches(contacts[i].id)) return &contacts[i]; // already known - if (!contacts[i].isAdmin() && contacts[i].last_activity < min_time) { - oldest = &contacts[i]; - min_time = oldest->last_activity; - } - } - - ContactInfo* c; - if (num_contacts < MAX_CONTACTS) { - c = &contacts[num_contacts++]; - } else { - c = oldest; // evict least active contact - } - memset(c, 0, sizeof(*c)); - c->permissions = init_perms; - c->id = id; - c->out_path_len = -1; // initially out_path is unknown - return c; -} - -bool SensorMesh::applyContactPermissions(const uint8_t* pubkey, int key_len, uint8_t perms) { - ContactInfo* c; - if ((perms & PERM_ACL_ROLE_MASK) == PERM_ACL_GUEST) { // guest role is not persisted in contacts - c = getContact(pubkey, key_len); - if (c == NULL) return false; // partial pubkey not found - - num_contacts--; // delete from contacts[] - int i = c - contacts; - while (i < num_contacts) { - contacts[i] = contacts[i + 1]; - i++; - } - } else { - if (key_len < PUB_KEY_SIZE) return false; // need complete pubkey when adding/modifying - - mesh::Identity id(pubkey); - c = putContact(id, 0); - - c->permissions = perms; // update their permissions - self_id.calcSharedSecret(c->shared_secret, pubkey); - } - dirty_contacts_expiry = futureMillis(LAZY_CONTACTS_WRITE_DELAY); // trigger saveContacts() - return true; -} - -void SensorMesh::sendAlert(ContactInfo* c, Trigger* t) { +void SensorMesh::sendAlert(const ClientInfo* c, Trigger* t) { int text_len = strlen(t->text); uint8_t data[MAX_PACKET_PAYLOAD]; @@ -457,9 +329,9 @@ int SensorMesh::getAGCResetInterval() const { } uint8_t SensorMesh::handleLoginReq(const mesh::Identity& sender, const uint8_t* secret, uint32_t sender_timestamp, const uint8_t* data) { - ContactInfo* client; + ClientInfo* client; if (data[0] == 0) { // blank password, just check if sender is in ACL - client = getContact(sender.pub_key, PUB_KEY_SIZE); + client = acl.getClient(sender.pub_key, PUB_KEY_SIZE); if (client == NULL) { #if MESH_DEBUG MESH_DEBUG_PRINTLN("Login, sender not in ACL"); @@ -474,7 +346,7 @@ uint8_t SensorMesh::handleLoginReq(const mesh::Identity& sender, const uint8_t* return 0; } - client = putContact(sender, PERM_RECV_ALERTS_HI | PERM_RECV_ALERTS_LO); // add to contacts (if not already known) + client = acl.putClient(sender, PERM_RECV_ALERTS_HI | PERM_RECV_ALERTS_LO); // add to contacts (if not already known) if (sender_timestamp <= client->last_timestamp) { MESH_DEBUG_PRINTLN("Possible login replay attack!"); return 0; // FATAL: client table is full -OR- replay attack @@ -527,7 +399,8 @@ void SensorMesh::handleCommand(uint32_t sender_timestamp, char* command, char* r int hex_len = min(sp - hex, PUB_KEY_SIZE*2); if (mesh::Utils::fromHex(pubkey, hex_len / 2, hex)) { uint8_t perms = atoi(sp); - if (applyContactPermissions(pubkey, hex_len / 2, perms)) { + if (acl.applyPermissions(self_id, pubkey, hex_len / 2, perms)) { + dirty_contacts_expiry = futureMillis(LAZY_CONTACTS_WRITE_DELAY); // trigger acl.save() strcpy(reply, "OK"); } else { strcpy(reply, "Err - invalid params"); @@ -538,8 +411,8 @@ void SensorMesh::handleCommand(uint32_t sender_timestamp, char* command, char* r } } else if (sender_timestamp == 0 && strcmp(command, "get acl") == 0) { Serial.println("ACL:"); - for (int i = 0; i < num_contacts; i++) { - auto c = &contacts[i]; + for (int i = 0; i < acl.getNumClients(); i++) { + auto c = acl.getClientByIdx(i); if (c->permissions == 0) continue; // skip deleted entries Serial.printf("%02X ", c->permissions); @@ -595,8 +468,8 @@ void SensorMesh::onAnonDataRecv(mesh::Packet* packet, const uint8_t* secret, con int SensorMesh::searchPeersByHash(const uint8_t* hash) { int n = 0; - for (int i = 0; i < num_contacts && n < MAX_SEARCH_RESULTS; i++) { - if (contacts[i].id.isHashMatch(hash)) { + for (int i = 0; i < acl.getNumClients() && n < MAX_SEARCH_RESULTS; i++) { + if (acl.getClientByIdx(i)->id.isHashMatch(hash)) { matching_peer_indexes[n++] = i; // store the INDEXES of matching contacts (for subsequent 'peer' methods) } } @@ -605,15 +478,15 @@ int SensorMesh::searchPeersByHash(const uint8_t* hash) { void SensorMesh::getPeerSharedSecret(uint8_t* dest_secret, int peer_idx) { int i = matching_peer_indexes[peer_idx]; - if (i >= 0 && i < num_contacts) { + if (i >= 0 && i < acl.getNumClients()) { // lookup pre-calculated shared_secret - memcpy(dest_secret, contacts[i].shared_secret, PUB_KEY_SIZE); + memcpy(dest_secret, acl.getClientByIdx(i)->shared_secret, PUB_KEY_SIZE); } else { MESH_DEBUG_PRINTLN("getPeerSharedSecret: Invalid peer idx: %d", i); } } -void SensorMesh::sendAckTo(const ContactInfo& dest, uint32_t ack_hash) { +void SensorMesh::sendAckTo(const ClientInfo& dest, uint32_t ack_hash) { if (dest.out_path_len < 0) { mesh::Packet* ack = createAck(ack_hash); if (ack) sendFlood(ack, TXT_ACK_DELAY); @@ -632,34 +505,34 @@ void SensorMesh::sendAckTo(const ContactInfo& dest, uint32_t ack_hash) { void SensorMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_idx, const uint8_t* secret, uint8_t* data, size_t len) { int i = matching_peer_indexes[sender_idx]; - if (i < 0 || i >= num_contacts) { + if (i < 0 || i >= acl.getNumClients()) { MESH_DEBUG_PRINTLN("onPeerDataRecv: Invalid sender idx: %d", i); return; } - ContactInfo& from = contacts[i]; + ClientInfo* from = acl.getClientByIdx(i); if (type == PAYLOAD_TYPE_REQ) { // request (from a known contact) uint32_t timestamp; memcpy(×tamp, data, 4); - if (timestamp > from.last_timestamp) { // prevent replay attacks - uint8_t reply_len = handleRequest(from.isAdmin() ? 0xFF : from.permissions, timestamp, data[4], &data[5], len - 5); + if (timestamp > from->last_timestamp) { // prevent replay attacks + uint8_t reply_len = handleRequest(from->isAdmin() ? 0xFF : from->permissions, timestamp, data[4], &data[5], len - 5); if (reply_len == 0) return; // invalid command - from.last_timestamp = timestamp; - from.last_activity = getRTCClock()->getCurrentTime(); + from->last_timestamp = timestamp; + from->last_activity = getRTCClock()->getCurrentTime(); if (packet->isRouteFlood()) { // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response - mesh::Packet* path = createPathReturn(from.id, secret, packet->path, packet->path_len, + mesh::Packet* path = createPathReturn(from->id, secret, packet->path, packet->path_len, PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); if (path) sendFlood(path, SERVER_RESPONSE_DELAY); } else { - mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, from.id, secret, reply_data, reply_len); + mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, from->id, secret, reply_data, reply_len); if (reply) { - if (from.out_path_len >= 0) { // we have an out_path, so send DIRECT - sendDirect(reply, from.out_path, from.out_path_len, SERVER_RESPONSE_DELAY); + if (from->out_path_len >= 0) { // we have an out_path, so send DIRECT + sendDirect(reply, from->out_path, from->out_path_len, SERVER_RESPONSE_DELAY); } else { sendFlood(reply, SERVER_RESPONSE_DELAY); } @@ -668,30 +541,30 @@ void SensorMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_i } else { MESH_DEBUG_PRINTLN("onPeerDataRecv: possible replay attack detected"); } - } else if (type == PAYLOAD_TYPE_TXT_MSG && len > 5 && from.isAdmin()) { // a CLI command + } else if (type == PAYLOAD_TYPE_TXT_MSG && len > 5 && from->isAdmin()) { // a CLI command uint32_t sender_timestamp; memcpy(&sender_timestamp, data, 4); // timestamp (by sender's RTC clock - which could be wrong) uint flags = (data[4] >> 2); // message attempt number, and other flags - if (sender_timestamp > from.last_timestamp) { // prevent replay attacks + if (sender_timestamp > from->last_timestamp) { // prevent replay attacks if (flags == TXT_TYPE_PLAIN) { - bool handled = handleIncomingMsg(from, sender_timestamp, &data[5], flags, len - 5); + bool handled = handleIncomingMsg(*from, sender_timestamp, &data[5], flags, len - 5); if (handled) { // if msg was handled then send an ack uint32_t ack_hash; // calc truncated hash of the message timestamp + text + sender pub_key, to prove to sender that we got it - mesh::Utils::sha256((uint8_t *) &ack_hash, 4, data, 5 + strlen((char *)&data[5]), from.id.pub_key, PUB_KEY_SIZE); + mesh::Utils::sha256((uint8_t *) &ack_hash, 4, data, 5 + strlen((char *)&data[5]), from->id.pub_key, PUB_KEY_SIZE); if (packet->isRouteFlood()) { // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the ACK - mesh::Packet* path = createPathReturn(from.id, secret, packet->path, packet->path_len, - PAYLOAD_TYPE_ACK, (uint8_t *) &ack_hash, 4); + mesh::Packet* path = createPathReturn(from->id, secret, packet->path, packet->path_len, + PAYLOAD_TYPE_ACK, (uint8_t *) &ack_hash, 4); if (path) sendFlood(path, TXT_ACK_DELAY); } else { - sendAckTo(from, ack_hash); - } + sendAckTo(*from, ack_hash); + } } } else if (flags == TXT_TYPE_CLI_DATA) { - from.last_timestamp = sender_timestamp; - from.last_activity = getRTCClock()->getCurrentTime(); + from->last_timestamp = sender_timestamp; + from->last_activity = getRTCClock()->getCurrentTime(); // len can be > original length, but 'text' will be padded with zeroes data[len] = 0; // need to make a C string again, with null terminator @@ -711,12 +584,12 @@ void SensorMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_i memcpy(temp, ×tamp, 4); // mostly an extra blob to help make packet_hash unique temp[4] = (TXT_TYPE_CLI_DATA << 2); - auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, from.id, secret, temp, 5 + text_len); + auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, from->id, secret, temp, 5 + text_len); if (reply) { - if (from.out_path_len < 0) { + if (from->out_path_len < 0) { sendFlood(reply, CLI_REPLY_DELAY_MILLIS); } else { - sendDirect(reply, from.out_path, from.out_path_len, CLI_REPLY_DELAY_MILLIS); + sendDirect(reply, from->out_path, from->out_path_len, CLI_REPLY_DELAY_MILLIS); } } } @@ -729,7 +602,7 @@ void SensorMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_i } } -bool SensorMesh::handleIncomingMsg(ContactInfo& from, uint32_t timestamp, uint8_t* data, uint flags, size_t len) { +bool SensorMesh::handleIncomingMsg(ClientInfo& from, uint32_t timestamp, uint8_t* data, uint flags, size_t len) { MESH_DEBUG_PRINT("handleIncomingMsg: unhandled msg from "); #ifdef MESH_DEBUG mesh::Utils::printHex(Serial, from.id.pub_key, PUB_KEY_SIZE); @@ -740,21 +613,21 @@ bool SensorMesh::handleIncomingMsg(ContactInfo& from, uint32_t timestamp, uint8_ bool SensorMesh::onPeerPathRecv(mesh::Packet* packet, int sender_idx, const uint8_t* secret, uint8_t* path, uint8_t path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) { int i = matching_peer_indexes[sender_idx]; - if (i < 0 || i >= num_contacts) { + if (i < 0 || i >= acl.getNumClients()) { MESH_DEBUG_PRINTLN("onPeerPathRecv: Invalid sender idx: %d", i); return false; } - ContactInfo& from = contacts[i]; + ClientInfo* from = acl.getClientByIdx(i); MESH_DEBUG_PRINTLN("PATH to contact, path_len=%d", (uint32_t) path_len); // NOTE: for this impl, we just replace the current 'out_path' regardless, whenever sender sends us a new out_path. // FUTURE: could store multiple out_paths per contact, and try to find which is the 'best'(?) - memcpy(from.out_path, path, from.out_path_len = path_len); // store a copy of path, for sendDirect() - from.last_activity = getRTCClock()->getCurrentTime(); + memcpy(from->out_path, path, from->out_path_len = path_len); // store a copy of path, for sendDirect() + from->last_activity = getRTCClock()->getCurrentTime(); // REVISIT: maybe make ALL out_paths non-persisted to minimise flash writes?? - if (from.isAdmin()) { + if (from->isAdmin()) { // only do saveContacts() (of this out_path change) if this is an admin dirty_contacts_expiry = futureMillis(LAZY_CONTACTS_WRITE_DELAY); } @@ -781,7 +654,6 @@ SensorMesh::SensorMesh(mesh::MainBoard& board, mesh::Radio& radio, mesh::Millise : mesh::Mesh(radio, ms, rng, rtc, *new StaticPoolPacketManager(32), tables), _cli(board, rtc, &_prefs, this), telemetry(MAX_PACKET_PAYLOAD - 4) { - num_contacts = 0; next_local_advert = next_flood_advert = 0; dirty_contacts_expiry = 0; last_read_time = 0; @@ -815,7 +687,7 @@ void SensorMesh::begin(FILESYSTEM* fs) { // load persisted prefs _cli.loadPrefs(_fs); - loadContacts(); + acl.load(_fs); radio_set_params(_prefs.freq, _prefs.bw, _prefs.sf, _prefs.cr); radio_set_tx_power(_prefs.tx_power_dbm); @@ -967,13 +839,13 @@ void SensorMesh::loop() { if (millisHasNowPassed(t->send_expiry)) { // next send needed? if (t->attempt >= 4) { // max attempts reached, try next contact t->curr_contact_idx++; - if (t->curr_contact_idx >= num_contacts) { // no more contacts to try? + if (t->curr_contact_idx >= acl.getNumClients()) { // no more contacts to try? num_alert_tasks--; // remove t from queue for (int i = 0; i < num_alert_tasks; i++) { alert_tasks[i] = alert_tasks[i + 1]; } } else { - auto c = &contacts[t->curr_contact_idx]; + auto c = acl.getClientByIdx(t->curr_contact_idx); uint16_t pri_mask = (t->pri == HIGH_PRI_ALERT) ? PERM_RECV_ALERTS_HI : PERM_RECV_ALERTS_LO; if (c->permissions & pri_mask) { // contact wants alert @@ -986,8 +858,8 @@ void SensorMesh::loop() { // next contact tested in next ::loop() } } - } else if (t->curr_contact_idx < num_contacts) { - auto c = &contacts[t->curr_contact_idx]; // send next attempt + } else if (t->curr_contact_idx < acl.getNumClients()) { + auto c = acl.getClientByIdx(t->curr_contact_idx); // send next attempt sendAlert(c, t); // NOTE: modifies attempt, expected_acks[] and send_expiry } else { // contact list has likely been modified while waiting for alert ACK, cancel this task @@ -998,7 +870,7 @@ void SensorMesh::loop() { // is there are pending dirty contacts write needed? if (dirty_contacts_expiry && millisHasNowPassed(dirty_contacts_expiry)) { - saveContacts(); + acl.save(_fs); dirty_contacts_expiry = 0; } } diff --git a/examples/simple_sensor/SensorMesh.h b/examples/simple_sensor/SensorMesh.h index 7b3b395..7f7ee79 100644 --- a/examples/simple_sensor/SensorMesh.h +++ b/examples/simple_sensor/SensorMesh.h @@ -20,15 +20,10 @@ #include <helpers/AdvertDataHelpers.h> #include <helpers/TxtDataHelpers.h> #include <helpers/CommonCLI.h> +#include <helpers/ClientACL.h> #include <RTClib.h> #include <target.h> -#define PERM_ACL_ROLE_MASK 3 // lower 2 bits -#define PERM_ACL_GUEST 0 -#define PERM_ACL_READ_ONLY 1 -#define PERM_ACL_READ_WRITE 2 -#define PERM_ACL_ADMIN 3 - #define PERM_RESERVED1 (1 << 2) #define PERM_RESERVED2 (1 << 3) #define PERM_RESERVED3 (1 << 4) @@ -36,18 +31,6 @@ #define PERM_RECV_ALERTS_LO (1 << 6) // low priority alerts #define PERM_RECV_ALERTS_HI (1 << 7) // high priority alerts -struct ContactInfo { - mesh::Identity id; - uint8_t permissions; - int8_t out_path_len; - uint8_t out_path[MAX_PATH_SIZE]; - uint8_t shared_secret[PUB_KEY_SIZE]; - uint32_t last_timestamp; // by THEIR clock (transient) - uint32_t last_activity; // by OUR clock (transient) - - bool isAdmin() const { return (permissions & PERM_ACL_ROLE_MASK) == PERM_ACL_ADMIN; } -}; - #ifndef FIRMWARE_BUILD_DATE #define FIRMWARE_BUILD_DATE "1 Sep 2025" #endif @@ -58,8 +41,6 @@ struct ContactInfo { #define FIRMWARE_ROLE "sensor" -#define MAX_CONTACTS 20 - #define MAX_SEARCH_RESULTS 8 #define MAX_CONCURRENT_ALERTS 4 @@ -141,16 +122,15 @@ protected: void onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_idx, const uint8_t* secret, uint8_t* data, size_t len) override; bool onPeerPathRecv(mesh::Packet* packet, int sender_idx, const uint8_t* secret, uint8_t* path, uint8_t path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) override; void onAckRecv(mesh::Packet* packet, uint32_t ack_crc) override; - virtual bool handleIncomingMsg(ContactInfo& from, uint32_t timestamp, uint8_t* data, uint flags, size_t len); - void sendAckTo(const ContactInfo& dest, uint32_t ack_hash); + virtual bool handleIncomingMsg(ClientInfo& from, uint32_t timestamp, uint8_t* data, uint flags, size_t len); + void sendAckTo(const ClientInfo& dest, uint32_t ack_hash); private: FILESYSTEM* _fs; unsigned long next_local_advert, next_flood_advert; NodePrefs _prefs; CommonCLI _cli; uint8_t reply_data[MAX_PACKET_PAYLOAD]; - ContactInfo contacts[MAX_CONTACTS]; - int num_contacts; + ClientACL acl; unsigned long dirty_contacts_expiry; CayenneLPP telemetry; uint32_t last_read_time; @@ -163,15 +143,10 @@ private: uint8_t pending_sf; uint8_t pending_cr; - void loadContacts(); - void saveContacts(); uint8_t handleLoginReq(const mesh::Identity& sender, const uint8_t* secret, uint32_t sender_timestamp, const uint8_t* data); uint8_t handleRequest(uint8_t perms, uint32_t sender_timestamp, uint8_t req_type, uint8_t* payload, size_t payload_len); mesh::Packet* createSelfAdvert(); - ContactInfo* getContact(const uint8_t* pubkey, int key_len); - ContactInfo* putContact(const mesh::Identity& id, uint8_t init_perms); - bool applyContactPermissions(const uint8_t* pubkey, int key_len, uint8_t perms); - void sendAlert(ContactInfo* c, Trigger* t); + void sendAlert(const ClientInfo* c, Trigger* t); }; diff --git a/src/Identity.cpp b/src/Identity.cpp index 138c66b..8329892 100644 --- a/src/Identity.cpp +++ b/src/Identity.cpp @@ -92,7 +92,7 @@ void LocalIdentity::sign(uint8_t* sig, const uint8_t* message, int msg_len) cons ed25519_sign(sig, message, msg_len, pub_key, prv_key); } -void LocalIdentity::calcSharedSecret(uint8_t* secret, const uint8_t* other_pub_key) { +void LocalIdentity::calcSharedSecret(uint8_t* secret, const uint8_t* other_pub_key) const { ed25519_key_exchange(secret, other_pub_key, prv_key); } diff --git a/src/Identity.h b/src/Identity.h index e84c193..24a7c0f 100644 --- a/src/Identity.h +++ b/src/Identity.h @@ -71,7 +71,7 @@ public: * \param secret OUT - the 'shared secret' (must be PUB_KEY_SIZE bytes) * \param other_pub_key IN - the public key of second party in the exchange (must be PUB_KEY_SIZE bytes) */ - void calcSharedSecret(uint8_t* secret, const uint8_t* other_pub_key); + void calcSharedSecret(uint8_t* secret, const uint8_t* other_pub_key) const; bool readFrom(Stream& s); bool writeTo(Stream& s) const; diff --git a/src/helpers/ClientACL.cpp b/src/helpers/ClientACL.cpp new file mode 100644 index 0000000..23f7b33 --- /dev/null +++ b/src/helpers/ClientACL.cpp @@ -0,0 +1,128 @@ +#include "ClientACL.h" + +static File openWrite(FILESYSTEM* _fs, const char* filename) { + #if defined(NRF52_PLATFORM) || defined(STM32_PLATFORM) + _fs->remove(filename); + return _fs->open(filename, FILE_O_WRITE); + #elif defined(RP2040_PLATFORM) + return _fs->open(filename, "w"); + #else + return _fs->open(filename, "w", true); + #endif +} + +void ClientACL::load(FILESYSTEM* _fs) { + num_clients = 0; + if (_fs->exists("/s_contacts")) { + #if defined(RP2040_PLATFORM) + File file = _fs->open("/s_contacts", "r"); + #else + File file = _fs->open("/s_contacts"); + #endif + if (file) { + bool full = false; + while (!full) { + ClientInfo c; + uint8_t pub_key[32]; + uint8_t unused[6]; + + bool success = (file.read(pub_key, 32) == 32); + success = success && (file.read((uint8_t *) &c.permissions, 1) == 1); + success = success && (file.read(unused, 6) == 6); + success = success && (file.read((uint8_t *)&c.out_path_len, 1) == 1); + success = success && (file.read(c.out_path, 64) == 64); + success = success && (file.read(c.shared_secret, PUB_KEY_SIZE) == PUB_KEY_SIZE); + c.last_timestamp = 0; // transient + c.last_activity = 0; + + if (!success) break; // EOF + + c.id = mesh::Identity(pub_key); + if (num_clients < MAX_CLIENTS) { + clients[num_clients++] = c; + } else { + full = true; + } + } + file.close(); + } + } +} + +void ClientACL::save(FILESYSTEM* _fs) { + File file = openWrite(_fs, "/s_contacts"); + if (file) { + uint8_t unused[6]; + memset(unused, 0, sizeof(unused)); + + for (int i = 0; i < num_clients; i++) { + auto c = &clients[i]; + if (c->permissions == 0) continue; // skip deleted entries + + bool success = (file.write(c->id.pub_key, 32) == 32); + success = success && (file.write((uint8_t *) &c->permissions, 1) == 1); + success = success && (file.write(unused, 6) == 6); + success = success && (file.write((uint8_t *)&c->out_path_len, 1) == 1); + success = success && (file.write(c->out_path, 64) == 64); + success = success && (file.write(c->shared_secret, PUB_KEY_SIZE) == PUB_KEY_SIZE); + + if (!success) break; // write failed + } + file.close(); + } +} + +ClientInfo* ClientACL::getClient(const uint8_t* pubkey, int key_len) { + for (int i = 0; i < num_clients; i++) { + if (memcmp(pubkey, clients[i].id.pub_key, key_len) == 0) return &clients[i]; // already known + } + return NULL; // not found +} + +ClientInfo* ClientACL::putClient(const mesh::Identity& id, uint8_t init_perms) { + uint32_t min_time = 0xFFFFFFFF; + ClientInfo* oldest = &clients[MAX_CLIENTS - 1]; + for (int i = 0; i < num_clients; i++) { + if (id.matches(clients[i].id)) return &clients[i]; // already known + if (!clients[i].isAdmin() && clients[i].last_activity < min_time) { + oldest = &clients[i]; + min_time = oldest->last_activity; + } + } + + ClientInfo* c; + if (num_clients < MAX_CLIENTS) { + c = &clients[num_clients++]; + } else { + c = oldest; // evict least active contact + } + memset(c, 0, sizeof(*c)); + c->permissions = init_perms; + c->id = id; + c->out_path_len = -1; // initially out_path is unknown + return c; +} + +bool ClientACL::applyPermissions(const mesh::LocalIdentity& self_id, const uint8_t* pubkey, int key_len, uint8_t perms) { + ClientInfo* c; + if ((perms & PERM_ACL_ROLE_MASK) == PERM_ACL_GUEST) { // guest role is not persisted in contacts + c = getClient(pubkey, key_len); + if (c == NULL) return false; // partial pubkey not found + + num_clients--; // delete from contacts[] + int i = c - clients; + while (i < num_clients) { + clients[i] = clients[i + 1]; + i++; + } + } else { + if (key_len < PUB_KEY_SIZE) return false; // need complete pubkey when adding/modifying + + mesh::Identity id(pubkey); + c = putClient(id, 0); + + c->permissions = perms; // update their permissions + self_id.calcSharedSecret(c->shared_secret, pubkey); + } + return true; +} diff --git a/src/helpers/ClientACL.h b/src/helpers/ClientACL.h new file mode 100644 index 0000000..f8cc123 --- /dev/null +++ b/src/helpers/ClientACL.h @@ -0,0 +1,47 @@ +#pragma once + +#include <Arduino.h> // needed for PlatformIO +#include <Mesh.h> +#include <helpers/IdentityStore.h> + +#define PERM_ACL_ROLE_MASK 3 // lower 2 bits +#define PERM_ACL_GUEST 0 +#define PERM_ACL_READ_ONLY 1 +#define PERM_ACL_READ_WRITE 2 +#define PERM_ACL_ADMIN 3 + +struct ClientInfo { + mesh::Identity id; + uint8_t permissions; + int8_t out_path_len; + uint8_t out_path[MAX_PATH_SIZE]; + uint8_t shared_secret[PUB_KEY_SIZE]; + uint32_t last_timestamp; // by THEIR clock (transient) + uint32_t last_activity; // by OUR clock (transient) + + bool isAdmin() const { return (permissions & PERM_ACL_ROLE_MASK) == PERM_ACL_ADMIN; } +}; + +#ifndef MAX_CLIENTS + #define MAX_CLIENTS 20 +#endif + +class ClientACL { + ClientInfo clients[MAX_CLIENTS]; + int num_clients; + +public: + ClientACL() { + memset(clients, 0, sizeof(clients)); + num_clients = 0; + } + void load(FILESYSTEM* _fs); + void save(FILESYSTEM* _fs); + + ClientInfo* getClient(const uint8_t* pubkey, int key_len); + ClientInfo* putClient(const mesh::Identity& id, uint8_t init_perms); + bool applyPermissions(const mesh::LocalIdentity& self_id, const uint8_t* pubkey, int key_len, uint8_t perms); + + int getNumClients() const { return num_clients; } + ClientInfo* getClientByIdx(int idx) { return &clients[idx]; } +}; From 25ea953cc3d744fde55b0cd78ffe222b4af5715f Mon Sep 17 00:00:00 2001 From: liamcottle <liam@liamcottle.com> Date: Fri, 12 Sep 2025 20:23:21 +1200 Subject: [PATCH 49/50] don't mark as connected until connection secured --- src/helpers/nrf52/SerialBLEInterface.cpp | 14 ++++++++++---- src/helpers/nrf52/SerialBLEInterface.h | 1 + 2 files changed, 11 insertions(+), 4 deletions(-) diff --git a/src/helpers/nrf52/SerialBLEInterface.cpp b/src/helpers/nrf52/SerialBLEInterface.cpp index 4bc9d10..ad5823f 100644 --- a/src/helpers/nrf52/SerialBLEInterface.cpp +++ b/src/helpers/nrf52/SerialBLEInterface.cpp @@ -4,10 +4,7 @@ static SerialBLEInterface* instance; void SerialBLEInterface::onConnect(uint16_t connection_handle) { BLE_DEBUG_PRINTLN("SerialBLEInterface: connected"); - if(instance){ - instance->_isDeviceConnected = true; - // no need to stop advertising on connect, as the ble stack does this automatically - } + // we now set _isDeviceConnected=true in onSecured callback instead } void SerialBLEInterface::onDisconnect(uint16_t connection_handle, uint8_t reason) { @@ -18,6 +15,14 @@ void SerialBLEInterface::onDisconnect(uint16_t connection_handle, uint8_t reason } } +void SerialBLEInterface::onSecured(uint16_t connection_handle) { + BLE_DEBUG_PRINTLN("SerialBLEInterface: onSecured"); + if(instance){ + instance->_isDeviceConnected = true; + // no need to stop advertising on connect, as the ble stack does this automatically + } +} + void SerialBLEInterface::begin(const char* device_name, uint32_t pin_code) { instance = this; @@ -36,6 +41,7 @@ void SerialBLEInterface::begin(const char* device_name, uint32_t pin_code) { Bluefruit.Periph.setConnectCallback(onConnect); Bluefruit.Periph.setDisconnectCallback(onDisconnect); + Bluefruit.Security.setSecuredCallback(onSecured); // To be consistent OTA DFU should be added first if it exists //bledfu.begin(); diff --git a/src/helpers/nrf52/SerialBLEInterface.h b/src/helpers/nrf52/SerialBLEInterface.h index 239cf6c..bf29892 100644 --- a/src/helpers/nrf52/SerialBLEInterface.h +++ b/src/helpers/nrf52/SerialBLEInterface.h @@ -25,6 +25,7 @@ class SerialBLEInterface : public BaseSerialInterface { void clearBuffers() { send_queue_len = 0; } static void onConnect(uint16_t connection_handle); static void onDisconnect(uint16_t connection_handle, uint8_t reason); + static void onSecured(uint16_t connection_handle); public: SerialBLEInterface() { From b5820b1ce0ae8fb00baf8b51ae4111c614d769c9 Mon Sep 17 00:00:00 2001 From: Bryant Kelley <bryant@bryantkelley.com> Date: Fri, 12 Sep 2025 11:22:53 -0700 Subject: [PATCH 50/50] Add companion not showing up over BLE to FAQ --- docs/faq.md | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/docs/faq.md b/docs/faq.md index 6dc8fe9..391ceb5 100644 --- a/docs/faq.md +++ b/docs/faq.md @@ -63,10 +63,11 @@ author: https://github.com/LitBomb<!-- omit from toc --> - [6.1. Q: My client says another client or a repeater or a room server was last seen many, many days ago.](#61-q-my-client-says-another-client-or-a-repeater-or-a-room-server-was-last-seen-many-many-days-ago) - [6.2. Q: A repeater or a client or a room server I expect to see on my discover list (on T-Deck) or contact list (on a smart device client) are not listed.](#62-q-a-repeater-or-a-client-or-a-room-server-i-expect-to-see-on-my-discover-list-on-t-deck-or-contact-list-on-a-smart-device-client-are-not-listed) - [6.3. Q: How to connect to a repeater via BLE (Bluetooth)?](#63-q-how-to-connect-to-a-repeater-via-ble-bluetooth) - - [6.4. Q: I can't connect via Bluetooth, what is the Bluetooth pairing code?](#64-q-i-cant-connect-via-bluetooth-what-is-the-bluetooth-pairing-code) - - [6.5. Q: My Heltec V3 keeps disconnecting from my smartphone. It can't hold a solid Bluetooth connection.](#65-q-my-heltec-v3-keeps-disconnecting-from-my-smartphone--it-cant-hold-a-solid-bluetooth-connection) - - [6.6. Q: My RAK/T1000-E/xiao\_nRF52 device seems to be corrupted, how do I wipe it clean to start fresh?](#66-q-my-rakt1000-exiao_nrf52-device-seems-to-be-corrupted-how-do-i-wipe-it-clean-to-start-fresh) - - [6.7. Q: WebFlasher fails on Linux with failed to open](#67-q-webflasher-fails-on-linux-with-failed-to-open) + - [6.4. Q: My companion isn't showing up over Bluetooth?](#64-q-my-companion-isnt-showing-up-over-bluetooth) + - [6.5. Q: I can't connect via Bluetooth, what is the Bluetooth pairing code?](#64-q-i-cant-connect-via-bluetooth-what-is-the-bluetooth-pairing-code) + - [6.6. Q: My Heltec V3 keeps disconnecting from my smartphone. It can't hold a solid Bluetooth connection.](#65-q-my-heltec-v3-keeps-disconnecting-from-my-smartphone--it-cant-hold-a-solid-bluetooth-connection) + - [6.7. Q: My RAK/T1000-E/xiao\_nRF52 device seems to be corrupted, how do I wipe it clean to start fresh?](#66-q-my-rakt1000-exiao_nrf52-device-seems-to-be-corrupted-how-do-i-wipe-it-clean-to-start-fresh) + - [6.8. Q: WebFlasher fails on Linux with failed to open](#67-q-webflasher-fails-on-linux-with-failed-to-open) - [7. Other Questions:](#7-other-questions) - [7.1 Q: How to update nRF (RAK, T114, Seed XIAO) repeater and room server firmware over the air using the new simpler DFU app?](#71-q-how-to-update-nrf-rak-t114-seed-xiao-repeater-and-room-server-firmware-over-the-air-using-the-new-simpler-dfu-app) - [7.2 Q: How to update ESP32-based devices over the air?](#72-q-how-to-update-esp32-based-devices-over-the-air) @@ -563,15 +564,19 @@ You can get the epoch time on <https://www.epochconverter.com/> and use it to se ### 6.3. Q: How to connect to a repeater via BLE (Bluetooth)? **A:** You can't connect to a device running repeater firmware via Bluetooth. Devices running the BLE companion firmware you can connect to it via Bluetooth using the android app -### 6.4. Q: I can't connect via Bluetooth, what is the Bluetooth pairing code? +### 6.4. Q: My companion isn't showing up over Bluetooth? + +**A:** make sure that you flashed the Bluetooth companion firmware and not the USB-only companion firmware. + +### 6.5. Q: I can't connect via Bluetooth, what is the Bluetooth pairing code? **A:** the default Bluetooth pairing code is `123456` -### 6.5. Q: My Heltec V3 keeps disconnecting from my smartphone. It can't hold a solid Bluetooth connection. +### 6.6. Q: My Heltec V3 keeps disconnecting from my smartphone. It can't hold a solid Bluetooth connection. **A:** Heltec V3 has a very small coil antenna on its PCB for Wi-Fi and Bluetooth connectivity. It has a very short range, only a few feet. It is possible to remove the coil antenna and replace it with a 31mm wire. The BT range is much improved with the modification. -### 6.6. Q: My RAK/T1000-E/xiao_nRF52 device seems to be corrupted, how do I wipe it clean to start fresh? +### 6.7. Q: My RAK/T1000-E/xiao_nRF52 device seems to be corrupted, how do I wipe it clean to start fresh? **A:** 1. Connect USB-C cable to your device, per your device's instruction, get it to flash mode: @@ -591,8 +596,7 @@ You can get the epoch time on <https://www.epochconverter.com/> and use it to se Separately, starting in firmware version 1.7.0, there is a CLI Rescue mode. If your device has a user button (e.g. some RAK, T114), you can activate the rescue mode by hold down the user button of the device within 8 seconds of boot. Then you can use the 'Console' on flasher.meshcore.co.uk - -### 6.7. Q: WebFlasher fails on Linux with failed to open +### 6.8. Q: WebFlasher fails on Linux with failed to open **A:** If the usb port doesn't have the right ownership for this task, the process fails with the following error: `NetworkError: Failed to execute 'open' on 'SerialPort': Failed to open serial port.`