Compare commits

...

79 Commits

Author SHA1 Message Date
Matthias Wientapper
4da42d02d4 Disable flood adverts 2026-03-03 20:13:23 +01:00
Matthias Wientapper
16faa821eb Set RAK boot lock voltage to 0V 2026-03-03 20:13:23 +01:00
Matthias Wientapper
08341eb27a Integration of upstrem PR #1810 2026-03-03 20:13:23 +01:00
Matthias Wientapper
4d352d646a Integration of upstrem PR #1338 2026-03-03 20:13:23 +01:00
Matthias Wientapper
aee066dd0f Integration of upstrem PR #1297 2026-03-03 20:13:22 +01:00
Liam Cottle
cdd3d5f34e Merge pull request #1841 from weebl2000/nit-prefs
prefs is 5 char length :nerd:
2026-03-04 01:39:55 +13:00
ripplebiz
7c594ebc50 Merge pull request #1743 from weebl2000/fixagcreset
fix agc reset on SX126x, SX1276 & LR11x0 chips
2026-03-03 22:19:34 +11:00
Liam Cottle
ba3d9e264e Merge pull request #1836 from weebl2000/fix-rak3401-sky66122-11-fem
Fix RAK3401 SKY66122-11 FEM control: enable CSD/CPS for proper PA/LNA operation
2026-03-03 23:51:42 +13:00
Liam Cottle
d7ad89046b Merge pull request #1633 from weebl2000/fix/gps-uart-power-leak
Fix GPS UART consuming +8mA when disabled (nRF52)
2026-03-03 23:26:58 +13:00
Liam Cottle
67779aded8 Merge pull request #1600 from weebl2000/heltec_deep_sleep_lna
Hold GC1109 PA_POWER during deep sleep for LNA RX wake
2026-03-03 23:20:22 +13:00
Liam Cottle
bbd621ba85 Merge pull request #1351 from weebl2000/heltec_wireless_tracker_gps
Support GPS properly on Heltec Wireless Tracker v1.x
2026-03-03 23:11:46 +13:00
ripplebiz
6431cd2d47 Merge pull request #1900 from wbijen/feature/contact-filter-by-hops
Add configurable max hops filter for auto-add contacts
2026-03-03 21:05:44 +11:00
Wouter Bijen
1d190ad944 Clamp max_hops to 64 to cover full protocol hop range (0-63) 2026-03-03 09:05:53 +01:00
Wouter Bijen
2cb08775c0 Clarify comment wording: 1 = direct (0 hops)
Co-Authored-By: Claude Opus 4.6 <noreply@anthropic.com>
2026-03-03 08:40:17 +01:00
Wouter Bijen
c016db86d5 Address PR review: subtract-1 encoding and clamp max_hops
- Change > to >= so stored value 1 means direct/0-hop only (liamcottle)
- Clamp max_hops to 63 on write since getPathHashCount() caps at 63 (robekl)
- Update comments to reflect encoding: 0=no limit, 1=direct only, N=up to N-1 hops

Co-Authored-By: Claude Opus 4.6 <noreply@anthropic.com>
2026-03-03 08:37:22 +01:00
Wouter Bijen
00566741f6 Add configurable max hops filter for auto-add contacts
Filter auto-add of new contacts by hop count (issues #1533, #1546).
Setting is configurable from the companion app via extended
CMD_SET/GET_AUTOADD_CONFIG protocol (0 = no limit, 1-63 = max hops).

Co-Authored-By: Claude Opus 4.6 <noreply@anthropic.com>
2026-03-02 20:41:41 +01:00
Wessel Nieboer
8a9a0dca5f Fix GPS +8mA power leak when disabled (nRF52)
On the T114, GPS_RESET (pin 38) is the same pin as PIN_3V3_EN.
MicroNMEALocationProvider::begin() sets pin 38 HIGH (powering the 3V3
rail) but stop() never set it back LOW, leaving the GPS module powered
even when disabled.

Assert reset pin in stop() to mirror begin(), and guard
_location->loop() behind gps_active check.

Fixes meshcore-dev/MeshCore#1628
2026-02-28 19:13:42 +01:00
Wessel Nieboer
59d9770ab9 Add GPS support Heltec Wireless Tracker v1.x
Pin mapping verified against HTIT-Tracker V0.5 schematic:
- GPIO35 (GPS_EN): N-ch MOSFET drives P-ch high-side switch, active HIGH
- GPIO36 (GPS_RST): hardware reset, active LOW
- GPIO33/34: UART TX/RX

Delegates power management to MicroNMEALocationProvider begin()/stop()
which independently controls GPS power via GPS_EN and shares VEXT with
the display through RefCountedDigitalPin.
2026-02-28 19:09:28 +01:00
Wessel Nieboer
9bae9d0ed2 fix comment, we know the band now after checking LR1110 user manual 2026-02-28 19:09:25 +01:00
Wessel Nieboer
85f764a114 Calibrate configured frequency for AGC reset 2026-02-28 19:09:25 +01:00
Wessel Nieboer
f54948e06d Also implement LR11x10 AGC reset
Similar to SX126x but simpler.
2026-02-28 19:09:25 +01:00
Wessel Nieboer
b2032e11b6 make it more dry 2026-02-28 19:09:25 +01:00
Wessel Nieboer
9106ab46e1 reset noise_floor sampling after agc reset 2026-02-28 19:09:25 +01:00
Wessel Nieboer
a2dc2eb50c when doing AGC reset, call Calibrate(0x7F)
1. warm sleep
2. wake to stdby
3. Calibrate(0x7F) to reset all internal blocks
4. re-apply DIO2 RF / boosted gain & register patch to make sure
everything is as it was
2026-02-28 19:09:25 +01:00
Wessel Nieboer
f81ec4b14c fix agc reset 2026-02-28 19:09:25 +01:00
Wessel Nieboer
49d8313501 Fix pin mapping & TX switch (it's DIO2) 2026-02-28 19:09:06 +01:00
Wessel Nieboer
5a5568ed56 Drive CTX low first 2026-02-28 19:09:06 +01:00
Wessel Nieboer
ac2aa03b09 Add SX126X_REGISTER_PATCH for RAK3401 2026-02-28 19:09:06 +01:00
Wessel Nieboer
70f1ad4aeb Fix RAK3401 SKY66122-11 FEM control: enable CSD/CPS for proper PA and LNA operation
The RAK13302 1W module uses a Skyworks SKY66122-11 front-end module with
three digital control pins (CSD, CTX, CPS) that must be actively driven
by the host MCU. The previous code only managed CTX (GPIO 31) — toggling
it for TX/RX — but never initialized CSD (GPIO 24) or CPS (GPIO 21),
leaving them floating with no pull-up/pull-down resistors on the PCB.

With floating CSD and CPS, the SKY66122 was in an undefined operating
mode:
- The 30 dB TX PA may not have been reliably engaging
- The 16 dB RX LNA was never reliably active, degrading receive
sensitivity
2026-02-28 19:09:06 +01:00
Wessel Nieboer
d9e67222f5 prefs is 5 char length :nerd: 2026-02-28 19:07:38 +01:00
Wessel Nieboer
2bb6f636a4 Add 1ms delay after powering PA (cold-boot) 2026-02-28 19:05:31 +01:00
Wessel Nieboer
329e408197 Hold GC1109 PA_POWER during deep sleep for LNA RX wake
The GC1109 FEM needs its VFEM_Ctrl pin held HIGH during deep sleep
to keep the LNA active, enabling proper RX sensitivity for
wake-on-packet. Without this, the LNA is unpowered during sleep
and RX wake sensitivity is degraded by ~17dB.

Release RTC holds in begin() after configuring GPIO registers
(not before) to ensure glitch-free pin transitions on wake.

Trade-off: ~6.5mA additional sleep current for significantly
improved wake-on-packet range.
2026-02-28 19:05:31 +01:00
Matthias Wientapper
37d3afc17e Disable flood_adverts per default 2026-02-28 15:49:52 +01:00
Matthias Wientapper
516d784087 Add cli config flood.advert.base
0 = forwarding flood adverts off
1 = forwarding flood adverts on (unrestricted)
0.308 (default) = prob. forwarding according to #1338
2026-02-28 15:29:20 +01:00
Matthias Wientapper
3088d1862a Limit flood advert packet forwarding for roomservers as well 2026-02-28 15:29:20 +01:00
Matthias Wientapper
6f1e01a750 Limit flood advert packet forwarding, implements #1223 2026-02-28 15:25:43 +01:00
fdlamotte
06ab9f7f6b Merge pull request #1871 from enricolorenzoni59/gps-sync-reply
`gps sync` reply: fill buffer with text
2026-02-28 07:45:19 -04:00
enricolorenzoni59
8ad17d1022 gps sync reply: fill buffer with text 2026-02-28 09:07:30 +00:00
Liam Cottle
eee42c5099 Merge pull request #1569 from IoTThinks/MCdev-Fixed-Incorrect-Release-of-RefCountedDigitalPin
Fixed RefCountedDigitalPin.h and SSD1306Display for Heltec v4
2026-02-28 17:35:17 +13:00
Scott Powell
b67decfba0 * bug fix: Packet::writeTo(), Packet::readFrom() 2026-02-26 15:36:21 +11:00
Scott Powell
ca81f645ed Merge branch 'multibyte-paths' into dev 2026-02-26 12:30:23 +11:00
ripplebiz
5280433098 Merge pull request #1820 from recrof/patch-1
Update default preset to EU/UK (Narrow)
2026-02-26 12:08:17 +11:00
Scott Powell
def01889aa Merge branch 'dev' into multibyte-paths 2026-02-25 17:11:51 +11:00
Scott Powell
8737c64fdb * Packet::copyPath() fix 2026-02-25 17:10:31 +11:00
Liam Cottle
e6e87fb8ca Merge pull request #1838 from weebl2000/github_workflows_sanitycheck
Add basic sanity test github PR workflow
2026-02-25 14:52:10 +13:00
Wessel Nieboer
15cce12efd Add basic sanity test github PR workflow
Build a few generic variants to verify at least those compile. Can't
hurt.
2026-02-25 02:43:48 +01:00
Scott Powell
f4748a7f9d * misc 2026-02-24 21:30:04 +11:00
Rastislav Vysoky
b777a7c635 Update default preset to EU/UK (Narrow) 2026-02-24 11:28:23 +01:00
Scott Powell
b14879ce2d * CMD_GET_ADVERT_PATH bug fix 2026-02-24 14:23:59 +11:00
Liam Cottle
f7c8cf1146 Merge pull request #1808 from callum5892/dev
Added build flags for M5Stack Unit C6L
2026-02-24 12:24:56 +13:00
Stefan Berthold
f864c5f547 allow direct message paths when denyf * is set 2026-02-23 23:33:41 +01:00
callum5892
9f4eeeeceb Added build flags for M5Stack Unit C6L
Enabled USB-CDC on boot for M5Stack_Unit_C6L_companion_radio_usb to fix serial connection issues
2026-02-23 17:31:18 +00:00
Scott Powell
9d5c4865c3 * room server fix 2026-02-24 01:08:11 +11:00
Scott Powell
213d085012 * revert CMD_SEND_SELF_ADVERT, use _prefs.path_hash_mode 2026-02-24 00:08:13 +11:00
Scott Powell
45564bad9b * Dispatcher bug fixes 2026-02-23 23:51:30 +11:00
Scott Powell
5b0884ad2d * added CMD_SET_PATH_HASH_MODE 2026-02-23 21:08:22 +11:00
Scott Powell
e52d57c065 * companion: new pref: path_hash_mode (0..2)
* companion: new field in CMD_SET_OTHER_PARAMS, path_hash_mode
* companion: CMD_SEND_SELF_ADVERT, cmd_frame[1] now holds the path hash size (0 = zero hop, 1..3 = flood path hash size)
2026-02-23 18:26:56 +11:00
Scott Powell
a66773bac0 * CommonCLI: added "get/set path.hash.mode " 2026-02-23 14:25:19 +11:00
Scott Powell
05e7b682b9 Merge branch 'dev' into multibyte-paths 2026-02-23 13:11:36 +11:00
ripplebiz
9c318561da Merge pull request #1792 from ElectroMW/feature/t-beam-supreme-improvements
T-Beam Supreme - Make full use of board's 8MB Flash and add Companion WiFi target
2026-02-23 12:38:56 +11:00
ripplebiz
2e0fa3ec46 Merge pull request #1794 from accumulator/heltec_wireless_tracker_companion_usb
add companion usb build target for Heltec Wireless Tracker
2026-02-23 12:37:02 +11:00
ripplebiz
8ee4867397 Merge pull request #1795 from DanielNovak/fix-packetqueue-millis-wraparound
Fix millis() wraparound in PacketQueue time comparisons
2026-02-23 12:33:21 +11:00
Sam Koucha
5a885bffe4 Make full use of board's 8MB Flash and add companion WiFI target 2026-02-22 18:14:39 +00:00
Daniel Novak
011edd3c99 Fix millis() wraparound in PacketQueue time comparisons
PacketQueue::countBefore() and PacketQueue::get() use unsigned
comparison (_schedule_table[j] > now) to check if a packet is
scheduled for the future. This breaks when millis() wraps around
after ~49.7 days: packets scheduled just before the wrap appear
to be in the far future and get stuck in the queue.

Use signed subtraction instead, matching the approach already used
by Dispatcher::millisHasNowPassed(). This correctly handles the
wraparound for time differences up to ~24.8 days in either
direction, well beyond the maximum queue delay of 32 seconds.
2026-02-22 18:01:55 +01:00
Sander van Grieken
3dc14976a0 add companion usb build target for Heltec Wireless Tracker 2026-02-22 17:57:36 +01:00
Matthias Wientapper
b039af0b52 Rak bootlock voltage set to 0x 2026-02-21 19:21:38 +01:00
Scott Powell
3e76161e9c * refactor of Contact/Client out_path_len (stored in files), from signed to unsigned byte (+2 squashed commits)
Squashed commits:
[f326e25] * misc
[fa5152e] * new 'path mode' parsing in Dispatcher
2026-02-21 19:35:51 +11:00
ripplebiz
d05d6abab8 Merge pull request #1726 from weebl2000/fix-packet-pool-leak-queue-full
Fix packet pool leak when rx queue is full
2026-02-21 17:18:02 +11:00
ripplebiz
c2abe894c9 Merge pull request #1728 from oltaco/nrf52-bootloader-version
NRF52: Add get bootloader.ver command for NRF52
2026-02-21 12:56:52 +11:00
Kevin Le
13d0dff918 Reverted to use GPIO 17, 18 as I2C for Heltec v4 repeater 2026-02-18 22:38:24 +07:00
Kevin Le
44b80d00c2 Disabled periph_power for Heltec v4's display 2026-02-18 22:32:01 +07:00
Kevin Le
f6603fe7a5 Set back PIN_VEXT_EN_ACTIVE=HIGH 2026-02-18 22:32:01 +07:00
Kevin Le
39fb2902ec Avoid negative _claims 2026-02-18 22:32:01 +07:00
Kevin Le
063f5056f2 Fixed RefCountedDigitalPin.h to release claim correctly. Ensure no negative claims number. 2026-02-18 22:32:01 +07:00
taco
1500a5a9cb add get bootloader.ver command for nrf52 2026-02-18 15:35:20 +11:00
Wessel Nieboer
ffc9815e9a Fix packet pool leak when rx queue is full
PacketQueue::add() silently dropped packets when the queue was at
capacity. The packet pointer was lost — never enqueued, never returned
to the unused pool. Each occurrence permanently shrank the 32-packet
pool until allocNew() returned NULL and the node went deaf. Return bool
from add() and free the packet back to the pool on failure.
2026-02-17 23:54:33 +01:00
ViezeVingertjes
519b97a90a Updated the Dispatcher logic to replace hardcoded values with defined constants for minimum TX budget reserve and airtime division. 2026-02-07 19:07:33 +01:00
ViezeVingertjes
30d6588792 Update logic in Dispatcher to ensure refill is only applied when greater than zero. 2026-02-07 18:26:39 +01:00
ViezeVingertjes
eb4fa032ff Implement token bucket duty cycle enforcement 2026-01-04 21:33:46 +01:00
60 changed files with 772 additions and 280 deletions

43
.github/workflows/pr-build-check.yml vendored Normal file
View File

@@ -0,0 +1,43 @@
name: PR Build Check
on:
pull_request:
branches: [main, dev]
paths:
- 'src/**'
- 'examples/**'
- 'variants/**'
- 'platformio.ini'
- '.github/workflows/pr-build-check.yml'
jobs:
build:
runs-on: ubuntu-latest
strategy:
fail-fast: false
matrix:
environment:
# ESP32-S3 (most common platform)
- Heltec_v3_companion_radio_ble
- Heltec_v3_repeater
- Heltec_v3_room_server
# nRF52
- RAK_4631_companion_radio_ble
- RAK_4631_repeater
- RAK_4631_room_server
# RP2040
- PicoW_repeater
# STM32
- wio-e5-mini_repeater
# ESP32-C6
- LilyGo_Tlora_C6_repeater_
steps:
- name: Clone Repo
uses: actions/checkout@v4
- name: Setup Build Environment
uses: ./.github/actions/setup-build-environment
- name: Build ${{ matrix.environment }}
run: pio run -e ${{ matrix.environment }}

View File

@@ -41,7 +41,7 @@
"name": "LilyGo T-Beam supreme (8MB Flash 8MB PSRAM)", "name": "LilyGo T-Beam supreme (8MB Flash 8MB PSRAM)",
"upload": { "upload": {
"flash_size": "8MB", "flash_size": "8MB",
"maximum_ram_size": 327680, "maximum_ram_size": 8388608,
"maximum_size": 8388608, "maximum_size": 8388608,
"require_upload_port": true, "require_upload_port": true,
"speed": 460800 "speed": 460800

View File

@@ -222,12 +222,14 @@ void DataStore::loadPrefsInt(const char *filename, NodePrefs& _prefs, double& no
file.read((uint8_t *)&_prefs.rx_delay_base, sizeof(_prefs.rx_delay_base)); // 72 file.read((uint8_t *)&_prefs.rx_delay_base, sizeof(_prefs.rx_delay_base)); // 72
file.read((uint8_t *)&_prefs.advert_loc_policy, sizeof(_prefs.advert_loc_policy)); // 76 file.read((uint8_t *)&_prefs.advert_loc_policy, sizeof(_prefs.advert_loc_policy)); // 76
file.read((uint8_t *)&_prefs.multi_acks, sizeof(_prefs.multi_acks)); // 77 file.read((uint8_t *)&_prefs.multi_acks, sizeof(_prefs.multi_acks)); // 77
file.read(pad, 2); // 78 file.read((uint8_t *)&_prefs.path_hash_mode, sizeof(_prefs.path_hash_mode)); // 78
file.read(pad, 1); // 79
file.read((uint8_t *)&_prefs.ble_pin, sizeof(_prefs.ble_pin)); // 80 file.read((uint8_t *)&_prefs.ble_pin, sizeof(_prefs.ble_pin)); // 80
file.read((uint8_t *)&_prefs.buzzer_quiet, sizeof(_prefs.buzzer_quiet)); // 84 file.read((uint8_t *)&_prefs.buzzer_quiet, sizeof(_prefs.buzzer_quiet)); // 84
file.read((uint8_t *)&_prefs.gps_enabled, sizeof(_prefs.gps_enabled)); // 85 file.read((uint8_t *)&_prefs.gps_enabled, sizeof(_prefs.gps_enabled)); // 85
file.read((uint8_t *)&_prefs.gps_interval, sizeof(_prefs.gps_interval)); // 86 file.read((uint8_t *)&_prefs.gps_interval, sizeof(_prefs.gps_interval)); // 86
file.read((uint8_t *)&_prefs.autoadd_config, sizeof(_prefs.autoadd_config)); // 87 file.read((uint8_t *)&_prefs.autoadd_config, sizeof(_prefs.autoadd_config)); // 87
file.read((uint8_t *)&_prefs.autoadd_max_hops, sizeof(_prefs.autoadd_max_hops)); // 88
file.close(); file.close();
} }
@@ -257,12 +259,14 @@ void DataStore::savePrefs(const NodePrefs& _prefs, double node_lat, double node_
file.write((uint8_t *)&_prefs.rx_delay_base, sizeof(_prefs.rx_delay_base)); // 72 file.write((uint8_t *)&_prefs.rx_delay_base, sizeof(_prefs.rx_delay_base)); // 72
file.write((uint8_t *)&_prefs.advert_loc_policy, sizeof(_prefs.advert_loc_policy)); // 76 file.write((uint8_t *)&_prefs.advert_loc_policy, sizeof(_prefs.advert_loc_policy)); // 76
file.write((uint8_t *)&_prefs.multi_acks, sizeof(_prefs.multi_acks)); // 77 file.write((uint8_t *)&_prefs.multi_acks, sizeof(_prefs.multi_acks)); // 77
file.write(pad, 2); // 78 file.write((uint8_t *)&_prefs.path_hash_mode, sizeof(_prefs.path_hash_mode)); // 78
file.write(pad, 1); // 79
file.write((uint8_t *)&_prefs.ble_pin, sizeof(_prefs.ble_pin)); // 80 file.write((uint8_t *)&_prefs.ble_pin, sizeof(_prefs.ble_pin)); // 80
file.write((uint8_t *)&_prefs.buzzer_quiet, sizeof(_prefs.buzzer_quiet)); // 84 file.write((uint8_t *)&_prefs.buzzer_quiet, sizeof(_prefs.buzzer_quiet)); // 84
file.write((uint8_t *)&_prefs.gps_enabled, sizeof(_prefs.gps_enabled)); // 85 file.write((uint8_t *)&_prefs.gps_enabled, sizeof(_prefs.gps_enabled)); // 85
file.write((uint8_t *)&_prefs.gps_interval, sizeof(_prefs.gps_interval)); // 86 file.write((uint8_t *)&_prefs.gps_interval, sizeof(_prefs.gps_interval)); // 86
file.write((uint8_t *)&_prefs.autoadd_config, sizeof(_prefs.autoadd_config)); // 87 file.write((uint8_t *)&_prefs.autoadd_config, sizeof(_prefs.autoadd_config)); // 87
file.write((uint8_t *)&_prefs.autoadd_max_hops, sizeof(_prefs.autoadd_max_hops)); // 88
file.close(); file.close();
} }

View File

@@ -57,6 +57,7 @@
#define CMD_SET_AUTOADD_CONFIG 58 #define CMD_SET_AUTOADD_CONFIG 58
#define CMD_GET_AUTOADD_CONFIG 59 #define CMD_GET_AUTOADD_CONFIG 59
#define CMD_GET_ALLOWED_REPEAT_FREQ 60 #define CMD_GET_ALLOWED_REPEAT_FREQ 60
#define CMD_SET_PATH_HASH_MODE 61
// Stats sub-types for CMD_GET_STATS // Stats sub-types for CMD_GET_STATS
#define STATS_TYPE_CORE 0 #define STATS_TYPE_CORE 0
@@ -258,11 +259,11 @@ int MyMesh::calcRxDelay(float score, uint32_t air_time) const {
} }
uint32_t MyMesh::getRetransmitDelay(const mesh::Packet *packet) { uint32_t MyMesh::getRetransmitDelay(const mesh::Packet *packet) {
uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * 0.5f); uint32_t t = (_radio->getEstAirtimeFor(packet->getPathByteLen() + packet->payload_len + 2) * 0.5f);
return getRNG()->nextInt(0, 5*t + 1); return getRNG()->nextInt(0, 5*t + 1);
} }
uint32_t MyMesh::getDirectRetransmitDelay(const mesh::Packet *packet) { uint32_t MyMesh::getDirectRetransmitDelay(const mesh::Packet *packet) {
uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * 0.2f); uint32_t t = (_radio->getEstAirtimeFor(packet->getPathByteLen() + packet->payload_len + 2) * 0.2f);
return getRNG()->nextInt(0, 5*t + 1); return getRNG()->nextInt(0, 5*t + 1);
} }
@@ -317,6 +318,10 @@ bool MyMesh::shouldOverwriteWhenFull() const {
return (_prefs.autoadd_config & AUTO_ADD_OVERWRITE_OLDEST) != 0; return (_prefs.autoadd_config & AUTO_ADD_OVERWRITE_OLDEST) != 0;
} }
uint8_t MyMesh::getAutoAddMaxHops() const {
return _prefs.autoadd_max_hops;
}
void MyMesh::onContactOverwrite(const uint8_t* pub_key) { void MyMesh::onContactOverwrite(const uint8_t* pub_key) {
_store->deleteBlobByKey(pub_key, PUB_KEY_SIZE); // delete from storage _store->deleteBlobByKey(pub_key, PUB_KEY_SIZE); // delete from storage
if (_serial->isConnected()) { if (_serial->isConnected()) {
@@ -349,7 +354,7 @@ void MyMesh::onDiscoveredContact(ContactInfo &contact, bool is_new, uint8_t path
} }
// add inbound-path to mem cache // add inbound-path to mem cache
if (path && path_len <= sizeof(AdvertPath::path)) { // check path is valid if (path && mesh::Packet::isValidPathLen(path_len)) { // check path is valid
AdvertPath* p = advert_paths; AdvertPath* p = advert_paths;
uint32_t oldest = 0xFFFFFFFF; uint32_t oldest = 0xFFFFFFFF;
for (int i = 0; i < ADVERT_PATH_TABLE_SIZE; i++) { // check if already in table, otherwise evict oldest for (int i = 0; i < ADVERT_PATH_TABLE_SIZE; i++) { // check if already in table, otherwise evict oldest
@@ -366,8 +371,7 @@ void MyMesh::onDiscoveredContact(ContactInfo &contact, bool is_new, uint8_t path
memcpy(p->pubkey_prefix, contact.id.pub_key, sizeof(p->pubkey_prefix)); memcpy(p->pubkey_prefix, contact.id.pub_key, sizeof(p->pubkey_prefix));
strcpy(p->name, contact.name); strcpy(p->name, contact.name);
p->recv_timestamp = getRTCClock()->getCurrentTime(); p->recv_timestamp = getRTCClock()->getCurrentTime();
p->path_len = path_len; p->path_len = mesh::Packet::copyPath(p->path, path, path_len);
memcpy(p->path, path, p->path_len);
} }
if (!is_new) dirty_contacts_expiry = futureMillis(LAZY_CONTACTS_WRITE_DELAY); // only schedule lazy write for contacts that are in contacts[] if (!is_new) dirty_contacts_expiry = futureMillis(LAZY_CONTACTS_WRITE_DELAY); // only schedule lazy write for contacts that are in contacts[]
@@ -473,23 +477,23 @@ bool MyMesh::allowPacketForward(const mesh::Packet* packet) {
void MyMesh::sendFloodScoped(const ContactInfo& recipient, mesh::Packet* pkt, uint32_t delay_millis) { void MyMesh::sendFloodScoped(const ContactInfo& recipient, mesh::Packet* pkt, uint32_t delay_millis) {
// TODO: dynamic send_scope, depending on recipient and current 'home' Region // TODO: dynamic send_scope, depending on recipient and current 'home' Region
if (send_scope.isNull()) { if (send_scope.isNull()) {
sendFlood(pkt, delay_millis); sendFlood(pkt, delay_millis, _prefs.path_hash_mode + 1);
} else { } else {
uint16_t codes[2]; uint16_t codes[2];
codes[0] = send_scope.calcTransportCode(pkt); codes[0] = send_scope.calcTransportCode(pkt);
codes[1] = 0; // REVISIT: set to 'home' Region, for sender/return region? codes[1] = 0; // REVISIT: set to 'home' Region, for sender/return region?
sendFlood(pkt, codes, delay_millis); sendFlood(pkt, codes, delay_millis, _prefs.path_hash_mode + 1);
} }
} }
void MyMesh::sendFloodScoped(const mesh::GroupChannel& channel, mesh::Packet* pkt, uint32_t delay_millis) { void MyMesh::sendFloodScoped(const mesh::GroupChannel& channel, mesh::Packet* pkt, uint32_t delay_millis) {
// TODO: have per-channel send_scope // TODO: have per-channel send_scope
if (send_scope.isNull()) { if (send_scope.isNull()) {
sendFlood(pkt, delay_millis); sendFlood(pkt, delay_millis, _prefs.path_hash_mode + 1);
} else { } else {
uint16_t codes[2]; uint16_t codes[2];
codes[0] = send_scope.calcTransportCode(pkt); codes[0] = send_scope.calcTransportCode(pkt);
codes[1] = 0; // REVISIT: set to 'home' Region, for sender/return region? codes[1] = 0; // REVISIT: set to 'home' Region, for sender/return region?
sendFlood(pkt, codes, delay_millis); sendFlood(pkt, codes, delay_millis, _prefs.path_hash_mode + 1);
} }
} }
@@ -686,7 +690,7 @@ bool MyMesh::onContactPathRecv(ContactInfo& contact, uint8_t* in_path, uint8_t i
if (tag == pending_discovery) { // check for matching response tag) if (tag == pending_discovery) { // check for matching response tag)
pending_discovery = 0; pending_discovery = 0;
if (in_path_len > MAX_PATH_SIZE || out_path_len > MAX_PATH_SIZE) { if (!mesh::Packet::isValidPathLen(in_path_len) || !mesh::Packet::isValidPathLen(out_path_len)) {
MESH_DEBUG_PRINTLN("onContactPathRecv, invalid path sizes: %d, %d", in_path_len, out_path_len); MESH_DEBUG_PRINTLN("onContactPathRecv, invalid path sizes: %d, %d", in_path_len, out_path_len);
} else { } else {
int i = 0; int i = 0;
@@ -695,11 +699,9 @@ bool MyMesh::onContactPathRecv(ContactInfo& contact, uint8_t* in_path, uint8_t i
memcpy(&out_frame[i], contact.id.pub_key, 6); memcpy(&out_frame[i], contact.id.pub_key, 6);
i += 6; // pub_key_prefix i += 6; // pub_key_prefix
out_frame[i++] = out_path_len; out_frame[i++] = out_path_len;
memcpy(&out_frame[i], out_path, out_path_len); i += mesh::Packet::writePath(&out_frame[i], out_path, out_path_len);
i += out_path_len;
out_frame[i++] = in_path_len; out_frame[i++] = in_path_len;
memcpy(&out_frame[i], in_path, in_path_len); i += mesh::Packet::writePath(&out_frame[i], in_path, in_path_len);
i += in_path_len;
// NOTE: telemetry data in 'extra' is discarded at present // NOTE: telemetry data in 'extra' is discarded at present
_serial->writeFrame(out_frame, i); _serial->writeFrame(out_frame, i);
@@ -785,9 +787,10 @@ uint32_t MyMesh::calcFloodTimeoutMillisFor(uint32_t pkt_airtime_millis) const {
return SEND_TIMEOUT_BASE_MILLIS + (FLOOD_SEND_TIMEOUT_FACTOR * pkt_airtime_millis); return SEND_TIMEOUT_BASE_MILLIS + (FLOOD_SEND_TIMEOUT_FACTOR * pkt_airtime_millis);
} }
uint32_t MyMesh::calcDirectTimeoutMillisFor(uint32_t pkt_airtime_millis, uint8_t path_len) const { uint32_t MyMesh::calcDirectTimeoutMillisFor(uint32_t pkt_airtime_millis, uint8_t path_len) const {
uint8_t path_hash_count = path_len & 63;
return SEND_TIMEOUT_BASE_MILLIS + return SEND_TIMEOUT_BASE_MILLIS +
((pkt_airtime_millis * DIRECT_SEND_PERHOP_FACTOR + DIRECT_SEND_PERHOP_EXTRA_MILLIS) * ((pkt_airtime_millis * DIRECT_SEND_PERHOP_FACTOR + DIRECT_SEND_PERHOP_EXTRA_MILLIS) *
(path_len + 1)); (path_hash_count + 1));
} }
void MyMesh::onSendTimeout() {} void MyMesh::onSendTimeout() {}
@@ -808,7 +811,7 @@ MyMesh::MyMesh(mesh::Radio &radio, mesh::RNG &rng, mesh::RTCClock &rtc, SimpleMe
// defaults // defaults
memset(&_prefs, 0, sizeof(_prefs)); memset(&_prefs, 0, sizeof(_prefs));
_prefs.airtime_factor = 1.0; // one half _prefs.airtime_factor = 1.0;
strcpy(_prefs.node_name, "NONAME"); strcpy(_prefs.node_name, "NONAME");
_prefs.freq = LORA_FREQ; _prefs.freq = LORA_FREQ;
_prefs.sf = LORA_SF; _prefs.sf = LORA_SF;
@@ -938,6 +941,7 @@ void MyMesh::handleCmdFrame(size_t len) {
StrHelper::strzcpy((char *)&out_frame[i], FIRMWARE_VERSION, 20); StrHelper::strzcpy((char *)&out_frame[i], FIRMWARE_VERSION, 20);
i += 20; i += 20;
out_frame[i++] = _prefs.client_repeat; // v9+ out_frame[i++] = _prefs.client_repeat; // v9+
out_frame[i++] = _prefs.path_hash_mode; // v10+
_serial->writeFrame(out_frame, i); _serial->writeFrame(out_frame, i);
} else if (cmd_frame[0] == CMD_APP_START && } else if (cmd_frame[0] == CMD_APP_START &&
len >= 8) { // sent when app establishes connection, respond with node ID len >= 8) { // sent when app establishes connection, respond with node ID
@@ -1115,7 +1119,8 @@ void MyMesh::handleCmdFrame(size_t len) {
} }
if (pkt) { if (pkt) {
if (len >= 2 && cmd_frame[1] == 1) { // optional param (1 = flood, 0 = zero hop) if (len >= 2 && cmd_frame[1] == 1) { // optional param (1 = flood, 0 = zero hop)
sendFlood(pkt); unsigned long delay_millis = 0;
sendFlood(pkt, delay_millis, _prefs.path_hash_mode + 1);
} else { } else {
sendZeroHop(pkt); sendZeroHop(pkt);
} }
@@ -1127,7 +1132,7 @@ void MyMesh::handleCmdFrame(size_t len) {
uint8_t *pub_key = &cmd_frame[1]; uint8_t *pub_key = &cmd_frame[1];
ContactInfo *recipient = lookupContactByPubKey(pub_key, PUB_KEY_SIZE); ContactInfo *recipient = lookupContactByPubKey(pub_key, PUB_KEY_SIZE);
if (recipient) { if (recipient) {
recipient->out_path_len = -1; recipient->out_path_len = OUT_PATH_UNKNOWN;
// recipient->lastmod = ?? shouldn't be needed, app already has this version of contact // recipient->lastmod = ?? shouldn't be needed, app already has this version of contact
dirty_contacts_expiry = futureMillis(LAZY_CONTACTS_WRITE_DELAY); dirty_contacts_expiry = futureMillis(LAZY_CONTACTS_WRITE_DELAY);
writeOKFrame(); writeOKFrame();
@@ -1312,6 +1317,14 @@ void MyMesh::handleCmdFrame(size_t len) {
} }
savePrefs(); savePrefs();
writeOKFrame(); writeOKFrame();
} else if (cmd_frame[0] == CMD_SET_PATH_HASH_MODE && cmd_frame[1] == 0 && len >= 3) {
if (cmd_frame[2] >= 3) {
writeErrFrame(ERR_CODE_ILLEGAL_ARG);
} else {
_prefs.path_hash_mode = cmd_frame[2];
savePrefs();
writeOKFrame();
}
} else if (cmd_frame[0] == CMD_REBOOT && memcmp(&cmd_frame[1], "reboot", 6) == 0) { } else if (cmd_frame[0] == CMD_REBOOT && memcmp(&cmd_frame[1], "reboot", 6) == 0) {
if (dirty_contacts_expiry) { // is there are pending dirty contacts write needed? if (dirty_contacts_expiry) { // is there are pending dirty contacts write needed?
saveContacts(); saveContacts();
@@ -1449,7 +1462,7 @@ void MyMesh::handleCmdFrame(size_t len) {
memset(&req_data[2], 0, 3); // reserved memset(&req_data[2], 0, 3); // reserved
getRNG()->random(&req_data[5], 4); // random blob to help make packet-hash unique getRNG()->random(&req_data[5], 4); // random blob to help make packet-hash unique
auto save = recipient->out_path_len; // temporarily force sendRequest() to flood auto save = recipient->out_path_len; // temporarily force sendRequest() to flood
recipient->out_path_len = -1; recipient->out_path_len = OUT_PATH_UNKNOWN;
int result = sendRequest(*recipient, req_data, sizeof(req_data), tag, est_timeout); int result = sendRequest(*recipient, req_data, sizeof(req_data), tag, est_timeout);
recipient->out_path_len = save; recipient->out_path_len = save;
if (result == MSG_SEND_FAILED) { if (result == MSG_SEND_FAILED) {
@@ -1686,11 +1699,12 @@ void MyMesh::handleCmdFrame(size_t len) {
} }
} }
if (found) { if (found) {
out_frame[0] = RESP_CODE_ADVERT_PATH; int i = 0;
memcpy(&out_frame[1], &found->recv_timestamp, 4); out_frame[i++] = RESP_CODE_ADVERT_PATH;
out_frame[5] = found->path_len; memcpy(&out_frame[i], &found->recv_timestamp, 4); i += 4;
memcpy(&out_frame[6], found->path, found->path_len); out_frame[i++] = found->path_len;
_serial->writeFrame(out_frame, 6 + found->path_len); i += mesh::Packet::writePath(&out_frame[i], found->path, found->path_len);
_serial->writeFrame(out_frame, i);
} else { } else {
writeErrFrame(ERR_CODE_NOT_FOUND); writeErrFrame(ERR_CODE_NOT_FOUND);
} }
@@ -1775,12 +1789,16 @@ void MyMesh::handleCmdFrame(size_t len) {
} }
} else if (cmd_frame[0] == CMD_SET_AUTOADD_CONFIG) { } else if (cmd_frame[0] == CMD_SET_AUTOADD_CONFIG) {
_prefs.autoadd_config = cmd_frame[1]; _prefs.autoadd_config = cmd_frame[1];
if (len >= 3) {
_prefs.autoadd_max_hops = min(cmd_frame[2], (uint8_t)64);
}
savePrefs(); savePrefs();
writeOKFrame(); writeOKFrame();
} else if (cmd_frame[0] == CMD_GET_AUTOADD_CONFIG) { } else if (cmd_frame[0] == CMD_GET_AUTOADD_CONFIG) {
int i = 0; int i = 0;
out_frame[i++] = RESP_CODE_AUTOADD_CONFIG; out_frame[i++] = RESP_CODE_AUTOADD_CONFIG;
out_frame[i++] = _prefs.autoadd_config; out_frame[i++] = _prefs.autoadd_config;
out_frame[i++] = _prefs.autoadd_max_hops;
_serial->writeFrame(out_frame, i); _serial->writeFrame(out_frame, i);
} else if (cmd_frame[0] == CMD_GET_ALLOWED_REPEAT_FREQ) { } else if (cmd_frame[0] == CMD_GET_ALLOWED_REPEAT_FREQ) {
int i = 0; int i = 0;

View File

@@ -5,7 +5,7 @@
#include "AbstractUITask.h" #include "AbstractUITask.h"
/*------------ Frame Protocol --------------*/ /*------------ Frame Protocol --------------*/
#define FIRMWARE_VER_CODE 9 #define FIRMWARE_VER_CODE 10
#ifndef FIRMWARE_BUILD_DATE #ifndef FIRMWARE_BUILD_DATE
#define FIRMWARE_BUILD_DATE "15 Feb 2026" #define FIRMWARE_BUILD_DATE "15 Feb 2026"
@@ -119,6 +119,7 @@ protected:
bool isAutoAddEnabled() const override; bool isAutoAddEnabled() const override;
bool shouldAutoAddContactType(uint8_t type) const override; bool shouldAutoAddContactType(uint8_t type) const override;
bool shouldOverwriteWhenFull() const override; bool shouldOverwriteWhenFull() const override;
uint8_t getAutoAddMaxHops() const override;
void onContactsFull() override; void onContactsFull() override;
void onContactOverwrite(const uint8_t* pub_key) override; void onContactOverwrite(const uint8_t* pub_key) override;
bool onContactPathRecv(ContactInfo& from, uint8_t* in_path, uint8_t in_path_len, uint8_t* out_path, uint8_t out_path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) override; bool onContactPathRecv(ContactInfo& from, uint8_t* in_path, uint8_t in_path_len, uint8_t* out_path, uint8_t out_path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) override;

View File

@@ -29,4 +29,6 @@ struct NodePrefs { // persisted to file
uint32_t gps_interval; // GPS read interval in seconds uint32_t gps_interval; // GPS read interval in seconds
uint8_t autoadd_config; // bitmask for auto-add contacts config uint8_t autoadd_config; // bitmask for auto-add contacts config
uint8_t client_repeat; uint8_t client_repeat;
uint8_t path_hash_mode; // which path mode to use when sending
uint8_t autoadd_max_hops; // 0 = no limit, 1 = direct (0 hops), N = up to N-1 hops (max 64)
}; };

View File

@@ -129,7 +129,7 @@ uint8_t MyMesh::handleLoginReq(const mesh::Identity& sender, const uint8_t* secr
} }
if (is_flood) { if (is_flood) {
client->out_path_len = -1; // need to rediscover out_path client->out_path_len = OUT_PATH_UNKNOWN; // need to rediscover out_path
} }
uint32_t now = getRTCClock()->getCurrentTimeUnique(); uint32_t now = getRTCClock()->getCurrentTimeUnique();
@@ -147,9 +147,12 @@ uint8_t MyMesh::handleLoginReq(const mesh::Identity& sender, const uint8_t* secr
uint8_t MyMesh::handleAnonRegionsReq(const mesh::Identity& sender, uint32_t sender_timestamp, const uint8_t* data) { uint8_t MyMesh::handleAnonRegionsReq(const mesh::Identity& sender, uint32_t sender_timestamp, const uint8_t* data) {
if (anon_limiter.allow(rtc_clock.getCurrentTime())) { if (anon_limiter.allow(rtc_clock.getCurrentTime())) {
// request data has: {reply-path-len}{reply-path} // request data has: {reply-path-len}{reply-path}
reply_path_len = *data++ & 0x3F; reply_path_len = *data & 63;
memcpy(reply_path, data, reply_path_len); reply_path_hash_size = (*data >> 6) + 1;
// data += reply_path_len; data++;
memcpy(reply_path, data, ((uint8_t)reply_path_len) * reply_path_hash_size);
// data += (uint8_t)reply_path_len * reply_path_hash_size;
memcpy(reply_data, &sender_timestamp, 4); // prefix with sender_timestamp, like a tag memcpy(reply_data, &sender_timestamp, 4); // prefix with sender_timestamp, like a tag
uint32_t now = getRTCClock()->getCurrentTime(); uint32_t now = getRTCClock()->getCurrentTime();
@@ -163,9 +166,12 @@ uint8_t MyMesh::handleAnonRegionsReq(const mesh::Identity& sender, uint32_t send
uint8_t MyMesh::handleAnonOwnerReq(const mesh::Identity& sender, uint32_t sender_timestamp, const uint8_t* data) { uint8_t MyMesh::handleAnonOwnerReq(const mesh::Identity& sender, uint32_t sender_timestamp, const uint8_t* data) {
if (anon_limiter.allow(rtc_clock.getCurrentTime())) { if (anon_limiter.allow(rtc_clock.getCurrentTime())) {
// request data has: {reply-path-len}{reply-path} // request data has: {reply-path-len}{reply-path}
reply_path_len = *data++ & 0x3F; reply_path_len = *data & 63;
memcpy(reply_path, data, reply_path_len); reply_path_hash_size = (*data >> 6) + 1;
// data += reply_path_len; data++;
memcpy(reply_path, data, ((uint8_t)reply_path_len) * reply_path_hash_size);
// data += (uint8_t)reply_path_len * reply_path_hash_size;
memcpy(reply_data, &sender_timestamp, 4); // prefix with sender_timestamp, like a tag memcpy(reply_data, &sender_timestamp, 4); // prefix with sender_timestamp, like a tag
uint32_t now = getRTCClock()->getCurrentTime(); uint32_t now = getRTCClock()->getCurrentTime();
@@ -180,9 +186,12 @@ uint8_t MyMesh::handleAnonOwnerReq(const mesh::Identity& sender, uint32_t sender
uint8_t MyMesh::handleAnonClockReq(const mesh::Identity& sender, uint32_t sender_timestamp, const uint8_t* data) { uint8_t MyMesh::handleAnonClockReq(const mesh::Identity& sender, uint32_t sender_timestamp, const uint8_t* data) {
if (anon_limiter.allow(rtc_clock.getCurrentTime())) { if (anon_limiter.allow(rtc_clock.getCurrentTime())) {
// request data has: {reply-path-len}{reply-path} // request data has: {reply-path-len}{reply-path}
reply_path_len = *data++ & 0x3F; reply_path_len = *data & 63;
memcpy(reply_path, data, reply_path_len); reply_path_hash_size = (*data >> 6) + 1;
// data += reply_path_len; data++;
memcpy(reply_path, data, ((uint8_t)reply_path_len) * reply_path_hash_size);
// data += (uint8_t)reply_path_len * reply_path_hash_size;
memcpy(reply_data, &sender_timestamp, 4); // prefix with sender_timestamp, like a tag memcpy(reply_data, &sender_timestamp, 4); // prefix with sender_timestamp, like a tag
uint32_t now = getRTCClock()->getCurrentTime(); uint32_t now = getRTCClock()->getCurrentTime();
@@ -389,11 +398,19 @@ File MyMesh::openAppend(const char *fname) {
bool MyMesh::allowPacketForward(const mesh::Packet *packet) { bool MyMesh::allowPacketForward(const mesh::Packet *packet) {
if (_prefs.disable_fwd) return false; if (_prefs.disable_fwd) return false;
if (packet->isRouteFlood() && packet->path_len >= _prefs.flood_max) return false; if (packet->isRouteFlood() && packet->getPathHashCount() >= _prefs.flood_max) return false;
if (packet->isRouteFlood() && recv_pkt_region == NULL) { if (packet->isRouteFlood() && recv_pkt_region == NULL) {
MESH_DEBUG_PRINTLN("allowPacketForward: unknown transport code, or wildcard not allowed for FLOOD packet"); MESH_DEBUG_PRINTLN("allowPacketForward: unknown transport code, or wildcard not allowed for FLOOD packet");
return false; return false;
} }
// Limit flood advert paket forwarding using a probabilistic reduction defined by P(h) = 0.308^(hops-1)
// https://github.com/meshcore-dev/MeshCore/issues/1223
double_t roll_dice = (double)rand() / RAND_MAX;
double_t forw_prob = pow(_prefs.flood_advert_base, packet->path_len - 1);
if (packet->getPayloadType() == PAYLOAD_TYPE_ADVERT && packet->isRouteFlood() && roll_dice > forw_prob)
return false;
// all other packets
return true; return true;
} }
@@ -484,11 +501,11 @@ int MyMesh::calcRxDelay(float score, uint32_t air_time) const {
} }
uint32_t MyMesh::getRetransmitDelay(const mesh::Packet *packet) { uint32_t MyMesh::getRetransmitDelay(const mesh::Packet *packet) {
uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.tx_delay_factor); uint32_t t = (_radio->getEstAirtimeFor(packet->getPathByteLen() + packet->payload_len + 2) * _prefs.tx_delay_factor);
return getRNG()->nextInt(0, 5*t + 1); return getRNG()->nextInt(0, 5*t + 1);
} }
uint32_t MyMesh::getDirectRetransmitDelay(const mesh::Packet *packet) { 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); uint32_t t = (_radio->getEstAirtimeFor(packet->getPathByteLen() + packet->payload_len + 2) * _prefs.direct_tx_delay_factor);
return getRNG()->nextInt(0, 5*t + 1); return getRNG()->nextInt(0, 5*t + 1);
} }
@@ -497,7 +514,10 @@ bool MyMesh::filterRecvFloodPacket(mesh::Packet* pkt) {
if (pkt->getRouteType() == ROUTE_TYPE_TRANSPORT_FLOOD) { if (pkt->getRouteType() == ROUTE_TYPE_TRANSPORT_FLOOD) {
recv_pkt_region = region_map.findMatch(pkt, REGION_DENY_FLOOD); recv_pkt_region = region_map.findMatch(pkt, REGION_DENY_FLOOD);
} else if (pkt->getRouteType() == ROUTE_TYPE_FLOOD) { } else if (pkt->getRouteType() == ROUTE_TYPE_FLOOD) {
if (region_map.getWildcard().flags & REGION_DENY_FLOOD) { if ((pkt->getPayloadType() == PAYLOAD_TYPE_GRP_TXT ||
pkt->getPayloadType() == PAYLOAD_TYPE_GRP_DATA ||
pkt->getPayloadType() == PAYLOAD_TYPE_ADVERT) &&
region_map.getWildcard().flags & REGION_DENY_FLOOD) {
recv_pkt_region = NULL; recv_pkt_region = NULL;
} else { } else {
recv_pkt_region = &region_map.getWildcard(); recv_pkt_region = &region_map.getWildcard();
@@ -538,13 +558,14 @@ void MyMesh::onAnonDataRecv(mesh::Packet *packet, const uint8_t *secret, const m
// let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response
mesh::Packet* path = createPathReturn(sender, secret, packet->path, packet->path_len, mesh::Packet* path = createPathReturn(sender, secret, packet->path, packet->path_len,
PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); PAYLOAD_TYPE_RESPONSE, reply_data, reply_len);
if (path) sendFlood(path, SERVER_RESPONSE_DELAY); if (path) sendFlood(path, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} else if (reply_path_len < 0) { } else if (reply_path_len < 0) {
mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, secret, reply_data, reply_len); mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, secret, reply_data, reply_len);
if (reply) sendFlood(reply, SERVER_RESPONSE_DELAY); if (reply) sendFlood(reply, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} else { } else {
mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, secret, reply_data, reply_len); mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, secret, reply_data, reply_len);
if (reply) sendDirect(reply, reply_path, reply_path_len, SERVER_RESPONSE_DELAY); uint8_t path_len = ((reply_path_hash_size - 1) << 6) | (reply_path_len & 63);
if (reply) sendDirect(reply, reply_path, path_len, SERVER_RESPONSE_DELAY);
} }
} }
} }
@@ -613,15 +634,15 @@ void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx,
// let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response // 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, mesh::Packet *path = createPathReturn(client->id, secret, packet->path, packet->path_len,
PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); PAYLOAD_TYPE_RESPONSE, reply_data, reply_len);
if (path) sendFlood(path, SERVER_RESPONSE_DELAY); if (path) sendFlood(path, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} else { } else {
mesh::Packet *reply = mesh::Packet *reply =
createDatagram(PAYLOAD_TYPE_RESPONSE, client->id, secret, reply_data, reply_len); createDatagram(PAYLOAD_TYPE_RESPONSE, client->id, secret, reply_data, reply_len);
if (reply) { if (reply) {
if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT if (client->out_path_len != OUT_PATH_UNKNOWN) { // we have an out_path, so send DIRECT
sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY);
} else { } else {
sendFlood(reply, SERVER_RESPONSE_DELAY); sendFlood(reply, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} }
} }
} }
@@ -651,8 +672,8 @@ void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx,
mesh::Packet *ack = createAck(ack_hash); mesh::Packet *ack = createAck(ack_hash);
if (ack) { if (ack) {
if (client->out_path_len < 0) { if (client->out_path_len == OUT_PATH_UNKNOWN) {
sendFlood(ack, TXT_ACK_DELAY); sendFlood(ack, TXT_ACK_DELAY, packet->getPathHashSize());
} else { } else {
sendDirect(ack, client->out_path, client->out_path_len, TXT_ACK_DELAY); sendDirect(ack, client->out_path, client->out_path_len, TXT_ACK_DELAY);
} }
@@ -679,8 +700,8 @@ void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx,
auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, secret, temp, 5 + text_len); auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, secret, temp, 5 + text_len);
if (reply) { if (reply) {
if (client->out_path_len < 0) { if (client->out_path_len == OUT_PATH_UNKNOWN) {
sendFlood(reply, CLI_REPLY_DELAY_MILLIS); sendFlood(reply, CLI_REPLY_DELAY_MILLIS, packet->getPathHashSize());
} else { } else {
sendDirect(reply, client->out_path, client->out_path_len, CLI_REPLY_DELAY_MILLIS); sendDirect(reply, client->out_path, client->out_path_len, CLI_REPLY_DELAY_MILLIS);
} }
@@ -701,7 +722,8 @@ bool MyMesh::onPeerPathRecv(mesh::Packet *packet, int sender_idx, const uint8_t
MESH_DEBUG_PRINTLN("PATH to client, path_len=%d", (uint32_t)path_len); MESH_DEBUG_PRINTLN("PATH to client, path_len=%d", (uint32_t)path_len);
auto client = acl.getClientByIdx(i); auto client = acl.getClientByIdx(i);
memcpy(client->out_path, path, client->out_path_len = path_len); // store a copy of path, for sendDirect() // store a copy of path, for sendDirect()
client->out_path_len = mesh::Packet::copyPath(client->out_path, path, path_len);
client->last_activity = getRTCClock()->getCurrentTime(); client->last_activity = getRTCClock()->getCurrentTime();
} else { } else {
MESH_DEBUG_PRINTLN("onPeerPathRecv: invalid peer idx: %d", i); MESH_DEBUG_PRINTLN("onPeerPathRecv: invalid peer idx: %d", i);
@@ -813,7 +835,7 @@ MyMesh::MyMesh(mesh::MainBoard &board, mesh::Radio &radio, mesh::MillisecondCloc
// defaults // defaults
memset(&_prefs, 0, sizeof(_prefs)); memset(&_prefs, 0, sizeof(_prefs));
_prefs.airtime_factor = 1.0; // one half _prefs.airtime_factor = 1.0;
_prefs.rx_delay_base = 0.0f; // turn off by default, was 10.0; _prefs.rx_delay_base = 0.0f; // turn off by default, was 10.0;
_prefs.tx_delay_factor = 0.5f; // was 0.25f _prefs.tx_delay_factor = 0.5f; // was 0.25f
_prefs.direct_tx_delay_factor = 0.3f; // was 0.2 _prefs.direct_tx_delay_factor = 0.3f; // was 0.2
@@ -827,7 +849,8 @@ MyMesh::MyMesh(mesh::MainBoard &board, mesh::Radio &radio, mesh::MillisecondCloc
_prefs.cr = LORA_CR; _prefs.cr = LORA_CR;
_prefs.tx_power_dbm = LORA_TX_POWER; _prefs.tx_power_dbm = LORA_TX_POWER;
_prefs.advert_interval = 1; // default to 2 minutes for NEW installs _prefs.advert_interval = 1; // default to 2 minutes for NEW installs
_prefs.flood_advert_interval = 12; // 12 hours _prefs.flood_advert_interval = 0; // 12 hours
_prefs.flood_advert_base = 0.308f;
_prefs.flood_max = 64; _prefs.flood_max = 64;
_prefs.interference_threshold = 0; // disabled _prefs.interference_threshold = 0; // disabled
@@ -906,7 +929,7 @@ void MyMesh::sendSelfAdvertisement(int delay_millis, bool flood) {
mesh::Packet *pkt = createSelfAdvert(); mesh::Packet *pkt = createSelfAdvert();
if (pkt) { if (pkt) {
if (flood) { if (flood) {
sendFlood(pkt, delay_millis); sendFlood(pkt, delay_millis, _prefs.path_hash_mode + 1);
} else { } else {
sendZeroHop(pkt, delay_millis); sendZeroHop(pkt, delay_millis);
} }

View File

@@ -92,6 +92,7 @@ class MyMesh : public mesh::Mesh, public CommonCLICallbacks {
uint8_t reply_data[MAX_PACKET_PAYLOAD]; uint8_t reply_data[MAX_PACKET_PAYLOAD];
uint8_t reply_path[MAX_PATH_SIZE]; uint8_t reply_path[MAX_PATH_SIZE];
int8_t reply_path_len; int8_t reply_path_len;
uint8_t reply_path_hash_size;
TransportKeyStore key_store; TransportKeyStore key_store;
RegionMap region_map, temp_map; RegionMap region_map, temp_map;
RegionEntry* load_stack[8]; RegionEntry* load_stack[8];

View File

@@ -73,13 +73,15 @@ void MyMesh::pushPostToClient(ClientInfo *client, PostInfo &post) {
auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, client->shared_secret, reply_data, len); auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, client->shared_secret, reply_data, len);
if (reply) { if (reply) {
if (client->out_path_len < 0) { if (client->out_path_len == OUT_PATH_UNKNOWN) {
sendFlood(reply); unsigned long delay_millis = 0;
sendFlood(reply, delay_millis, _prefs.path_hash_mode + 1);
client->extra.room.ack_timeout = futureMillis(PUSH_ACK_TIMEOUT_FLOOD); client->extra.room.ack_timeout = futureMillis(PUSH_ACK_TIMEOUT_FLOOD);
} else { } else {
sendDirect(reply, client->out_path, client->out_path_len); sendDirect(reply, client->out_path, client->out_path_len);
client->extra.room.ack_timeout =
futureMillis(PUSH_TIMEOUT_BASE + PUSH_ACK_TIMEOUT_FACTOR * (client->out_path_len + 1)); uint8_t path_hash_count = client->out_path_len & 63;
client->extra.room.ack_timeout = futureMillis(PUSH_TIMEOUT_BASE + PUSH_ACK_TIMEOUT_FACTOR * (path_hash_count + 1));
} }
_num_post_pushes++; // stats _num_post_pushes++; // stats
} else { } else {
@@ -264,17 +266,26 @@ const char *MyMesh::getLogDateTime() {
} }
uint32_t MyMesh::getRetransmitDelay(const mesh::Packet *packet) { uint32_t MyMesh::getRetransmitDelay(const mesh::Packet *packet) {
uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.tx_delay_factor); uint32_t t = (_radio->getEstAirtimeFor(packet->getPathByteLen() + packet->payload_len + 2) * _prefs.tx_delay_factor);
return getRNG()->nextInt(0, 5*t + 1); return getRNG()->nextInt(0, 5*t + 1);
} }
uint32_t MyMesh::getDirectRetransmitDelay(const mesh::Packet *packet) { 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); uint32_t t = (_radio->getEstAirtimeFor(packet->getPathByteLen() + packet->payload_len + 2) * _prefs.direct_tx_delay_factor);
return getRNG()->nextInt(0, 5*t + 1); return getRNG()->nextInt(0, 5*t + 1);
} }
bool MyMesh::allowPacketForward(const mesh::Packet *packet) { bool MyMesh::allowPacketForward(const mesh::Packet *packet) {
if (_prefs.disable_fwd) return false; if (_prefs.disable_fwd) return false;
if (packet->isRouteFlood() && packet->path_len >= _prefs.flood_max) return false; if (packet->isRouteFlood() && packet->getPathHashCount() >= _prefs.flood_max) return false;
// Limit flood advert paket forwarding using a probabilistic reduction defined by P(h) = 0.308^(hops-1)
// https://github.com/meshcore-dev/MeshCore/issues/1223
double_t roll_dice = (double)rand() / RAND_MAX;
double_t forw_prob = pow(_prefs.flood_advert_base, packet->path_len - 1);
if (packet->getPayloadType() == PAYLOAD_TYPE_ADVERT && packet->isRouteFlood() && roll_dice > forw_prob)
return false;
// all other packets
return true; return true;
} }
@@ -333,7 +344,7 @@ void MyMesh::onAnonDataRecv(mesh::Packet *packet, const uint8_t *secret, const m
} }
if (packet->isRouteFlood()) { if (packet->isRouteFlood()) {
client->out_path_len = -1; // need to rediscover out_path client->out_path_len = OUT_PATH_UNKNOWN; // need to rediscover out_path
} }
uint32_t now = getRTCClock()->getCurrentTimeUnique(); uint32_t now = getRTCClock()->getCurrentTimeUnique();
@@ -353,14 +364,14 @@ void MyMesh::onAnonDataRecv(mesh::Packet *packet, const uint8_t *secret, const m
// let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response
mesh::Packet *path = createPathReturn(sender, client->shared_secret, packet->path, packet->path_len, mesh::Packet *path = createPathReturn(sender, client->shared_secret, packet->path, packet->path_len,
PAYLOAD_TYPE_RESPONSE, reply_data, 13); PAYLOAD_TYPE_RESPONSE, reply_data, 13);
if (path) sendFlood(path, SERVER_RESPONSE_DELAY); if (path) sendFlood(path, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} else { } else {
mesh::Packet *reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, client->shared_secret, reply_data, 13); mesh::Packet *reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, client->shared_secret, reply_data, 13);
if (reply) { if (reply) {
if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT if (client->out_path_len != OUT_PATH_UNKNOWN) { // we have an out_path, so send DIRECT
sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY);
} else { } else {
sendFlood(reply, SERVER_RESPONSE_DELAY); sendFlood(reply, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} }
} }
} }
@@ -448,9 +459,9 @@ void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx,
uint32_t delay_millis; uint32_t delay_millis;
if (send_ack) { if (send_ack) {
if (client->out_path_len < 0) { if (client->out_path_len == OUT_PATH_UNKNOWN) {
mesh::Packet *ack = createAck(ack_hash); mesh::Packet *ack = createAck(ack_hash);
if (ack) sendFlood(ack, TXT_ACK_DELAY); if (ack) sendFlood(ack, TXT_ACK_DELAY, packet->getPathHashSize());
delay_millis = TXT_ACK_DELAY + REPLY_DELAY_MILLIS; delay_millis = TXT_ACK_DELAY + REPLY_DELAY_MILLIS;
} else { } else {
uint32_t d = TXT_ACK_DELAY; uint32_t d = TXT_ACK_DELAY;
@@ -482,8 +493,8 @@ void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx,
auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, secret, temp, 5 + text_len); auto reply = createDatagram(PAYLOAD_TYPE_TXT_MSG, client->id, secret, temp, 5 + text_len);
if (reply) { if (reply) {
if (client->out_path_len < 0) { if (client->out_path_len == OUT_PATH_UNKNOWN) {
sendFlood(reply, delay_millis + SERVER_RESPONSE_DELAY); sendFlood(reply, delay_millis + SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} else { } else {
sendDirect(reply, client->out_path, client->out_path_len, delay_millis + SERVER_RESPONSE_DELAY); sendDirect(reply, client->out_path, client->out_path_len, delay_millis + SERVER_RESPONSE_DELAY);
} }
@@ -521,7 +532,7 @@ void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx,
// if client sends too quickly, evict() // if client sends too quickly, evict()
// RULE: only send keep_alive response DIRECT! // RULE: only send keep_alive response DIRECT!
if (client->out_path_len >= 0) { if (client->out_path_len != OUT_PATH_UNKNOWN) {
uint32_t ack_hash; // calc ACK to prove to sender that we got request 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); mesh::Utils::sha256((uint8_t *)&ack_hash, 4, data, 9, client->id.pub_key, PUB_KEY_SIZE);
@@ -538,14 +549,14 @@ void MyMesh::onPeerDataRecv(mesh::Packet *packet, uint8_t type, int sender_idx,
// let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response // 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, mesh::Packet *path = createPathReturn(client->id, secret, packet->path, packet->path_len,
PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); PAYLOAD_TYPE_RESPONSE, reply_data, reply_len);
if (path) sendFlood(path, SERVER_RESPONSE_DELAY); if (path) sendFlood(path, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} else { } else {
mesh::Packet *reply = createDatagram(PAYLOAD_TYPE_RESPONSE, client->id, secret, reply_data, reply_len); mesh::Packet *reply = createDatagram(PAYLOAD_TYPE_RESPONSE, client->id, secret, reply_data, reply_len);
if (reply) { if (reply) {
if (client->out_path_len >= 0) { // we have an out_path, so send DIRECT if (client->out_path_len != OUT_PATH_UNKNOWN) { // we have an out_path, so send DIRECT
sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY); sendDirect(reply, client->out_path, client->out_path_len, SERVER_RESPONSE_DELAY);
} else { } else {
sendFlood(reply, SERVER_RESPONSE_DELAY); sendFlood(reply, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} }
} }
} }
@@ -563,7 +574,7 @@ bool MyMesh::onPeerPathRecv(mesh::Packet *packet, int sender_idx, const uint8_t
if (i >= 0 && i < acl.getNumClients()) { // get from our known_clients table (sender SHOULD already be known in this context) if (i >= 0 && i < acl.getNumClients()) { // 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); MESH_DEBUG_PRINTLN("PATH to client, path_len=%d", (uint32_t)path_len);
auto client = acl.getClientByIdx(i); auto client = acl.getClientByIdx(i);
memcpy(client->out_path, path, client->out_path_len = path_len); // store a copy of path, for sendDirect() client->out_path_len = mesh::Packet::copyPath(client->out_path, path, path_len); // store a copy of path, for sendDirect()
client->last_activity = getRTCClock()->getCurrentTime(); client->last_activity = getRTCClock()->getCurrentTime();
} else { } else {
MESH_DEBUG_PRINTLN("onPeerPathRecv: invalid peer idx: %d", i); MESH_DEBUG_PRINTLN("onPeerPathRecv: invalid peer idx: %d", i);
@@ -597,7 +608,7 @@ MyMesh::MyMesh(mesh::MainBoard &board, mesh::Radio &radio, mesh::MillisecondCloc
// defaults // defaults
memset(&_prefs, 0, sizeof(_prefs)); memset(&_prefs, 0, sizeof(_prefs));
_prefs.airtime_factor = 1.0; // one half _prefs.airtime_factor = 1.0;
_prefs.rx_delay_base = 0.0f; // off by default, was 10.0 _prefs.rx_delay_base = 0.0f; // off by default, was 10.0
_prefs.tx_delay_factor = 0.5f; // was 0.25f; _prefs.tx_delay_factor = 0.5f; // was 0.25f;
_prefs.direct_tx_delay_factor = 0.2f; // was zero _prefs.direct_tx_delay_factor = 0.2f; // was zero
@@ -612,7 +623,8 @@ MyMesh::MyMesh(mesh::MainBoard &board, mesh::Radio &radio, mesh::MillisecondCloc
_prefs.tx_power_dbm = LORA_TX_POWER; _prefs.tx_power_dbm = LORA_TX_POWER;
_prefs.disable_fwd = 1; _prefs.disable_fwd = 1;
_prefs.advert_interval = 1; // default to 2 minutes for NEW installs _prefs.advert_interval = 1; // default to 2 minutes for NEW installs
_prefs.flood_advert_interval = 12; // 12 hours _prefs.flood_advert_interval = 0; // 12 hours
_prefs.flood_advert_base = 0.308f;
_prefs.flood_max = 64; _prefs.flood_max = 64;
_prefs.interference_threshold = 0; // disabled _prefs.interference_threshold = 0; // disabled
#ifdef ROOM_PASSWORD #ifdef ROOM_PASSWORD
@@ -679,7 +691,7 @@ void MyMesh::sendSelfAdvertisement(int delay_millis, bool flood) {
mesh::Packet *pkt = createSelfAdvert(); mesh::Packet *pkt = createSelfAdvert();
if (pkt) { if (pkt) {
if (flood) { if (flood) {
sendFlood(pkt, delay_millis); sendFlood(pkt, delay_millis, _prefs.path_hash_mode + 1);
} else { } else {
sendZeroHop(pkt, delay_millis); sendZeroHop(pkt, delay_millis);
} }

View File

@@ -213,7 +213,7 @@ protected:
} }
void onContactPathUpdated(const ContactInfo& contact) override { void onContactPathUpdated(const ContactInfo& contact) override {
Serial.printf("PATH to: %s, path_len=%d\n", contact.name, (int32_t) contact.out_path_len); Serial.printf("PATH to: %s, path_len=%d\n", contact.name, (uint32_t) contact.out_path_len);
saveContacts(); saveContacts();
} }
@@ -266,8 +266,9 @@ protected:
return SEND_TIMEOUT_BASE_MILLIS + (FLOOD_SEND_TIMEOUT_FACTOR * pkt_airtime_millis); return SEND_TIMEOUT_BASE_MILLIS + (FLOOD_SEND_TIMEOUT_FACTOR * pkt_airtime_millis);
} }
uint32_t calcDirectTimeoutMillisFor(uint32_t pkt_airtime_millis, uint8_t path_len) const override { uint32_t calcDirectTimeoutMillisFor(uint32_t pkt_airtime_millis, uint8_t path_len) const override {
uint8_t path_hash_count = path_len & 63;
return SEND_TIMEOUT_BASE_MILLIS + return SEND_TIMEOUT_BASE_MILLIS +
( (pkt_airtime_millis*DIRECT_SEND_PERHOP_FACTOR + DIRECT_SEND_PERHOP_EXTRA_MILLIS) * (path_len + 1)); ( (pkt_airtime_millis*DIRECT_SEND_PERHOP_FACTOR + DIRECT_SEND_PERHOP_EXTRA_MILLIS) * (path_hash_count + 1));
} }
void onSendTimeout() override { void onSendTimeout() override {
@@ -280,7 +281,7 @@ public:
{ {
// defaults // defaults
memset(&_prefs, 0, sizeof(_prefs)); memset(&_prefs, 0, sizeof(_prefs));
_prefs.airtime_factor = 2.0; // one third _prefs.airtime_factor = 1.0;
strcpy(_prefs.node_name, "NONAME"); strcpy(_prefs.node_name, "NONAME");
_prefs.freq = LORA_FREQ; _prefs.freq = LORA_FREQ;
_prefs.tx_power_dbm = LORA_TX_POWER; _prefs.tx_power_dbm = LORA_TX_POWER;

View File

@@ -258,10 +258,11 @@ void SensorMesh::sendAlert(const ClientInfo* c, Trigger* t) {
auto pkt = createDatagram(PAYLOAD_TYPE_TXT_MSG, c->id, c->shared_secret, data, 5 + text_len); auto pkt = createDatagram(PAYLOAD_TYPE_TXT_MSG, c->id, c->shared_secret, data, 5 + text_len);
if (pkt) { if (pkt) {
if (c->out_path_len >= 0) { // we have an out_path, so send DIRECT if (c->out_path_len != OUT_PATH_UNKNOWN) { // we have an out_path, so send DIRECT
sendDirect(pkt, c->out_path, c->out_path_len); sendDirect(pkt, c->out_path, c->out_path_len);
} else { } else {
sendFlood(pkt); unsigned long delay_millis = 0;
sendFlood(pkt, delay_millis, _prefs.path_hash_mode + 1);
} }
} }
t->send_expiry = futureMillis(ALERT_ACK_EXPIRY_MILLIS); t->send_expiry = futureMillis(ALERT_ACK_EXPIRY_MILLIS);
@@ -302,7 +303,7 @@ float SensorMesh::getAirtimeBudgetFactor() const {
bool SensorMesh::allowPacketForward(const mesh::Packet* packet) { bool SensorMesh::allowPacketForward(const mesh::Packet* packet) {
if (_prefs.disable_fwd) return false; if (_prefs.disable_fwd) return false;
if (packet->isRouteFlood() && packet->path_len >= _prefs.flood_max) return false; if (packet->isRouteFlood() && packet->getPathHashCount() >= _prefs.flood_max) return false;
return true; return true;
} }
@@ -312,11 +313,11 @@ int SensorMesh::calcRxDelay(float score, uint32_t air_time) const {
} }
uint32_t SensorMesh::getRetransmitDelay(const mesh::Packet* packet) { uint32_t SensorMesh::getRetransmitDelay(const mesh::Packet* packet) {
uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.tx_delay_factor); uint32_t t = (_radio->getEstAirtimeFor(packet->getPathByteLen() + packet->payload_len + 2) * _prefs.tx_delay_factor);
return getRNG()->nextInt(0, 6)*t; return getRNG()->nextInt(0, 6)*t;
} }
uint32_t SensorMesh::getDirectRetransmitDelay(const mesh::Packet* packet) { uint32_t SensorMesh::getDirectRetransmitDelay(const mesh::Packet* packet) {
uint32_t t = (_radio->getEstAirtimeFor(packet->path_len + packet->payload_len + 2) * _prefs.direct_tx_delay_factor); uint32_t t = (_radio->getEstAirtimeFor(packet->getPathByteLen() + packet->payload_len + 2) * _prefs.direct_tx_delay_factor);
return getRNG()->nextInt(0, 6)*t; return getRNG()->nextInt(0, 6)*t;
} }
int SensorMesh::getInterferenceThreshold() const { int SensorMesh::getInterferenceThreshold() const {
@@ -360,7 +361,7 @@ uint8_t SensorMesh::handleLoginReq(const mesh::Identity& sender, const uint8_t*
} }
if (is_flood) { if (is_flood) {
client->out_path_len = -1; // need to rediscover out_path client->out_path_len = OUT_PATH_UNKNOWN; // need to rediscover out_path
} }
uint32_t now = getRTCClock()->getCurrentTimeUnique(); uint32_t now = getRTCClock()->getCurrentTimeUnique();
@@ -468,10 +469,10 @@ void SensorMesh::onAnonDataRecv(mesh::Packet* packet, const uint8_t* secret, con
// let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response // let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response
mesh::Packet* path = createPathReturn(sender, secret, packet->path, packet->path_len, mesh::Packet* path = createPathReturn(sender, secret, packet->path, packet->path_len,
PAYLOAD_TYPE_RESPONSE, reply_data, reply_len); PAYLOAD_TYPE_RESPONSE, reply_data, reply_len);
if (path) sendFlood(path, SERVER_RESPONSE_DELAY); if (path) sendFlood(path, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} else { } else {
mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, secret, reply_data, reply_len); mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, sender, secret, reply_data, reply_len);
if (reply) sendFlood(reply, SERVER_RESPONSE_DELAY); if (reply) sendFlood(reply, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} }
} }
} }
@@ -496,10 +497,10 @@ void SensorMesh::getPeerSharedSecret(uint8_t* dest_secret, int peer_idx) {
} }
} }
void SensorMesh::sendAckTo(const ClientInfo& dest, uint32_t ack_hash) { void SensorMesh::sendAckTo(const ClientInfo& dest, uint32_t ack_hash, uint8_t path_hash_size) {
if (dest.out_path_len < 0) { if (dest.out_path_len == OUT_PATH_UNKNOWN) {
mesh::Packet* ack = createAck(ack_hash); mesh::Packet* ack = createAck(ack_hash);
if (ack) sendFlood(ack, TXT_ACK_DELAY); if (ack) sendFlood(ack, TXT_ACK_DELAY, path_hash_size);
} else { } else {
uint32_t d = TXT_ACK_DELAY; uint32_t d = TXT_ACK_DELAY;
if (getExtraAckTransmitCount() > 0) { if (getExtraAckTransmitCount() > 0) {
@@ -537,14 +538,14 @@ void SensorMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_i
// let this sender know path TO here, so they can use sendDirect(), and ALSO encode the response // 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); PAYLOAD_TYPE_RESPONSE, reply_data, reply_len);
if (path) sendFlood(path, SERVER_RESPONSE_DELAY); if (path) sendFlood(path, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} else { } 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 (reply) {
if (from->out_path_len >= 0) { // we have an out_path, so send DIRECT if (from->out_path_len != OUT_PATH_UNKNOWN) { // we have an out_path, so send DIRECT
sendDirect(reply, from->out_path, from->out_path_len, SERVER_RESPONSE_DELAY); sendDirect(reply, from->out_path, from->out_path_len, SERVER_RESPONSE_DELAY);
} else { } else {
sendFlood(reply, SERVER_RESPONSE_DELAY); sendFlood(reply, SERVER_RESPONSE_DELAY, packet->getPathHashSize());
} }
} }
} }
@@ -567,9 +568,9 @@ void SensorMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_i
// let this sender know path TO here, so they can use sendDirect(), and ALSO encode the ACK // 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, mesh::Packet* path = createPathReturn(from->id, secret, packet->path, packet->path_len,
PAYLOAD_TYPE_ACK, (uint8_t *) &ack_hash, 4); PAYLOAD_TYPE_ACK, (uint8_t *) &ack_hash, 4);
if (path) sendFlood(path, TXT_ACK_DELAY); if (path) sendFlood(path, TXT_ACK_DELAY, packet->getPathHashSize());
} else { } else {
sendAckTo(*from, ack_hash); sendAckTo(*from, ack_hash, packet->getPathHashSize());
} }
} }
} else if (flags == TXT_TYPE_CLI_DATA) { } else if (flags == TXT_TYPE_CLI_DATA) {
@@ -596,8 +597,8 @@ void SensorMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender_i
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 (reply) {
if (from->out_path_len < 0) { if (from->out_path_len == OUT_PATH_UNKNOWN) {
sendFlood(reply, CLI_REPLY_DELAY_MILLIS); sendFlood(reply, CLI_REPLY_DELAY_MILLIS, packet->getPathHashSize());
} else { } 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);
} }
@@ -666,7 +667,7 @@ bool SensorMesh::onPeerPathRecv(mesh::Packet* packet, int sender_idx, const uint
MESH_DEBUG_PRINTLN("PATH to contact, path_len=%d", (uint32_t) path_len); 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. // 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'(?) // 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->out_path_len = mesh::Packet::copyPath(from->out_path, path, path_len); // store a copy of path, for sendDirect()
from->last_activity = getRTCClock()->getCurrentTime(); from->last_activity = getRTCClock()->getCurrentTime();
// REVISIT: maybe make ALL out_paths non-persisted to minimise flash writes?? // REVISIT: maybe make ALL out_paths non-persisted to minimise flash writes??
@@ -705,7 +706,7 @@ SensorMesh::SensorMesh(mesh::MainBoard& board, mesh::Radio& radio, mesh::Millise
// defaults // defaults
memset(&_prefs, 0, sizeof(_prefs)); memset(&_prefs, 0, sizeof(_prefs));
_prefs.airtime_factor = 1.0; // one half _prefs.airtime_factor = 1.0;
_prefs.rx_delay_base = 0.0f; // turn off by default, was 10.0; _prefs.rx_delay_base = 0.0f; // turn off by default, was 10.0;
_prefs.tx_delay_factor = 0.5f; // was 0.25f _prefs.tx_delay_factor = 0.5f; // was 0.25f
_prefs.direct_tx_delay_factor = 0.2f; // was zero _prefs.direct_tx_delay_factor = 0.2f; // was zero
@@ -791,7 +792,7 @@ void SensorMesh::sendSelfAdvertisement(int delay_millis, bool flood) {
mesh::Packet* pkt = createSelfAdvert(); mesh::Packet* pkt = createSelfAdvert();
if (pkt) { if (pkt) {
if (flood) { if (flood) {
sendFlood(pkt, delay_millis); sendFlood(pkt, delay_millis, _prefs.path_hash_mode + 1);
} else { } else {
sendZeroHop(pkt, delay_millis); sendZeroHop(pkt, delay_millis);
} }
@@ -868,7 +869,8 @@ void SensorMesh::loop() {
if (next_flood_advert && millisHasNowPassed(next_flood_advert)) { if (next_flood_advert && millisHasNowPassed(next_flood_advert)) {
mesh::Packet* pkt = createSelfAdvert(); mesh::Packet* pkt = createSelfAdvert();
if (pkt) sendFlood(pkt); unsigned long delay_millis = 0;
if (pkt) sendFlood(pkt, delay_millis, _prefs.path_hash_mode + 1);
updateFloodAdvertTimer(); // schedule next flood advert updateFloodAdvertTimer(); // schedule next flood advert
updateAdvertTimer(); // also schedule local advert (so they don't overlap) updateAdvertTimer(); // also schedule local advert (so they don't overlap)

View File

@@ -128,7 +128,7 @@ protected:
void onControlDataRecv(mesh::Packet* packet) override; void onControlDataRecv(mesh::Packet* packet) override;
void onAckRecv(mesh::Packet* packet, uint32_t ack_crc) override; void onAckRecv(mesh::Packet* packet, uint32_t ack_crc) override;
virtual bool handleIncomingMsg(ClientInfo& from, uint32_t timestamp, uint8_t* data, uint8_t flags, size_t len); virtual bool handleIncomingMsg(ClientInfo& from, uint32_t timestamp, uint8_t* data, uint8_t flags, size_t len);
void sendAckTo(const ClientInfo& dest, uint32_t ack_hash); void sendAckTo(const ClientInfo& dest, uint32_t ack_hash, uint8_t path_hash_size=1);
private: private:
FILESYSTEM* _fs; FILESYSTEM* _fs;
unsigned long next_local_advert, next_flood_advert; unsigned long next_local_advert, next_flood_advert;

View File

@@ -24,9 +24,9 @@ lib_deps =
melopero/Melopero RV3028 @ ^1.1.0 melopero/Melopero RV3028 @ ^1.1.0
electroniccats/CayenneLPP @ 1.6.1 electroniccats/CayenneLPP @ 1.6.1
build_flags = -w -DNDEBUG -DRADIOLIB_STATIC_ONLY=1 -DRADIOLIB_GODMODE=1 build_flags = -w -DNDEBUG -DRADIOLIB_STATIC_ONLY=1 -DRADIOLIB_GODMODE=1
-D LORA_FREQ=869.525 -D LORA_FREQ=869.618
-D LORA_BW=250 -D LORA_BW=62.5
-D LORA_SF=11 -D LORA_SF=8
-D ENABLE_ADVERT_ON_BOOT=1 -D ENABLE_ADVERT_ON_BOOT=1
-D ENABLE_PRIVATE_KEY_IMPORT=1 ; NOTE: comment these out for more secure firmware -D ENABLE_PRIVATE_KEY_IMPORT=1 ; NOTE: comment these out for more secure firmware
-D ENABLE_PRIVATE_KEY_EXPORT=1 -D ENABLE_PRIVATE_KEY_EXPORT=1

View File

@@ -8,7 +8,9 @@
namespace mesh { namespace mesh {
#define MAX_RX_DELAY_MILLIS 32000 // 32 seconds #define MAX_RX_DELAY_MILLIS 32000 // 32 seconds
#define MIN_TX_BUDGET_RESERVE_MS 100 // min budget (ms) required before allowing next TX
#define MIN_TX_BUDGET_AIRTIME_DIV 2 // require at least 1/N of estimated airtime as budget before TX
#ifndef NOISE_FLOOR_CALIB_INTERVAL #ifndef NOISE_FLOOR_CALIB_INTERVAL
#define NOISE_FLOOR_CALIB_INTERVAL 2000 // 2 seconds #define NOISE_FLOOR_CALIB_INTERVAL 2000 // 2 seconds
@@ -20,12 +22,34 @@ void Dispatcher::begin() {
_err_flags = 0; _err_flags = 0;
radio_nonrx_start = _ms->getMillis(); radio_nonrx_start = _ms->getMillis();
duty_cycle_window_ms = getDutyCycleWindowMs();
float duty_cycle = 1.0f / (1.0f + getAirtimeBudgetFactor());
tx_budget_ms = (unsigned long)(duty_cycle_window_ms * duty_cycle);
last_budget_update = _ms->getMillis();
_radio->begin(); _radio->begin();
prev_isrecv_mode = _radio->isInRecvMode(); prev_isrecv_mode = _radio->isInRecvMode();
} }
float Dispatcher::getAirtimeBudgetFactor() const { float Dispatcher::getAirtimeBudgetFactor() const {
return 2.0; // default, 33.3% (1/3rd) return 1.0;
}
void Dispatcher::updateTxBudget() {
unsigned long now = _ms->getMillis();
unsigned long elapsed = now - last_budget_update;
float duty_cycle = 1.0f / (1.0f + getAirtimeBudgetFactor());
unsigned long max_budget = (unsigned long)(getDutyCycleWindowMs() * duty_cycle);
unsigned long refill = (unsigned long)(elapsed * duty_cycle);
if (refill > 0) {
tx_budget_ms += refill;
if (tx_budget_ms > max_budget) {
tx_budget_ms = max_budget;
}
last_budget_update = now;
}
} }
int Dispatcher::calcRxDelay(float score, uint32_t air_time) const { int Dispatcher::calcRxDelay(float score, uint32_t air_time) const {
@@ -61,14 +85,27 @@ void Dispatcher::loop() {
if (outbound) { // waiting for outbound send to be completed if (outbound) { // waiting for outbound send to be completed
if (_radio->isSendComplete()) { if (_radio->isSendComplete()) {
long t = _ms->getMillis() - outbound_start; long t = _ms->getMillis() - outbound_start;
total_air_time += t; // keep track of how much air time we are using total_air_time += t;
//Serial.print(" airtime="); Serial.println(t); //Serial.print(" airtime="); Serial.println(t);
// will need radio silence up to next_tx_time updateTxBudget();
next_tx_time = futureMillis(t * getAirtimeBudgetFactor());
if (t > tx_budget_ms) {
tx_budget_ms = 0;
} else {
tx_budget_ms -= t;
}
if (tx_budget_ms < MIN_TX_BUDGET_RESERVE_MS) {
float duty_cycle = 1.0f / (1.0f + getAirtimeBudgetFactor());
unsigned long needed = MIN_TX_BUDGET_RESERVE_MS - tx_budget_ms;
next_tx_time = futureMillis((unsigned long)(needed / duty_cycle));
} else {
next_tx_time = _ms->getMillis();
}
_radio->onSendFinished(); _radio->onSendFinished();
logTx(outbound, 2 + outbound->path_len + outbound->payload_len); logTx(outbound, 2 + outbound->getPathByteLen() + outbound->payload_len);
if (outbound->isRouteFlood()) { if (outbound->isRouteFlood()) {
n_sent_flood++; n_sent_flood++;
} else { } else {
@@ -80,7 +117,7 @@ void Dispatcher::loop() {
MESH_DEBUG_PRINTLN("%s Dispatcher::loop(): WARNING: outbound packed send timed out!", getLogDateTime()); MESH_DEBUG_PRINTLN("%s Dispatcher::loop(): WARNING: outbound packed send timed out!", getLogDateTime());
_radio->onSendFinished(); _radio->onSendFinished();
logTxFail(outbound, 2 + outbound->path_len + outbound->payload_len); logTxFail(outbound, 2 + outbound->getPathByteLen() + outbound->payload_len);
releasePacket(outbound); // return to pool releasePacket(outbound); // return to pool
outbound = NULL; outbound = NULL;
@@ -108,6 +145,48 @@ void Dispatcher::loop() {
checkSend(); checkSend();
} }
bool Dispatcher::tryParsePacket(Packet* pkt, const uint8_t* raw, int len) {
int i = 0;
pkt->header = raw[i++];
if (pkt->getPayloadVer() > PAYLOAD_VER_1) {
MESH_DEBUG_PRINTLN("%s Dispatcher::checkRecv(): unsupported packet version", getLogDateTime());
return false;
}
if (pkt->hasTransportCodes()) {
memcpy(&pkt->transport_codes[0], &raw[i], 2); i += 2;
memcpy(&pkt->transport_codes[1], &raw[i], 2); i += 2;
} else {
pkt->transport_codes[0] = pkt->transport_codes[1] = 0;
}
pkt->path_len = raw[i++];
uint8_t path_mode = pkt->path_len >> 6; // upper 2 bits (legacy firmware: 00)
if (path_mode == 3) { // Reserved for future
MESH_DEBUG_PRINTLN("%s Dispatcher::checkRecv(): unsupported path mode: 3", getLogDateTime());
return false;
}
uint8_t path_byte_len = (pkt->path_len & 63) * pkt->getPathHashSize();
if (path_byte_len > MAX_PATH_SIZE || i + path_byte_len > len) {
MESH_DEBUG_PRINTLN("%s Dispatcher::checkRecv(): partial or corrupt packet received, len=%d", getLogDateTime(), len);
return false;
}
memcpy(pkt->path, &raw[i], path_byte_len); i += path_byte_len;
pkt->payload_len = len - i; // payload is remainder
if (pkt->payload_len > sizeof(pkt->payload)) {
MESH_DEBUG_PRINTLN("%s Dispatcher::checkRecv(): packet payload too big, payload_len=%d", getLogDateTime(), (uint32_t)pkt->payload_len);
return false;
}
memcpy(pkt->payload, &raw[i], pkt->payload_len);
return true; // success
}
void Dispatcher::checkRecv() { void Dispatcher::checkRecv() {
Packet* pkt; Packet* pkt;
float score; float score;
@@ -122,45 +201,14 @@ void Dispatcher::checkRecv() {
if (pkt == NULL) { if (pkt == NULL) {
MESH_DEBUG_PRINTLN("%s Dispatcher::checkRecv(): WARNING: received data, no unused packets available!", getLogDateTime()); MESH_DEBUG_PRINTLN("%s Dispatcher::checkRecv(): WARNING: received data, no unused packets available!", getLogDateTime());
} else { } else {
int i = 0; if (tryParsePacket(pkt, raw, len)) {
#ifdef NODE_ID pkt->_snr = _radio->getLastSNR() * 4.0f;
uint8_t sender_id = raw[i++]; score = _radio->packetScore(_radio->getLastSNR(), len);
if (sender_id == NODE_ID - 1 || sender_id == NODE_ID + 1) { // simulate that NODE_ID can only hear NODE_ID-1 or NODE_ID+1, eg. 3 can't hear 1 air_time = _radio->getEstAirtimeFor(len);
rx_air_time += air_time;
} else { } else {
_mgr->free(pkt); // put back into pool
return;
}
#endif
pkt->header = raw[i++];
if (pkt->hasTransportCodes()) {
memcpy(&pkt->transport_codes[0], &raw[i], 2); i += 2;
memcpy(&pkt->transport_codes[1], &raw[i], 2); i += 2;
} else {
pkt->transport_codes[0] = pkt->transport_codes[1] = 0;
}
pkt->path_len = raw[i++];
if (pkt->path_len > MAX_PATH_SIZE || i + pkt->path_len > len) {
MESH_DEBUG_PRINTLN("%s Dispatcher::checkRecv(): partial or corrupt packet received, len=%d", getLogDateTime(), len);
_mgr->free(pkt); // put back into pool _mgr->free(pkt); // put back into pool
pkt = NULL; pkt = NULL;
} else {
memcpy(pkt->path, &raw[i], pkt->path_len); i += pkt->path_len;
pkt->payload_len = len - i; // payload is remainder
if (pkt->payload_len > sizeof(pkt->payload)) {
MESH_DEBUG_PRINTLN("%s Dispatcher::checkRecv(): packet payload too big, payload_len=%d", getLogDateTime(), (uint32_t)pkt->payload_len);
_mgr->free(pkt); // put back into pool
pkt = NULL;
} else {
memcpy(pkt->payload, &raw[i], pkt->payload_len);
pkt->_snr = _radio->getLastSNR() * 4.0f;
score = _radio->packetScore(_radio->getLastSNR(), len);
air_time = _radio->getEstAirtimeFor(len);
rx_air_time += air_time;
}
} }
} }
} else { } else {
@@ -224,9 +272,20 @@ void Dispatcher::processRecvPacket(Packet* pkt) {
} }
void Dispatcher::checkSend() { void Dispatcher::checkSend() {
if (_mgr->getOutboundCount(_ms->getMillis()) == 0) return; // nothing waiting to send if (_mgr->getOutboundCount(_ms->getMillis()) == 0) return;
if (!millisHasNowPassed(next_tx_time)) return; // still in 'radio silence' phase (from airtime budget setting)
if (_radio->isReceiving()) { // LBT - check if radio is currently mid-receive, or if channel activity updateTxBudget();
uint32_t est_airtime = _radio->getEstAirtimeFor(MAX_TRANS_UNIT);
if (tx_budget_ms < est_airtime / MIN_TX_BUDGET_AIRTIME_DIV) {
float duty_cycle = 1.0f / (1.0f + getAirtimeBudgetFactor());
unsigned long needed = est_airtime / MIN_TX_BUDGET_AIRTIME_DIV - tx_budget_ms;
next_tx_time = futureMillis((unsigned long)(needed / duty_cycle));
return;
}
if (!millisHasNowPassed(next_tx_time)) return;
if (_radio->isReceiving()) {
if (cad_busy_start == 0) { if (cad_busy_start == 0) {
cad_busy_start = _ms->getMillis(); // record when CAD busy state started cad_busy_start = _ms->getMillis(); // record when CAD busy state started
} }
@@ -249,16 +308,13 @@ void Dispatcher::checkSend() {
int len = 0; int len = 0;
uint8_t raw[MAX_TRANS_UNIT]; uint8_t raw[MAX_TRANS_UNIT];
#ifdef NODE_ID
raw[len++] = NODE_ID;
#endif
raw[len++] = outbound->header; raw[len++] = outbound->header;
if (outbound->hasTransportCodes()) { if (outbound->hasTransportCodes()) {
memcpy(&raw[len], &outbound->transport_codes[0], 2); len += 2; memcpy(&raw[len], &outbound->transport_codes[0], 2); len += 2;
memcpy(&raw[len], &outbound->transport_codes[1], 2); len += 2; memcpy(&raw[len], &outbound->transport_codes[1], 2); len += 2;
} }
raw[len++] = outbound->path_len; raw[len++] = outbound->path_len;
memcpy(&raw[len], outbound->path, outbound->path_len); len += outbound->path_len; len += Packet::writePath(&raw[len], outbound->path, outbound->path_len);
if (len + outbound->payload_len > MAX_TRANS_UNIT) { if (len + outbound->payload_len > MAX_TRANS_UNIT) {
MESH_DEBUG_PRINTLN("%s Dispatcher::checkSend(): FATAL: Invalid packet queued... too long, len=%d", getLogDateTime(), len + outbound->payload_len); MESH_DEBUG_PRINTLN("%s Dispatcher::checkSend(): FATAL: Invalid packet queued... too long, len=%d", getLogDateTime(), len + outbound->payload_len);
@@ -312,7 +368,7 @@ void Dispatcher::releasePacket(Packet* packet) {
} }
void Dispatcher::sendPacket(Packet* packet, uint8_t priority, uint32_t delay_millis) { void Dispatcher::sendPacket(Packet* packet, uint8_t priority, uint32_t delay_millis) {
if (packet->path_len > MAX_PATH_SIZE || packet->payload_len > MAX_PACKET_PAYLOAD) { if (!Packet::isValidPathLen(packet->path_len) || packet->payload_len > MAX_PACKET_PAYLOAD) {
MESH_DEBUG_PRINTLN("%s Dispatcher::sendPacket(): ERROR: invalid packet... path_len=%d, payload_len=%d", getLogDateTime(), (uint32_t) packet->path_len, (uint32_t) packet->payload_len); MESH_DEBUG_PRINTLN("%s Dispatcher::sendPacket(): ERROR: invalid packet... path_len=%d, payload_len=%d", getLogDateTime(), (uint32_t) packet->path_len, (uint32_t) packet->payload_len);
_mgr->free(packet); _mgr->free(packet);
} else { } else {

View File

@@ -122,8 +122,12 @@ class Dispatcher {
bool prev_isrecv_mode; bool prev_isrecv_mode;
uint32_t n_sent_flood, n_sent_direct; uint32_t n_sent_flood, n_sent_direct;
uint32_t n_recv_flood, n_recv_direct; uint32_t n_recv_flood, n_recv_direct;
unsigned long tx_budget_ms;
unsigned long last_budget_update;
unsigned long duty_cycle_window_ms;
void processRecvPacket(Packet* pkt); void processRecvPacket(Packet* pkt);
void updateTxBudget();
protected: protected:
PacketManager* _mgr; PacketManager* _mgr;
@@ -142,6 +146,9 @@ protected:
_err_flags = 0; _err_flags = 0;
radio_nonrx_start = 0; radio_nonrx_start = 0;
prev_isrecv_mode = true; prev_isrecv_mode = true;
tx_budget_ms = 0;
last_budget_update = 0;
duty_cycle_window_ms = 3600000;
} }
virtual DispatcherAction onRecvPacket(Packet* pkt) = 0; virtual DispatcherAction onRecvPacket(Packet* pkt) = 0;
@@ -159,6 +166,7 @@ protected:
virtual uint32_t getCADFailMaxDuration() const; virtual uint32_t getCADFailMaxDuration() const;
virtual int getInterferenceThreshold() const { return 0; } // disabled by default virtual int getInterferenceThreshold() const { return 0; } // disabled by default
virtual int getAGCResetInterval() const { return 0; } // disabled by default virtual int getAGCResetInterval() const { return 0; } // disabled by default
virtual unsigned long getDutyCycleWindowMs() const { return 3600000; }
public: public:
void begin(); void begin();
@@ -168,8 +176,9 @@ public:
void releasePacket(Packet* packet); void releasePacket(Packet* packet);
void sendPacket(Packet* packet, uint8_t priority, uint32_t delay_millis=0); void sendPacket(Packet* packet, uint8_t priority, uint32_t delay_millis=0);
unsigned long getTotalAirTime() const { return total_air_time; } // in milliseconds unsigned long getTotalAirTime() const { return total_air_time; }
unsigned long getReceiveAirTime() const {return rx_air_time; } unsigned long getReceiveAirTime() const {return rx_air_time; }
unsigned long getRemainingTxBudget() const { return tx_budget_ms; }
uint32_t getNumSentFlood() const { return n_sent_flood; } uint32_t getNumSentFlood() const { return n_sent_flood; }
uint32_t getNumSentDirect() const { return n_sent_direct; } uint32_t getNumSentDirect() const { return n_sent_direct; }
uint32_t getNumRecvFlood() const { return n_recv_flood; } uint32_t getNumRecvFlood() const { return n_recv_flood; }
@@ -184,6 +193,7 @@ public:
unsigned long futureMillis(int millis_from_now) const; unsigned long futureMillis(int millis_from_now) const;
private: private:
bool tryParsePacket(Packet* pkt, const uint8_t* raw, int len);
void checkRecv(); void checkRecv();
void checkSend(); void checkSend();
}; };

View File

@@ -20,6 +20,10 @@ public:
memcpy(dest, pub_key, PATH_HASH_SIZE); // hash is just prefix of pub_key memcpy(dest, pub_key, PATH_HASH_SIZE); // hash is just prefix of pub_key
return PATH_HASH_SIZE; return PATH_HASH_SIZE;
} }
int copyHashTo(uint8_t* dest, uint8_t len) const {
memcpy(dest, pub_key, len); // hash is just prefix of pub_key
return len;
}
bool isHashMatch(const uint8_t* hash) const { bool isHashMatch(const uint8_t* hash) const {
return memcmp(hash, pub_key, PATH_HASH_SIZE) == 0; return memcmp(hash, pub_key, PATH_HASH_SIZE) == 0;
} }

View File

@@ -39,11 +39,6 @@ int Mesh::searchChannelsByHash(const uint8_t* hash, GroupChannel channels[], int
} }
DispatcherAction Mesh::onRecvPacket(Packet* pkt) { DispatcherAction Mesh::onRecvPacket(Packet* pkt) {
if (pkt->getPayloadVer() > PAYLOAD_VER_1) { // not supported in this firmware version
MESH_DEBUG_PRINTLN("%s Mesh::onRecvPacket(): unsupported packet version", getLogDateTime());
return ACTION_RELEASE;
}
if (pkt->isRouteDirect() && pkt->getPayloadType() == PAYLOAD_TYPE_TRACE) { if (pkt->isRouteDirect() && pkt->getPayloadType() == PAYLOAD_TYPE_TRACE) {
if (pkt->path_len < MAX_PATH_SIZE) { if (pkt->path_len < MAX_PATH_SIZE) {
uint8_t i = 0; uint8_t i = 0;
@@ -70,14 +65,14 @@ DispatcherAction Mesh::onRecvPacket(Packet* pkt) {
} }
if (pkt->isRouteDirect() && pkt->getPayloadType() == PAYLOAD_TYPE_CONTROL && (pkt->payload[0] & 0x80) != 0) { if (pkt->isRouteDirect() && pkt->getPayloadType() == PAYLOAD_TYPE_CONTROL && (pkt->payload[0] & 0x80) != 0) {
if (pkt->path_len == 0) { if (pkt->getPathHashCount() == 0) {
onControlDataRecv(pkt); onControlDataRecv(pkt);
} }
// just zero-hop control packets allowed (for this subset of payloads) // just zero-hop control packets allowed (for this subset of payloads)
return ACTION_RELEASE; return ACTION_RELEASE;
} }
if (pkt->isRouteDirect() && pkt->path_len >= PATH_HASH_SIZE) { if (pkt->isRouteDirect() && pkt->getPathHashCount() > 0) {
// check for 'early received' ACK // check for 'early received' ACK
if (pkt->getPayloadType() == PAYLOAD_TYPE_ACK) { if (pkt->getPayloadType() == PAYLOAD_TYPE_ACK) {
int i = 0; int i = 0;
@@ -88,7 +83,7 @@ DispatcherAction Mesh::onRecvPacket(Packet* pkt) {
} }
} }
if (self_id.isHashMatch(pkt->path) && allowPacketForward(pkt)) { if (self_id.isHashMatch(pkt->path, pkt->getPathHashSize()) && allowPacketForward(pkt)) {
if (pkt->getPayloadType() == PAYLOAD_TYPE_MULTIPART) { if (pkt->getPayloadType() == PAYLOAD_TYPE_MULTIPART) {
return forwardMultipartDirect(pkt); return forwardMultipartDirect(pkt);
} else if (pkt->getPayloadType() == PAYLOAD_TYPE_ACK) { } else if (pkt->getPayloadType() == PAYLOAD_TYPE_ACK) {
@@ -158,7 +153,9 @@ DispatcherAction Mesh::onRecvPacket(Packet* pkt) {
if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH) { if (pkt->getPayloadType() == PAYLOAD_TYPE_PATH) {
int k = 0; int k = 0;
uint8_t path_len = data[k++]; uint8_t path_len = data[k++];
uint8_t* path = &data[k]; k += path_len; uint8_t hash_size = (path_len >> 6) + 1;
uint8_t hash_count = path_len & 63;
uint8_t* path = &data[k]; k += hash_size*hash_count;
uint8_t extra_type = data[k++] & 0x0F; // upper 4 bits reserved for future use uint8_t extra_type = data[k++] & 0x0F; // upper 4 bits reserved for future use
uint8_t* extra = &data[k]; uint8_t* extra = &data[k];
uint8_t extra_len = len - k; // remainder of packet (may be padded with zeroes!) uint8_t extra_len = len - k; // remainder of packet (may be padded with zeroes!)
@@ -293,8 +290,7 @@ DispatcherAction Mesh::onRecvPacket(Packet* pkt) {
if (type == PAYLOAD_TYPE_ACK && pkt->payload_len >= 5) { // a multipart ACK if (type == PAYLOAD_TYPE_ACK && pkt->payload_len >= 5) { // a multipart ACK
Packet tmp; Packet tmp;
tmp.header = pkt->header; tmp.header = pkt->header;
tmp.path_len = pkt->path_len; tmp.path_len = Packet::copyPath(tmp.path, pkt->path, pkt->path_len);
memcpy(tmp.path, pkt->path, pkt->path_len);
tmp.payload_len = pkt->payload_len - 1; tmp.payload_len = pkt->payload_len - 1;
memcpy(tmp.payload, &pkt->payload[1], tmp.payload_len); memcpy(tmp.payload, &pkt->payload[1], tmp.payload_len);
@@ -321,27 +317,25 @@ DispatcherAction Mesh::onRecvPacket(Packet* pkt) {
void Mesh::removeSelfFromPath(Packet* pkt) { void Mesh::removeSelfFromPath(Packet* pkt) {
// remove our hash from 'path' // remove our hash from 'path'
pkt->path_len -= PATH_HASH_SIZE; pkt->setPathHashCount(pkt->getPathHashCount() - 1); // decrement the count
#if 0
memcpy(pkt->path, &pkt->path[PATH_HASH_SIZE], pkt->path_len); uint8_t sz = pkt->getPathHashSize();
#elif PATH_HASH_SIZE == 1 for (int k = 0; k < pkt->getPathHashCount()*sz; k += sz) { // shuffle path by 1 'entry'
for (int k = 0; k < pkt->path_len; k++) { // shuffle bytes by 1 memcpy(&pkt->path[k], &pkt->path[k + sz], sz);
pkt->path[k] = pkt->path[k + 1];
} }
#else
#error "need path remove impl"
#endif
} }
DispatcherAction Mesh::routeRecvPacket(Packet* packet) { DispatcherAction Mesh::routeRecvPacket(Packet* packet) {
uint8_t n = packet->getPathHashCount();
if (packet->isRouteFlood() && !packet->isMarkedDoNotRetransmit() if (packet->isRouteFlood() && !packet->isMarkedDoNotRetransmit()
&& packet->path_len + PATH_HASH_SIZE <= MAX_PATH_SIZE && allowPacketForward(packet)) { && (n + 1)*packet->getPathHashSize() <= MAX_PATH_SIZE && allowPacketForward(packet)) {
// append this node's hash to 'path' // append this node's hash to 'path'
packet->path_len += self_id.copyHashTo(&packet->path[packet->path_len]); self_id.copyHashTo(&packet->path[n * packet->getPathHashSize()], packet->getPathHashSize());
packet->setPathHashCount(n + 1);
uint32_t d = getRetransmitDelay(packet); uint32_t d = getRetransmitDelay(packet);
// as this propagates outwards, give it lower and lower priority // as this propagates outwards, give it lower and lower priority
return ACTION_RETRANSMIT_DELAYED(packet->path_len, d); // give priority to closer sources, than ones further away return ACTION_RETRANSMIT_DELAYED(packet->getPathHashCount(), d); // give priority to closer sources, than ones further away
} }
return ACTION_RELEASE; return ACTION_RELEASE;
} }
@@ -353,8 +347,7 @@ DispatcherAction Mesh::forwardMultipartDirect(Packet* pkt) {
if (type == PAYLOAD_TYPE_ACK && pkt->payload_len >= 5) { // a multipart ACK if (type == PAYLOAD_TYPE_ACK && pkt->payload_len >= 5) { // a multipart ACK
Packet tmp; Packet tmp;
tmp.header = pkt->header; tmp.header = pkt->header;
tmp.path_len = pkt->path_len; tmp.path_len = Packet::copyPath(tmp.path, pkt->path, pkt->path_len);
memcpy(tmp.path, pkt->path, pkt->path_len);
tmp.payload_len = pkt->payload_len - 1; tmp.payload_len = pkt->payload_len - 1;
memcpy(tmp.payload, &pkt->payload[1], tmp.payload_len); memcpy(tmp.payload, &pkt->payload[1], tmp.payload_len);
@@ -376,7 +369,7 @@ void Mesh::routeDirectRecvAcks(Packet* packet, uint32_t delay_millis) {
delay_millis += getDirectRetransmitDelay(packet) + 300; delay_millis += getDirectRetransmitDelay(packet) + 300;
auto a1 = createMultiAck(crc, extra); auto a1 = createMultiAck(crc, extra);
if (a1) { if (a1) {
memcpy(a1->path, packet->path, a1->path_len = packet->path_len); a1->path_len = Packet::copyPath(a1->path, packet->path, packet->path_len);
a1->header &= ~PH_ROUTE_MASK; a1->header &= ~PH_ROUTE_MASK;
a1->header |= ROUTE_TYPE_DIRECT; a1->header |= ROUTE_TYPE_DIRECT;
sendPacket(a1, 0, delay_millis); sendPacket(a1, 0, delay_millis);
@@ -386,7 +379,7 @@ void Mesh::routeDirectRecvAcks(Packet* packet, uint32_t delay_millis) {
auto a2 = createAck(crc); auto a2 = createAck(crc);
if (a2) { if (a2) {
memcpy(a2->path, packet->path, a2->path_len = packet->path_len); a2->path_len = Packet::copyPath(a2->path, packet->path, packet->path_len);
a2->header &= ~PH_ROUTE_MASK; a2->header &= ~PH_ROUTE_MASK;
a2->header |= ROUTE_TYPE_DIRECT; a2->header |= ROUTE_TYPE_DIRECT;
sendPacket(a2, 0, delay_millis); sendPacket(a2, 0, delay_millis);
@@ -439,7 +432,10 @@ Packet* Mesh::createPathReturn(const Identity& dest, const uint8_t* secret, cons
} }
Packet* Mesh::createPathReturn(const uint8_t* dest_hash, const uint8_t* secret, const uint8_t* path, uint8_t path_len, uint8_t extra_type, const uint8_t*extra, size_t extra_len) { Packet* Mesh::createPathReturn(const uint8_t* dest_hash, const uint8_t* secret, const uint8_t* path, uint8_t path_len, uint8_t extra_type, const uint8_t*extra, size_t extra_len) {
if (path_len + extra_len + 5 > MAX_COMBINED_PATH) return NULL; // too long!! uint8_t path_hash_size = (path_len >> 6) + 1;
uint8_t path_hash_count = path_len & 63;
if (path_hash_count*path_hash_size + extra_len + 5 > MAX_COMBINED_PATH) return NULL; // too long!!
Packet* packet = obtainNewPacket(); Packet* packet = obtainNewPacket();
if (packet == NULL) { if (packet == NULL) {
@@ -457,7 +453,7 @@ Packet* Mesh::createPathReturn(const uint8_t* dest_hash, const uint8_t* secret,
uint8_t data[MAX_PACKET_PAYLOAD]; uint8_t data[MAX_PACKET_PAYLOAD];
data[data_len++] = path_len; data[data_len++] = path_len;
memcpy(&data[data_len], path, path_len); data_len += path_len; memcpy(&data[data_len], path, path_hash_count*path_hash_size); data_len += path_hash_count*path_hash_size;
if (extra_len > 0) { if (extra_len > 0) {
data[data_len++] = extra_type; data[data_len++] = extra_type;
memcpy(&data[data_len], extra, extra_len); data_len += extra_len; memcpy(&data[data_len], extra, extra_len); data_len += extra_len;
@@ -624,15 +620,19 @@ Packet* Mesh::createControlData(const uint8_t* data, size_t len) {
return packet; return packet;
} }
void Mesh::sendFlood(Packet* packet, uint32_t delay_millis) { void Mesh::sendFlood(Packet* packet, uint32_t delay_millis, uint8_t path_hash_size) {
if (packet->getPayloadType() == PAYLOAD_TYPE_TRACE) { if (packet->getPayloadType() == PAYLOAD_TYPE_TRACE) {
MESH_DEBUG_PRINTLN("%s Mesh::sendFlood(): TRACE type not suspported", getLogDateTime()); MESH_DEBUG_PRINTLN("%s Mesh::sendFlood(): TRACE type not suspported", getLogDateTime());
return; return;
} }
if (path_hash_size == 0 || path_hash_size > 3) {
MESH_DEBUG_PRINTLN("%s Mesh::sendFlood(): invalid path_hash_size", getLogDateTime());
return;
}
packet->header &= ~PH_ROUTE_MASK; packet->header &= ~PH_ROUTE_MASK;
packet->header |= ROUTE_TYPE_FLOOD; packet->header |= ROUTE_TYPE_FLOOD;
packet->path_len = 0; packet->setPathHashSizeAndCount(path_hash_size, 0);
_tables->hasSeen(packet); // mark this packet as already sent in case it is rebroadcast back to us _tables->hasSeen(packet); // mark this packet as already sent in case it is rebroadcast back to us
@@ -647,17 +647,21 @@ void Mesh::sendFlood(Packet* packet, uint32_t delay_millis) {
sendPacket(packet, pri, delay_millis); sendPacket(packet, pri, delay_millis);
} }
void Mesh::sendFlood(Packet* packet, uint16_t* transport_codes, uint32_t delay_millis) { void Mesh::sendFlood(Packet* packet, uint16_t* transport_codes, uint32_t delay_millis, uint8_t path_hash_size) {
if (packet->getPayloadType() == PAYLOAD_TYPE_TRACE) { if (packet->getPayloadType() == PAYLOAD_TYPE_TRACE) {
MESH_DEBUG_PRINTLN("%s Mesh::sendFlood(): TRACE type not suspported", getLogDateTime()); MESH_DEBUG_PRINTLN("%s Mesh::sendFlood(): TRACE type not suspported", getLogDateTime());
return; return;
} }
if (path_hash_size == 0 || path_hash_size > 3) {
MESH_DEBUG_PRINTLN("%s Mesh::sendFlood(): invalid path_hash_size", getLogDateTime());
return;
}
packet->header &= ~PH_ROUTE_MASK; packet->header &= ~PH_ROUTE_MASK;
packet->header |= ROUTE_TYPE_TRANSPORT_FLOOD; packet->header |= ROUTE_TYPE_TRANSPORT_FLOOD;
packet->transport_codes[0] = transport_codes[0]; packet->transport_codes[0] = transport_codes[0];
packet->transport_codes[1] = transport_codes[1]; packet->transport_codes[1] = transport_codes[1];
packet->path_len = 0; packet->setPathHashSizeAndCount(path_hash_size, 0);
_tables->hasSeen(packet); // mark this packet as already sent in case it is rebroadcast back to us _tables->hasSeen(packet); // mark this packet as already sent in case it is rebroadcast back to us
@@ -679,13 +683,13 @@ void Mesh::sendDirect(Packet* packet, const uint8_t* path, uint8_t path_len, uin
uint8_t pri; uint8_t pri;
if (packet->getPayloadType() == PAYLOAD_TYPE_TRACE) { // TRACE packets are different if (packet->getPayloadType() == PAYLOAD_TYPE_TRACE) { // TRACE packets are different
// for TRACE packets, path is appended to end of PAYLOAD. (path is used for SNR's) // for TRACE packets, path is appended to end of PAYLOAD. (path is used for SNR's)
memcpy(&packet->payload[packet->payload_len], path, path_len); memcpy(&packet->payload[packet->payload_len], path, path_len); // NOTE: path_len here can be > 64, and NOT in the new scheme
packet->payload_len += path_len; packet->payload_len += path_len;
packet->path_len = 0; packet->path_len = 0;
pri = 5; // maybe make this configurable pri = 5; // maybe make this configurable
} else { } else {
memcpy(packet->path, path, packet->path_len = path_len); packet->path_len = Packet::copyPath(packet->path, path, path_len);
if (packet->getPayloadType() == PAYLOAD_TYPE_PATH) { if (packet->getPayloadType() == PAYLOAD_TYPE_PATH) {
pri = 1; // slightly less priority pri = 1; // slightly less priority
} else { } else {

View File

@@ -196,13 +196,13 @@ public:
/** /**
* \brief send a locally-generated Packet with flood routing * \brief send a locally-generated Packet with flood routing
*/ */
void sendFlood(Packet* packet, uint32_t delay_millis=0); void sendFlood(Packet* packet, uint32_t delay_millis=0, uint8_t path_hash_size=1);
/** /**
* \brief send a locally-generated Packet with flood routing * \brief send a locally-generated Packet with flood routing
* \param transport_codes array of 2 codes to attach to packet * \param transport_codes array of 2 codes to attach to packet
*/ */
void sendFlood(Packet* packet, uint16_t* transport_codes, uint32_t delay_millis=0); void sendFlood(Packet* packet, uint16_t* transport_codes, uint32_t delay_millis=0, uint8_t path_hash_size=1);
/** /**
* \brief send a locally-generated Packet with Direct routing * \brief send a locally-generated Packet with Direct routing

View File

@@ -55,6 +55,7 @@ public:
virtual uint32_t getGpio() { return 0; } virtual uint32_t getGpio() { return 0; }
virtual void setGpio(uint32_t values) {} virtual void setGpio(uint32_t values) {}
virtual uint8_t getStartupReason() const = 0; virtual uint8_t getStartupReason() const = 0;
virtual bool getBootloaderVersion(char* version, size_t max_len) { return false; }
virtual bool startOTAUpdate(const char* id, char reply[]) { return false; } // not supported virtual bool startOTAUpdate(const char* id, char reply[]) { return false; } // not supported
// Power management interface (boards with power management override these) // Power management interface (boards with power management override these)

View File

@@ -10,8 +10,32 @@ Packet::Packet() {
payload_len = 0; payload_len = 0;
} }
bool Packet::isValidPathLen(uint8_t path_len) {
uint8_t hash_count = path_len & 63;
uint8_t hash_size = (path_len >> 6) + 1;
if (hash_size == 4) return false; // Reserved for future
return hash_count*hash_size <= MAX_PATH_SIZE;
}
size_t Packet::writePath(uint8_t* dest, const uint8_t* src, uint8_t path_len) {
uint8_t hash_count = path_len & 63;
uint8_t hash_size = (path_len >> 6) + 1;
size_t len = hash_count*hash_size;
if (len > MAX_PATH_SIZE) {
MESH_DEBUG_PRINTLN("Packet::copyPath, invalid path_len=%d", (uint32_t)path_len);
return 0; // Error
}
memcpy(dest, src, len);
return len;
}
uint8_t Packet::copyPath(uint8_t* dest, const uint8_t* src, uint8_t path_len) {
writePath(dest, src, path_len);
return path_len;
}
int Packet::getRawLength() const { int Packet::getRawLength() const {
return 2 + path_len + payload_len + (hasTransportCodes() ? 4 : 0); return 2 + getPathByteLen() + payload_len + (hasTransportCodes() ? 4 : 0);
} }
void Packet::calculatePacketHash(uint8_t* hash) const { void Packet::calculatePacketHash(uint8_t* hash) const {
@@ -33,7 +57,7 @@ uint8_t Packet::writeTo(uint8_t dest[]) const {
memcpy(&dest[i], &transport_codes[1], 2); i += 2; memcpy(&dest[i], &transport_codes[1], 2); i += 2;
} }
dest[i++] = path_len; dest[i++] = path_len;
memcpy(&dest[i], path, path_len); i += path_len; i += writePath(&dest[i], path, path_len);
memcpy(&dest[i], payload, payload_len); i += payload_len; memcpy(&dest[i], payload, payload_len); i += payload_len;
return i; return i;
} }
@@ -48,8 +72,11 @@ bool Packet::readFrom(const uint8_t src[], uint8_t len) {
transport_codes[0] = transport_codes[1] = 0; transport_codes[0] = transport_codes[1] = 0;
} }
path_len = src[i++]; path_len = src[i++];
if (path_len > sizeof(path)) return false; // bad encoding if (!isValidPathLen(path_len)) return false; // bad encoding
memcpy(path, &src[i], path_len); i += path_len;
uint8_t bl = getPathByteLen();
memcpy(path, &src[i], bl); i += bl;
if (i >= len) return false; // bad encoding if (i >= len) return false; // bad encoding
payload_len = len - i; payload_len = len - i;
if (payload_len > sizeof(payload)) return false; // bad encoding if (payload_len > sizeof(payload)) return false; // bad encoding

View File

@@ -76,6 +76,16 @@ public:
*/ */
uint8_t getPayloadVer() const { return (header >> PH_VER_SHIFT) & PH_VER_MASK; } uint8_t getPayloadVer() const { return (header >> PH_VER_SHIFT) & PH_VER_MASK; }
uint8_t getPathHashSize() const { return (path_len >> 6) + 1; }
uint8_t getPathHashCount() const { return path_len & 63; }
uint8_t getPathByteLen() const { return getPathHashCount() * getPathHashSize(); }
void setPathHashCount(uint8_t n) { path_len &= ~63; path_len |= n; }
void setPathHashSizeAndCount(uint8_t sz, uint8_t n) { path_len = ((sz - 1) << 6) | (n & 63); }
static uint8_t copyPath(uint8_t* dest, const uint8_t* src, uint8_t path_len); // returns path_len
static size_t writePath(uint8_t* dest, const uint8_t* src, uint8_t path_len); // returns byte length written
static bool isValidPathLen(uint8_t path_len);
void markDoNotRetransmit() { header = 0xFF; } void markDoNotRetransmit() { header = 0xFF; }
bool isMarkedDoNotRetransmit() const { return header == 0xFF; } bool isMarkedDoNotRetransmit() const { return header == 0xFF; }

View File

@@ -39,7 +39,7 @@ mesh::Packet* BaseChatMesh::createSelfAdvert(const char* name, double lat, doubl
} }
void BaseChatMesh::sendAckTo(const ContactInfo& dest, uint32_t ack_hash) { void BaseChatMesh::sendAckTo(const ContactInfo& dest, uint32_t ack_hash) {
if (dest.out_path_len < 0) { if (dest.out_path_len == OUT_PATH_UNKNOWN) {
mesh::Packet* ack = createAck(ack_hash); mesh::Packet* ack = createAck(ack_hash);
if (ack) sendFloodScoped(dest, ack, TXT_ACK_DELAY); if (ack) sendFloodScoped(dest, ack, TXT_ACK_DELAY);
} else { } else {
@@ -92,7 +92,7 @@ ContactInfo* BaseChatMesh::allocateContactSlot() {
void BaseChatMesh::populateContactFromAdvert(ContactInfo& ci, const mesh::Identity& id, const AdvertDataParser& parser, uint32_t timestamp) { void BaseChatMesh::populateContactFromAdvert(ContactInfo& ci, const mesh::Identity& id, const AdvertDataParser& parser, uint32_t timestamp) {
memset(&ci, 0, sizeof(ci)); memset(&ci, 0, sizeof(ci));
ci.id = id; ci.id = id;
ci.out_path_len = -1; // initially out_path is unknown ci.out_path_len = OUT_PATH_UNKNOWN;
StrHelper::strncpy(ci.name, parser.getName(), sizeof(ci.name)); StrHelper::strncpy(ci.name, parser.getName(), sizeof(ci.name));
ci.type = parser.getType(); ci.type = parser.getType();
if (parser.hasLatLon()) { if (parser.hasLatLon()) {
@@ -141,6 +141,15 @@ void BaseChatMesh::onAdvertRecv(mesh::Packet* packet, const mesh::Identity& id,
return; return;
} }
// check hop limit for new contacts (0 = no limit, 1 = direct (0 hops), N = up to N-1 hops)
uint8_t max_hops = getAutoAddMaxHops();
if (max_hops > 0 && packet->getPathHashCount() >= max_hops) {
ContactInfo ci;
populateContactFromAdvert(ci, id, parser, timestamp);
onDiscoveredContact(ci, true, packet->path_len, packet->path); // let UI know
return;
}
from = allocateContactSlot(); from = allocateContactSlot();
if (from == NULL) { if (from == NULL) {
ContactInfo ci; ContactInfo ci;
@@ -263,7 +272,7 @@ void BaseChatMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender
} else { } else {
mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, from.id, secret, temp_buf, reply_len); mesh::Packet* reply = createDatagram(PAYLOAD_TYPE_RESPONSE, from.id, secret, temp_buf, reply_len);
if (reply) { if (reply) {
if (from.out_path_len >= 0) { // we have an out_path, so send DIRECT if (from.out_path_len != OUT_PATH_UNKNOWN) { // we have an out_path, so send DIRECT
sendDirect(reply, from.out_path, from.out_path_len, SERVER_RESPONSE_DELAY); sendDirect(reply, from.out_path, from.out_path_len, SERVER_RESPONSE_DELAY);
} else { } else {
sendFloodScoped(from, reply, SERVER_RESPONSE_DELAY); sendFloodScoped(from, reply, SERVER_RESPONSE_DELAY);
@@ -273,7 +282,7 @@ void BaseChatMesh::onPeerDataRecv(mesh::Packet* packet, uint8_t type, int sender
} }
} else if (type == PAYLOAD_TYPE_RESPONSE && len > 0) { } else if (type == PAYLOAD_TYPE_RESPONSE && len > 0) {
onContactResponse(from, data, len); onContactResponse(from, data, len);
if (packet->isRouteFlood() && from.out_path_len >= 0) { if (packet->isRouteFlood() && from.out_path_len != OUT_PATH_UNKNOWN) {
// we have direct path, but other node is still sending flood response, so maybe they didn't receive reciprocal path properly(?) // we have direct path, but other node is still sending flood response, so maybe they didn't receive reciprocal path properly(?)
handleReturnPathRetry(from, packet->path, packet->path_len); handleReturnPathRetry(from, packet->path, packet->path_len);
} }
@@ -295,7 +304,7 @@ bool BaseChatMesh::onPeerPathRecv(mesh::Packet* packet, int sender_idx, const ui
bool BaseChatMesh::onContactPathRecv(ContactInfo& from, uint8_t* in_path, uint8_t in_path_len, uint8_t* out_path, uint8_t out_path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) { bool BaseChatMesh::onContactPathRecv(ContactInfo& from, uint8_t* in_path, uint8_t in_path_len, uint8_t* out_path, uint8_t out_path_len, uint8_t extra_type, uint8_t* extra, uint8_t extra_len) {
// NOTE: default impl, we just replace the current 'out_path' regardless, whenever sender sends us a new out_path. // NOTE: default 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'(?) // FUTURE: could store multiple out_paths per contact, and try to find which is the 'best'(?)
memcpy(from.out_path, out_path, from.out_path_len = out_path_len); // store a copy of path, for sendDirect() from.out_path_len = mesh::Packet::copyPath(from.out_path, out_path, out_path_len); // store a copy of path, for sendDirect()
from.lastmod = getRTCClock()->getCurrentTime(); from.lastmod = getRTCClock()->getCurrentTime();
onContactPathUpdated(from); onContactPathUpdated(from);
@@ -317,7 +326,7 @@ void BaseChatMesh::onAckRecv(mesh::Packet* packet, uint32_t ack_crc) {
txt_send_timeout = 0; // matched one we're waiting for, cancel timeout timer txt_send_timeout = 0; // matched one we're waiting for, cancel timeout timer
packet->markDoNotRetransmit(); // ACK was for this node, so don't retransmit packet->markDoNotRetransmit(); // ACK was for this node, so don't retransmit
if (packet->isRouteFlood() && from->out_path_len >= 0) { if (packet->isRouteFlood() && from->out_path_len != OUT_PATH_UNKNOWN) {
// we have direct path, but other node is still sending flood, so maybe they didn't receive reciprocal path properly(?) // we have direct path, but other node is still sending flood, so maybe they didn't receive reciprocal path properly(?)
handleReturnPathRetry(*from, packet->path, packet->path_len); handleReturnPathRetry(*from, packet->path, packet->path_len);
} }
@@ -386,7 +395,7 @@ int BaseChatMesh::sendMessage(const ContactInfo& recipient, uint32_t timestamp,
uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength()); uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength());
int rc; int rc;
if (recipient.out_path_len < 0) { if (recipient.out_path_len == OUT_PATH_UNKNOWN) {
sendFloodScoped(recipient, pkt); sendFloodScoped(recipient, pkt);
txt_send_timeout = futureMillis(est_timeout = calcFloodTimeoutMillisFor(t)); txt_send_timeout = futureMillis(est_timeout = calcFloodTimeoutMillisFor(t));
rc = MSG_SEND_SENT_FLOOD; rc = MSG_SEND_SENT_FLOOD;
@@ -412,7 +421,7 @@ int BaseChatMesh::sendCommandData(const ContactInfo& recipient, uint32_t timest
uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength()); uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength());
int rc; int rc;
if (recipient.out_path_len < 0) { if (recipient.out_path_len == OUT_PATH_UNKNOWN) {
sendFloodScoped(recipient, pkt); sendFloodScoped(recipient, pkt);
txt_send_timeout = futureMillis(est_timeout = calcFloodTimeoutMillisFor(t)); txt_send_timeout = futureMillis(est_timeout = calcFloodTimeoutMillisFor(t));
rc = MSG_SEND_SENT_FLOOD; rc = MSG_SEND_SENT_FLOOD;
@@ -500,7 +509,7 @@ int BaseChatMesh::sendLogin(const ContactInfo& recipient, const char* password,
} }
if (pkt) { if (pkt) {
uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength()); uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength());
if (recipient.out_path_len < 0) { if (recipient.out_path_len == OUT_PATH_UNKNOWN) {
sendFloodScoped(recipient, pkt); sendFloodScoped(recipient, pkt);
est_timeout = calcFloodTimeoutMillisFor(t); est_timeout = calcFloodTimeoutMillisFor(t);
return MSG_SEND_SENT_FLOOD; return MSG_SEND_SENT_FLOOD;
@@ -525,7 +534,7 @@ int BaseChatMesh::sendAnonReq(const ContactInfo& recipient, const uint8_t* data,
} }
if (pkt) { if (pkt) {
uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength()); uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength());
if (recipient.out_path_len < 0) { if (recipient.out_path_len == OUT_PATH_UNKNOWN) {
sendFloodScoped(recipient, pkt); sendFloodScoped(recipient, pkt);
est_timeout = calcFloodTimeoutMillisFor(t); est_timeout = calcFloodTimeoutMillisFor(t);
return MSG_SEND_SENT_FLOOD; return MSG_SEND_SENT_FLOOD;
@@ -552,7 +561,7 @@ int BaseChatMesh::sendRequest(const ContactInfo& recipient, const uint8_t* req_
} }
if (pkt) { if (pkt) {
uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength()); uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength());
if (recipient.out_path_len < 0) { if (recipient.out_path_len == OUT_PATH_UNKNOWN) {
sendFloodScoped(recipient, pkt); sendFloodScoped(recipient, pkt);
est_timeout = calcFloodTimeoutMillisFor(t); est_timeout = calcFloodTimeoutMillisFor(t);
return MSG_SEND_SENT_FLOOD; return MSG_SEND_SENT_FLOOD;
@@ -579,7 +588,7 @@ int BaseChatMesh::sendRequest(const ContactInfo& recipient, uint8_t req_type, u
} }
if (pkt) { if (pkt) {
uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength()); uint32_t t = _radio->getEstAirtimeFor(pkt->getRawLength());
if (recipient.out_path_len < 0) { if (recipient.out_path_len == OUT_PATH_UNKNOWN) {
sendFloodScoped(recipient, pkt); sendFloodScoped(recipient, pkt);
est_timeout = calcFloodTimeoutMillisFor(t); est_timeout = calcFloodTimeoutMillisFor(t);
return MSG_SEND_SENT_FLOOD; return MSG_SEND_SENT_FLOOD;
@@ -683,7 +692,7 @@ void BaseChatMesh::checkConnections() {
MESH_DEBUG_PRINTLN("checkConnections(): Keep_alive contact not found!"); MESH_DEBUG_PRINTLN("checkConnections(): Keep_alive contact not found!");
continue; continue;
} }
if (contact->out_path_len < 0) { if (contact->out_path_len == OUT_PATH_UNKNOWN) {
MESH_DEBUG_PRINTLN("checkConnections(): Keep_alive contact, no out_path!"); MESH_DEBUG_PRINTLN("checkConnections(): Keep_alive contact, no out_path!");
continue; continue;
} }
@@ -710,7 +719,7 @@ void BaseChatMesh::checkConnections() {
} }
void BaseChatMesh::resetPathTo(ContactInfo& recipient) { void BaseChatMesh::resetPathTo(ContactInfo& recipient) {
recipient.out_path_len = -1; recipient.out_path_len = OUT_PATH_UNKNOWN;
} }
static ContactInfo* table; // pass via global :-( static ContactInfo* table; // pass via global :-(

View File

@@ -98,6 +98,7 @@ protected:
virtual bool shouldAutoAddContactType(uint8_t type) const { return true; } virtual bool shouldAutoAddContactType(uint8_t type) const { return true; }
virtual void onContactsFull() {}; virtual void onContactsFull() {};
virtual bool shouldOverwriteWhenFull() const { return false; } virtual bool shouldOverwriteWhenFull() const { return false; }
virtual uint8_t getAutoAddMaxHops() const { return 0; } // 0 = no limit, 1 = direct (0 hops), N = up to N-1 hops
virtual void onContactOverwrite(const uint8_t* pub_key) {}; virtual void onContactOverwrite(const uint8_t* pub_key) {};
virtual void onDiscoveredContact(ContactInfo& contact, bool is_new, uint8_t path_len, const uint8_t* path) = 0; virtual void onDiscoveredContact(ContactInfo& contact, bool is_new, uint8_t path_len, const uint8_t* path) = 0;
virtual ContactInfo* processAck(const uint8_t *data) = 0; virtual ContactInfo* processAck(const uint8_t *data) = 0;

View File

@@ -114,7 +114,7 @@ ClientInfo* ClientACL::putClient(const mesh::Identity& id, uint8_t init_perms) {
memset(c, 0, sizeof(*c)); memset(c, 0, sizeof(*c));
c->permissions = init_perms; c->permissions = init_perms;
c->id = id; c->id = id;
c->out_path_len = -1; // initially out_path is unknown c->out_path_len = OUT_PATH_UNKNOWN;
return c; return c;
} }

View File

@@ -10,10 +10,12 @@
#define PERM_ACL_READ_WRITE 2 #define PERM_ACL_READ_WRITE 2
#define PERM_ACL_ADMIN 3 #define PERM_ACL_ADMIN 3
#define OUT_PATH_UNKNOWN 0xFF
struct ClientInfo { struct ClientInfo {
mesh::Identity id; mesh::Identity id;
uint8_t permissions; uint8_t permissions;
int8_t out_path_len; uint8_t out_path_len;
uint8_t out_path[MAX_PATH_SIZE]; uint8_t out_path[MAX_PATH_SIZE];
uint8_t shared_secret[PUB_KEY_SIZE]; uint8_t shared_secret[PUB_KEY_SIZE];
uint32_t last_timestamp; // by THEIR clock (transient) uint32_t last_timestamp; // by THEIR clock (transient)

View File

@@ -63,7 +63,8 @@ void CommonCLI::loadPrefsInt(FILESYSTEM* fs, const char* filename) {
file.read((uint8_t *)&_prefs->multi_acks, sizeof(_prefs->multi_acks)); // 115 file.read((uint8_t *)&_prefs->multi_acks, sizeof(_prefs->multi_acks)); // 115
file.read((uint8_t *)&_prefs->bw, sizeof(_prefs->bw)); // 116 file.read((uint8_t *)&_prefs->bw, sizeof(_prefs->bw)); // 116
file.read((uint8_t *)&_prefs->agc_reset_interval, sizeof(_prefs->agc_reset_interval)); // 120 file.read((uint8_t *)&_prefs->agc_reset_interval, sizeof(_prefs->agc_reset_interval)); // 120
file.read(pad, 3); // 121 file.read((uint8_t *)&_prefs->path_hash_mode, sizeof(_prefs->path_hash_mode)); // 121
file.read(pad, 2); // 122
file.read((uint8_t *)&_prefs->flood_max, sizeof(_prefs->flood_max)); // 124 file.read((uint8_t *)&_prefs->flood_max, sizeof(_prefs->flood_max)); // 124
file.read((uint8_t *)&_prefs->flood_advert_interval, sizeof(_prefs->flood_advert_interval)); // 125 file.read((uint8_t *)&_prefs->flood_advert_interval, sizeof(_prefs->flood_advert_interval)); // 125
file.read((uint8_t *)&_prefs->interference_threshold, sizeof(_prefs->interference_threshold)); // 126 file.read((uint8_t *)&_prefs->interference_threshold, sizeof(_prefs->interference_threshold)); // 126
@@ -81,7 +82,9 @@ void CommonCLI::loadPrefsInt(FILESYSTEM* fs, const char* filename) {
file.read((uint8_t *)&_prefs->discovery_mod_timestamp, sizeof(_prefs->discovery_mod_timestamp)); // 162 file.read((uint8_t *)&_prefs->discovery_mod_timestamp, sizeof(_prefs->discovery_mod_timestamp)); // 162
file.read((uint8_t *)&_prefs->adc_multiplier, sizeof(_prefs->adc_multiplier)); // 166 file.read((uint8_t *)&_prefs->adc_multiplier, sizeof(_prefs->adc_multiplier)); // 166
file.read((uint8_t *)_prefs->owner_info, sizeof(_prefs->owner_info)); // 170 file.read((uint8_t *)_prefs->owner_info, sizeof(_prefs->owner_info)); // 170
// 290 file.read((uint8_t *)&_prefs->flood_advert_base, sizeof(_prefs->flood_advert_base)); // 290
// 294
// sanitise bad pref values // sanitise bad pref values
_prefs->rx_delay_base = constrain(_prefs->rx_delay_base, 0, 20.0f); _prefs->rx_delay_base = constrain(_prefs->rx_delay_base, 0, 20.0f);
@@ -95,6 +98,7 @@ void CommonCLI::loadPrefsInt(FILESYSTEM* fs, const char* filename) {
_prefs->tx_power_dbm = constrain(_prefs->tx_power_dbm, -9, 30); _prefs->tx_power_dbm = constrain(_prefs->tx_power_dbm, -9, 30);
_prefs->multi_acks = constrain(_prefs->multi_acks, 0, 1); _prefs->multi_acks = constrain(_prefs->multi_acks, 0, 1);
_prefs->adc_multiplier = constrain(_prefs->adc_multiplier, 0.0f, 10.0f); _prefs->adc_multiplier = constrain(_prefs->adc_multiplier, 0.0f, 10.0f);
_prefs->path_hash_mode = constrain(_prefs->path_hash_mode, 0, 2); // NOTE: mode 3 reserved for future
// sanitise bad bridge pref values // sanitise bad bridge pref values
_prefs->bridge_enabled = constrain(_prefs->bridge_enabled, 0, 1); _prefs->bridge_enabled = constrain(_prefs->bridge_enabled, 0, 1);
@@ -108,6 +112,8 @@ void CommonCLI::loadPrefsInt(FILESYSTEM* fs, const char* filename) {
_prefs->gps_enabled = constrain(_prefs->gps_enabled, 0, 1); _prefs->gps_enabled = constrain(_prefs->gps_enabled, 0, 1);
_prefs->advert_loc_policy = constrain(_prefs->advert_loc_policy, 0, 2); _prefs->advert_loc_policy = constrain(_prefs->advert_loc_policy, 0, 2);
_prefs->flood_advert_base = constrain(_prefs->flood_advert_base, 0, 1);
file.close(); file.close();
} }
} }
@@ -147,7 +153,8 @@ void CommonCLI::savePrefs(FILESYSTEM* fs) {
file.write((uint8_t *)&_prefs->multi_acks, sizeof(_prefs->multi_acks)); // 115 file.write((uint8_t *)&_prefs->multi_acks, sizeof(_prefs->multi_acks)); // 115
file.write((uint8_t *)&_prefs->bw, sizeof(_prefs->bw)); // 116 file.write((uint8_t *)&_prefs->bw, sizeof(_prefs->bw)); // 116
file.write((uint8_t *)&_prefs->agc_reset_interval, sizeof(_prefs->agc_reset_interval)); // 120 file.write((uint8_t *)&_prefs->agc_reset_interval, sizeof(_prefs->agc_reset_interval)); // 120
file.write(pad, 3); // 121 file.write((uint8_t *)&_prefs->path_hash_mode, sizeof(_prefs->path_hash_mode)); // 121
file.write(pad, 2); // 122
file.write((uint8_t *)&_prefs->flood_max, sizeof(_prefs->flood_max)); // 124 file.write((uint8_t *)&_prefs->flood_max, sizeof(_prefs->flood_max)); // 124
file.write((uint8_t *)&_prefs->flood_advert_interval, sizeof(_prefs->flood_advert_interval)); // 125 file.write((uint8_t *)&_prefs->flood_advert_interval, sizeof(_prefs->flood_advert_interval)); // 125
file.write((uint8_t *)&_prefs->interference_threshold, sizeof(_prefs->interference_threshold)); // 126 file.write((uint8_t *)&_prefs->interference_threshold, sizeof(_prefs->interference_threshold)); // 126
@@ -165,7 +172,9 @@ void CommonCLI::savePrefs(FILESYSTEM* fs) {
file.write((uint8_t *)&_prefs->discovery_mod_timestamp, sizeof(_prefs->discovery_mod_timestamp)); // 162 file.write((uint8_t *)&_prefs->discovery_mod_timestamp, sizeof(_prefs->discovery_mod_timestamp)); // 162
file.write((uint8_t *)&_prefs->adc_multiplier, sizeof(_prefs->adc_multiplier)); // 166 file.write((uint8_t *)&_prefs->adc_multiplier, sizeof(_prefs->adc_multiplier)); // 166
file.write((uint8_t *)_prefs->owner_info, sizeof(_prefs->owner_info)); // 170 file.write((uint8_t *)_prefs->owner_info, sizeof(_prefs->owner_info)); // 170
// 290 file.write((uint8_t *)&_prefs->flood_advert_base, sizeof(_prefs->flood_advert_base)); // 290
// 294
file.close(); file.close();
} }
@@ -325,6 +334,8 @@ void CommonCLI::handleCommand(uint32_t sender_timestamp, const char* command, ch
sp++; sp++;
} }
*reply = 0; // set null terminator *reply = 0; // set null terminator
} else if (memcmp(config, "path.hash.mode", 14) == 0) {
sprintf(reply, "> %d", (uint32_t)_prefs->path_hash_mode);
} else if (memcmp(config, "tx", 2) == 0 && (config[2] == 0 || config[2] == ' ')) { } else if (memcmp(config, "tx", 2) == 0 && (config[2] == 0 || config[2] == ' ')) {
sprintf(reply, "> %d", (int32_t) _prefs->tx_power_dbm); sprintf(reply, "> %d", (int32_t) _prefs->tx_power_dbm);
} else if (memcmp(config, "freq", 4) == 0) { } else if (memcmp(config, "freq", 4) == 0) {
@@ -362,6 +373,17 @@ void CommonCLI::handleCommand(uint32_t sender_timestamp, const char* command, ch
} else if (memcmp(config, "bridge.secret", 13) == 0) { } else if (memcmp(config, "bridge.secret", 13) == 0) {
sprintf(reply, "> %s", _prefs->bridge_secret); sprintf(reply, "> %s", _prefs->bridge_secret);
#endif #endif
} else if (memcmp(config, "bootloader.ver", 14) == 0) {
#ifdef NRF52_PLATFORM
char ver[32];
if (_board->getBootloaderVersion(ver, sizeof(ver))) {
sprintf(reply, "> %s", ver);
} else {
strcpy(reply, "> unknown");
}
#else
strcpy(reply, "ERROR: unsupported");
#endif
} else if (memcmp(config, "adc.multiplier", 14) == 0) { } else if (memcmp(config, "adc.multiplier", 14) == 0) {
float adc_mult = _board->getAdcMultiplier(); float adc_mult = _board->getAdcMultiplier();
if (adc_mult == 0.0f) { if (adc_mult == 0.0f) {
@@ -369,6 +391,8 @@ void CommonCLI::handleCommand(uint32_t sender_timestamp, const char* command, ch
} else { } else {
sprintf(reply, "> %.3f", adc_mult); sprintf(reply, "> %.3f", adc_mult);
} }
} else if (memcmp(config, "flood.advert.base", 17) == 0) {
sprintf(reply, "> %s", StrHelper::ftoa(_prefs->flood_advert_base));
// Power management commands // Power management commands
} else if (memcmp(config, "pwrmgt.support", 14) == 0) { } else if (memcmp(config, "pwrmgt.support", 14) == 0) {
#ifdef NRF52_POWER_MANAGEMENT #ifdef NRF52_POWER_MANAGEMENT
@@ -545,6 +569,16 @@ void CommonCLI::handleCommand(uint32_t sender_timestamp, const char* command, ch
*dp = 0; *dp = 0;
savePrefs(); savePrefs();
strcpy(reply, "OK"); strcpy(reply, "OK");
} else if (memcmp(config, "path.hash.mode ", 15) == 0) {
config += 15;
uint8_t mode = atoi(config);
if (mode < 3) {
_prefs->path_hash_mode = mode;
savePrefs();
strcpy(reply, "OK");
} else {
strcpy(reply, "Error, must be 0,1, or 2");
}
} else if (memcmp(config, "tx ", 3) == 0) { } else if (memcmp(config, "tx ", 3) == 0) {
_prefs->tx_power_dbm = atoi(&config[3]); _prefs->tx_power_dbm = atoi(&config[3]);
savePrefs(); savePrefs();
@@ -616,6 +650,15 @@ void CommonCLI::handleCommand(uint32_t sender_timestamp, const char* command, ch
_prefs->adc_multiplier = 0.0f; _prefs->adc_multiplier = 0.0f;
strcpy(reply, "Error: unsupported by this board"); strcpy(reply, "Error: unsupported by this board");
}; };
} else if (memcmp(config, "flood.advert.base ", 18) == 0) {
float f = atof(&config[18]);
if((f > 0) || (f<1)) {
_prefs->flood_advert_base = f;
savePrefs();
strcpy(reply, "OK");
} else {
strcpy(reply, "Error: base must be between 0 and 1");
}
} else { } else {
sprintf(reply, "unknown config: %s", config); sprintf(reply, "unknown config: %s", config);
} }
@@ -691,6 +734,9 @@ void CommonCLI::handleCommand(uint32_t sender_timestamp, const char* command, ch
LocationProvider * l = _sensors->getLocationProvider(); LocationProvider * l = _sensors->getLocationProvider();
if (l != NULL) { if (l != NULL) {
l->syncTime(); l->syncTime();
strcpy(reply, "ok");
} else {
strcpy(reply, "gps provider not found");
} }
} else if (memcmp(command, "gps setloc", 10) == 0) { } else if (memcmp(command, "gps setloc", 10) == 0) {
_prefs->node_lat = _sensors->node_lat; _prefs->node_lat = _sensors->node_lat;
@@ -720,7 +766,7 @@ void CommonCLI::handleCommand(uint32_t sender_timestamp, const char* command, ch
_prefs->advert_loc_policy = ADVERT_LOC_SHARE; _prefs->advert_loc_policy = ADVERT_LOC_SHARE;
savePrefs(); savePrefs();
strcpy(reply, "ok"); strcpy(reply, "ok");
} else if (memcmp(command+11, "prefs", 4) == 0) { } else if (memcmp(command+11, "prefs", 5) == 0) {
_prefs->advert_loc_policy = ADVERT_LOC_PREFS; _prefs->advert_loc_policy = ADVERT_LOC_PREFS;
savePrefs(); savePrefs();
strcpy(reply, "ok"); strcpy(reply, "ok");

View File

@@ -36,6 +36,7 @@ struct NodePrefs { // persisted to file
uint8_t flood_max; uint8_t flood_max;
uint8_t interference_threshold; uint8_t interference_threshold;
uint8_t agc_reset_interval; // secs / 4 uint8_t agc_reset_interval; // secs / 4
float flood_advert_base;
// Bridge settings // Bridge settings
uint8_t bridge_enabled; // boolean uint8_t bridge_enabled; // boolean
uint16_t bridge_delay; // milliseconds (default 500 ms) uint16_t bridge_delay; // milliseconds (default 500 ms)
@@ -52,6 +53,7 @@ struct NodePrefs { // persisted to file
uint32_t discovery_mod_timestamp; uint32_t discovery_mod_timestamp;
float adc_multiplier; float adc_multiplier;
char owner_info[120]; char owner_info[120];
uint8_t path_hash_mode; // which path mode to use when sending
}; };
class CommonCLICallbacks { class CommonCLICallbacks {

View File

@@ -3,12 +3,14 @@
#include <Arduino.h> #include <Arduino.h>
#include <Mesh.h> #include <Mesh.h>
#define OUT_PATH_UNKNOWN 0xFF
struct ContactInfo { struct ContactInfo {
mesh::Identity id; mesh::Identity id;
char name[32]; char name[32];
uint8_t type; // on of ADV_TYPE_* uint8_t type; // on of ADV_TYPE_*
uint8_t flags; uint8_t flags;
int8_t out_path_len; uint8_t out_path_len;
mutable bool shared_secret_valid; // flag to indicate if shared_secret has been calculated mutable bool shared_secret_valid; // flag to indicate if shared_secret has been calculated
uint8_t out_path[MAX_PATH_SIZE]; uint8_t out_path[MAX_PATH_SIZE];
uint32_t last_advert_timestamp; // by THEIR clock uint32_t last_advert_timestamp; // by THEIR clock

View File

@@ -297,6 +297,25 @@ float NRF52Board::getMCUTemperature() {
return temp * 0.25f; // Convert to *C return temp * 0.25f; // Convert to *C
} }
bool NRF52Board::getBootloaderVersion(char* out, size_t max_len) {
static const char BOOTLOADER_MARKER[] = "UF2 Bootloader ";
const uint8_t* flash = (const uint8_t*)0x000FB000; // earliest known info.txt location is 0xFB90B, latest is 0xFCC4B
for (uint32_t i = 0; i < 0x3000 - (sizeof(BOOTLOADER_MARKER) - 1); i++) {
if (memcmp(&flash[i], BOOTLOADER_MARKER, sizeof(BOOTLOADER_MARKER) - 1) == 0) {
const char* ver = (const char*)&flash[i + sizeof(BOOTLOADER_MARKER) - 1];
size_t len = 0;
while (len < max_len - 1 && ver[len] != '\0' && ver[len] != ' ' && ver[len] != '\n' && ver[len] != '\r') {
out[len] = ver[len];
len++;
}
out[len] = '\0';
return len > 0; // bootloader string is non-empty
}
}
return false;
}
bool NRF52Board::startOTAUpdate(const char *id, char reply[]) { bool NRF52Board::startOTAUpdate(const char *id, char reply[]) {
// Config the peripheral connection with maximum bandwidth // Config the peripheral connection with maximum bandwidth
// more SRAM required by SoftDevice // more SRAM required by SoftDevice

View File

@@ -50,6 +50,7 @@ public:
virtual uint8_t getStartupReason() const override { return startup_reason; } virtual uint8_t getStartupReason() const override { return startup_reason; }
virtual float getMCUTemperature() override; virtual float getMCUTemperature() override;
virtual void reboot() override { NVIC_SystemReset(); } virtual void reboot() override { NVIC_SystemReset(); }
virtual bool getBootloaderVersion(char* version, size_t max_len) override;
virtual bool startOTAUpdate(const char *id, char reply[]) override; virtual bool startOTAUpdate(const char *id, char reply[]) override;
virtual void sleep(uint32_t secs) override; virtual void sleep(uint32_t secs) override;

View File

@@ -20,7 +20,10 @@ public:
digitalWrite(_pin, _active); digitalWrite(_pin, _active);
} }
} }
void release() { void release() {
if (_claims == 0) return; // avoid negative _claims
_claims--; _claims--;
if (_claims == 0) { if (_claims == 0) {
digitalWrite(_pin, !_active); digitalWrite(_pin, !_active);

View File

@@ -11,7 +11,7 @@ PacketQueue::PacketQueue(int max_entries) {
int PacketQueue::countBefore(uint32_t now) const { int PacketQueue::countBefore(uint32_t now) const {
int n = 0; int n = 0;
for (int j = 0; j < _num; j++) { for (int j = 0; j < _num; j++) {
if (_schedule_table[j] > now) continue; // scheduled for future... ignore for now if ((int32_t)(_schedule_table[j] - now) > 0) continue; // scheduled for future... ignore for now
n++; n++;
} }
return n; return n;
@@ -21,7 +21,7 @@ mesh::Packet* PacketQueue::get(uint32_t now) {
uint8_t min_pri = 0xFF; uint8_t min_pri = 0xFF;
int best_idx = -1; int best_idx = -1;
for (int j = 0; j < _num; j++) { for (int j = 0; j < _num; j++) {
if (_schedule_table[j] > now) continue; // scheduled for future... ignore for now if ((int32_t)(_schedule_table[j] - now) > 0) continue; // scheduled for future... ignore for now
if (_pri_table[j] < min_pri) { // select most important priority amongst non-future entries if (_pri_table[j] < min_pri) { // select most important priority amongst non-future entries
min_pri = _pri_table[j]; min_pri = _pri_table[j];
best_idx = j; best_idx = j;
@@ -55,15 +55,15 @@ mesh::Packet* PacketQueue::removeByIdx(int i) {
return item; return item;
} }
void PacketQueue::add(mesh::Packet* packet, uint8_t priority, uint32_t scheduled_for) { bool PacketQueue::add(mesh::Packet* packet, uint8_t priority, uint32_t scheduled_for) {
if (_num == _size) { if (_num == _size) {
// TODO: log "FATAL: queue is full!" return false;
return;
} }
_table[_num] = packet; _table[_num] = packet;
_pri_table[_num] = priority; _pri_table[_num] = priority;
_schedule_table[_num] = scheduled_for; _schedule_table[_num] = scheduled_for;
_num++; _num++;
return true;
} }
StaticPoolPacketManager::StaticPoolPacketManager(int pool_size): unused(pool_size), send_queue(pool_size), rx_queue(pool_size) { StaticPoolPacketManager::StaticPoolPacketManager(int pool_size): unused(pool_size), send_queue(pool_size), rx_queue(pool_size) {
@@ -82,7 +82,10 @@ void StaticPoolPacketManager::free(mesh::Packet* packet) {
} }
void StaticPoolPacketManager::queueOutbound(mesh::Packet* packet, uint8_t priority, uint32_t scheduled_for) { void StaticPoolPacketManager::queueOutbound(mesh::Packet* packet, uint8_t priority, uint32_t scheduled_for) {
send_queue.add(packet, priority, scheduled_for); if (!send_queue.add(packet, priority, scheduled_for)) {
MESH_DEBUG_PRINTLN("queueOutbound: send queue full, dropping packet");
free(packet);
}
} }
mesh::Packet* StaticPoolPacketManager::getNextOutbound(uint32_t now) { mesh::Packet* StaticPoolPacketManager::getNextOutbound(uint32_t now) {
@@ -106,7 +109,10 @@ mesh::Packet* StaticPoolPacketManager::removeOutboundByIdx(int i) {
} }
void StaticPoolPacketManager::queueInbound(mesh::Packet* packet, uint32_t scheduled_for) { void StaticPoolPacketManager::queueInbound(mesh::Packet* packet, uint32_t scheduled_for) {
rx_queue.add(packet, 0, scheduled_for); if (!rx_queue.add(packet, 0, scheduled_for)) {
MESH_DEBUG_PRINTLN("queueInbound: rx queue full, dropping packet");
free(packet);
}
} }
mesh::Packet* StaticPoolPacketManager::getNextInbound(uint32_t now) { mesh::Packet* StaticPoolPacketManager::getNextInbound(uint32_t now) {
return rx_queue.get(now); return rx_queue.get(now);

View File

@@ -11,7 +11,7 @@ class PacketQueue {
public: public:
PacketQueue(int max_entries); PacketQueue(int max_entries);
mesh::Packet* get(uint32_t now); mesh::Packet* get(uint32_t now);
void add(mesh::Packet* packet, uint8_t priority, uint32_t scheduled_for); bool add(mesh::Packet* packet, uint8_t priority, uint32_t scheduled_for);
int count() const { return _num; } int count() const { return _num; }
int countBefore(uint32_t now) const; int countBefore(uint32_t now) const;
mesh::Packet* itemAt(int i) const { return _table[i]; } mesh::Packet* itemAt(int i) const { return _table[i]; }

View File

@@ -2,6 +2,7 @@
#include "CustomLLCC68.h" #include "CustomLLCC68.h"
#include "RadioLibWrappers.h" #include "RadioLibWrappers.h"
#include "SX126xReset.h"
class CustomLLCC68Wrapper : public RadioLibWrapper { class CustomLLCC68Wrapper : public RadioLibWrapper {
public: public:
@@ -19,4 +20,6 @@ public:
int sf = ((CustomLLCC68 *)_radio)->spreadingFactor; int sf = ((CustomLLCC68 *)_radio)->spreadingFactor;
return packetScoreInt(snr, sf, packet_len); return packetScoreInt(snr, sf, packet_len);
} }
void doResetAGC() override { sx126xResetAGC((SX126x *)_radio); }
}; };

View File

@@ -20,6 +20,8 @@ class CustomLR1110 : public LR1110 {
return len; return len;
} }
float getFreqMHz() const { return freqMHz; }
bool isReceiving() { bool isReceiving() {
uint16_t irq = getIrqStatus(); uint16_t irq = getIrqStatus();
bool detected = ((irq & RADIOLIB_LR11X0_IRQ_SYNC_WORD_HEADER_VALID) || (irq & RADIOLIB_LR11X0_IRQ_PREAMBLE_DETECTED)); bool detected = ((irq & RADIOLIB_LR11X0_IRQ_SYNC_WORD_HEADER_VALID) || (irq & RADIOLIB_LR11X0_IRQ_PREAMBLE_DETECTED));

View File

@@ -2,11 +2,13 @@
#include "CustomLR1110.h" #include "CustomLR1110.h"
#include "RadioLibWrappers.h" #include "RadioLibWrappers.h"
#include "LR11x0Reset.h"
class CustomLR1110Wrapper : public RadioLibWrapper { class CustomLR1110Wrapper : public RadioLibWrapper {
public: public:
CustomLR1110Wrapper(CustomLR1110& radio, mesh::MainBoard& board) : RadioLibWrapper(radio, board) { } CustomLR1110Wrapper(CustomLR1110& radio, mesh::MainBoard& board) : RadioLibWrapper(radio, board) { }
bool isReceivingPacket() override { void doResetAGC() override { lr11x0ResetAGC((LR11x0 *)_radio, ((CustomLR1110 *)_radio)->getFreqMHz()); }
bool isReceivingPacket() override {
return ((CustomLR1110 *)_radio)->isReceiving(); return ((CustomLR1110 *)_radio)->isReceiving();
} }
float getCurrentRSSI() override { float getCurrentRSSI() override {

View File

@@ -2,6 +2,7 @@
#include "CustomSTM32WLx.h" #include "CustomSTM32WLx.h"
#include "RadioLibWrappers.h" #include "RadioLibWrappers.h"
#include "SX126xReset.h"
#include <math.h> #include <math.h>
class CustomSTM32WLxWrapper : public RadioLibWrapper { class CustomSTM32WLxWrapper : public RadioLibWrapper {
@@ -20,4 +21,6 @@ public:
int sf = ((CustomSTM32WLx *)_radio)->spreadingFactor; int sf = ((CustomSTM32WLx *)_radio)->spreadingFactor;
return packetScoreInt(snr, sf, packet_len); return packetScoreInt(snr, sf, packet_len);
} }
void doResetAGC() override { sx126xResetAGC((SX126x *)_radio); }
}; };

View File

@@ -2,6 +2,7 @@
#include "CustomSX1262.h" #include "CustomSX1262.h"
#include "RadioLibWrappers.h" #include "RadioLibWrappers.h"
#include "SX126xReset.h"
class CustomSX1262Wrapper : public RadioLibWrapper { class CustomSX1262Wrapper : public RadioLibWrapper {
public: public:
@@ -22,4 +23,6 @@ public:
virtual void powerOff() override { virtual void powerOff() override {
((CustomSX1262 *)_radio)->sleep(false); ((CustomSX1262 *)_radio)->sleep(false);
} }
void doResetAGC() override { sx126xResetAGC((SX126x *)_radio); }
}; };

View File

@@ -2,6 +2,7 @@
#include "CustomSX1268.h" #include "CustomSX1268.h"
#include "RadioLibWrappers.h" #include "RadioLibWrappers.h"
#include "SX126xReset.h"
class CustomSX1268Wrapper : public RadioLibWrapper { class CustomSX1268Wrapper : public RadioLibWrapper {
public: public:
@@ -19,4 +20,6 @@ public:
int sf = ((CustomSX1268 *)_radio)->spreadingFactor; int sf = ((CustomSX1268 *)_radio)->spreadingFactor;
return packetScoreInt(snr, sf, packet_len); return packetScoreInt(snr, sf, packet_len);
} }
void doResetAGC() override { sx126xResetAGC((SX126x *)_radio); }
}; };

View File

@@ -0,0 +1,21 @@
#pragma once
#include <RadioLib.h>
// Full receiver reset for LR11x0-family chips (LR1110, LR1120, LR1121).
// Warm sleep powers down analog, calibrate(0x3F) refreshes all calibration blocks,
// then re-applies RX settings that calibration may reset.
inline void lr11x0ResetAGC(LR11x0* radio, float freqMHz) {
radio->sleep(true, 0);
radio->standby(RADIOLIB_LR11X0_STANDBY_RC, true);
radio->calibrate(RADIOLIB_LR11X0_CALIBRATE_ALL);
// calibrate(0x3F) defaults image calibration to 902-928MHz band.
// Re-calibrate for the actual operating frequency (band=4MHz matches RadioLib default).
radio->calibrateImageRejection(freqMHz - 4.0f, freqMHz + 4.0f);
#ifdef RX_BOOSTED_GAIN
radio->setRxBoostedGainMode(RX_BOOSTED_GAIN);
#endif
}

View File

@@ -53,13 +53,24 @@ void RadioLibWrapper::triggerNoiseFloorCalibrate(int threshold) {
} }
} }
void RadioLibWrapper::doResetAGC() {
_radio->sleep(); // warm sleep to reset analog frontend
}
void RadioLibWrapper::resetAGC() { void RadioLibWrapper::resetAGC() {
// make sure we're not mid-receive of packet! // make sure we're not mid-receive of packet!
if ((state & STATE_INT_READY) != 0 || isReceivingPacket()) return; if ((state & STATE_INT_READY) != 0 || isReceivingPacket()) return;
// NOTE: according to higher powers, just issuing RadioLib's startReceive() will reset the AGC. doResetAGC();
// revisit this if a better impl is discovered.
state = STATE_IDLE; // trigger a startReceive() state = STATE_IDLE; // trigger a startReceive()
// Reset noise floor sampling so it reconverges from scratch.
// Without this, a stuck _noise_floor of -120 makes the sampling threshold
// too low (-106) to accept normal samples (~-105), self-reinforcing the
// stuck value even after the receiver has recovered.
_noise_floor = 0;
_num_floor_samples = 0;
_floor_sample_sum = 0;
} }
void RadioLibWrapper::loop() { void RadioLibWrapper::loop() {

View File

@@ -16,6 +16,7 @@ protected:
void startRecv(); void startRecv();
float packetScoreInt(float snr, int sf, int packet_len); float packetScoreInt(float snr, int sf, int packet_len);
virtual bool isReceivingPacket() =0; virtual bool isReceivingPacket() =0;
virtual void doResetAGC();
public: public:
RadioLibWrapper(PhysicalLayer& radio, mesh::MainBoard& board) : _radio(&radio), _board(&board) { n_recv = n_sent = 0; } RadioLibWrapper(PhysicalLayer& radio, mesh::MainBoard& board) : _radio(&radio), _board(&board) { n_recv = n_sent = 0; }

View File

@@ -0,0 +1,37 @@
#pragma once
#include <RadioLib.h>
// Full receiver reset for all SX126x-family chips (SX1262, SX1268, LLCC68, STM32WLx).
// Warm sleep powers down analog, Calibrate(0x7F) refreshes ADC/PLL/image calibration,
// then re-applies RX settings that calibration may reset.
inline void sx126xResetAGC(SX126x* radio) {
radio->sleep(true);
radio->standby(RADIOLIB_SX126X_STANDBY_RC, true);
uint8_t calData = RADIOLIB_SX126X_CALIBRATE_ALL;
radio->mod->SPIwriteStream(RADIOLIB_SX126X_CMD_CALIBRATE, &calData, 1, true, false);
radio->mod->hal->delay(5);
uint32_t start = millis();
while (radio->mod->hal->digitalRead(radio->mod->getGpio())) {
if (millis() - start > 50) break;
radio->mod->hal->yield();
}
// Calibrate(0x7F) defaults image calibration to 902-928MHz band.
// Re-calibrate for the actual operating frequency.
radio->calibrateImage(radio->freqMHz);
#ifdef SX126X_DIO2_AS_RF_SWITCH
radio->setDio2AsRfSwitch(SX126X_DIO2_AS_RF_SWITCH);
#endif
#ifdef SX126X_RX_BOOSTED_GAIN
radio->setRxBoostedGainMode(SX126X_RX_BOOSTED_GAIN);
#endif
#ifdef SX126X_REGISTER_PATCH
uint8_t r_data = 0;
radio->readRegister(0x8B5, &r_data, 1);
r_data |= 0x01;
radio->writeRegister(0x8B5, &r_data, 1);
#endif
}

View File

@@ -707,7 +707,9 @@ void EnvironmentSensorManager::loop() {
static long next_gps_update = 0; static long next_gps_update = 0;
#if ENV_INCLUDE_GPS #if ENV_INCLUDE_GPS
_location->loop(); if (gps_active) {
_location->loop();
}
if (millis() > next_gps_update) { if (millis() > next_gps_update) {
if(gps_active){ if(gps_active){

View File

@@ -79,7 +79,10 @@ public :
if (_pin_en != -1) { if (_pin_en != -1) {
digitalWrite(_pin_en, !PIN_GPS_EN_ACTIVE); digitalWrite(_pin_en, !PIN_GPS_EN_ACTIVE);
} }
if (_peripher_power) _peripher_power->release(); if (_pin_reset != -1) {
digitalWrite(_pin_reset, GPS_RESET_FORCE);
}
if (_peripher_power) _peripher_power->release();
} }
bool isEnabled() override { bool isEnabled() override {

View File

@@ -32,6 +32,11 @@ build_flags =
-D PIN_TFT_LEDA_CTL=21 ; LEDK (switches on/off via mosfet to create the ground) -D PIN_TFT_LEDA_CTL=21 ; LEDK (switches on/off via mosfet to create the ground)
-D PIN_GPS_RX=33 -D PIN_GPS_RX=33
-D PIN_GPS_TX=34 -D PIN_GPS_TX=34
-D PIN_GPS_EN=35 ; N-ch MOSFET Q2 drives P-ch high-side switch → active HIGH (default)
-D PIN_GPS_RESET=36
-D PIN_GPS_RESET_ACTIVE=LOW
-D GPS_BAUD_RATE=115200
-D ENV_INCLUDE_GPS=1
-D SX126X_DIO2_AS_RF_SWITCH=true -D SX126X_DIO2_AS_RF_SWITCH=true
-D SX126X_DIO3_TCXO_VOLTAGE=1.8 -D SX126X_DIO3_TCXO_VOLTAGE=1.8
-D SX126X_CURRENT_LIMIT=140 -D SX126X_CURRENT_LIMIT=140
@@ -43,6 +48,31 @@ lib_deps =
stevemarple/MicroNMEA @ ^2.0.6 stevemarple/MicroNMEA @ ^2.0.6
adafruit/Adafruit ST7735 and ST7789 Library @ ^1.11.0 adafruit/Adafruit ST7735 and ST7789 Library @ ^1.11.0
[env:Heltec_Wireless_Tracker_companion_radio_usb]
extends = Heltec_tracker_base
build_flags =
${Heltec_tracker_base.build_flags}
-I src/helpers/ui
-I examples/companion_radio/ui-new
-D DISPLAY_ROTATION=1
-D DISPLAY_CLASS=ST7735Display
-D MAX_CONTACTS=350
-D MAX_GROUP_CHANNELS=40
; -D BLE_PIN_CODE=123456 ; HWT will use display for pin
; -D OFFLINE_QUEUE_SIZE=256
; -D BLE_DEBUG_LOGGING=1
; -D MESH_PACKET_LOGGING=1
; -D MESH_DEBUG=1
build_src_filter = ${Heltec_tracker_base.build_src_filter}
+<helpers/esp32/*.cpp>
+<helpers/ui/MomentaryButton.cpp>
+<../examples/companion_radio/*.cpp>
+<../examples/companion_radio/ui-new/*.cpp>
+<helpers/ui/ST7735Display.cpp>
lib_deps =
${Heltec_tracker_base.lib_deps}
densaugeo/base64 @ ~1.4.0
[env:Heltec_Wireless_Tracker_companion_radio_ble] [env:Heltec_Wireless_Tracker_companion_radio_ble]
extends = Heltec_tracker_base extends = Heltec_tracker_base
build_flags = build_flags =

View File

@@ -16,7 +16,8 @@ WRAPPER_CLASS radio_driver(radio, board);
ESP32RTCClock fallback_clock; ESP32RTCClock fallback_clock;
AutoDiscoverRTCClock rtc_clock(fallback_clock); AutoDiscoverRTCClock rtc_clock(fallback_clock);
MicroNMEALocationProvider nmea = MicroNMEALocationProvider(Serial1); // GPS_EN (GPIO35) drives N-ch MOSFET → P-ch high-side switch; GPS_RESET (GPIO36) active LOW
MicroNMEALocationProvider nmea = MicroNMEALocationProvider(Serial1, &rtc_clock, GPS_RESET, GPS_EN, &board.periph_power);
HWTSensorManager sensors = HWTSensorManager(nmea); HWTSensorManager sensors = HWTSensorManager(nmea);
#ifdef DISPLAY_CLASS #ifdef DISPLAY_CLASS
@@ -58,18 +59,16 @@ mesh::LocalIdentity radio_new_identity() {
void HWTSensorManager::start_gps() { void HWTSensorManager::start_gps() {
if (!gps_active) { if (!gps_active) {
board.periph_power.claim(); _location->begin(); // Claims periph_power via RefCountedDigitalPin
gps_active = true; gps_active = true;
Serial1.println("$CFGSYS,h35155*68"); Serial1.println("$CFGSYS,h35155*68"); // Configure GPS for all constellations
} }
} }
void HWTSensorManager::stop_gps() { void HWTSensorManager::stop_gps() {
if (gps_active) { if (gps_active) {
gps_active = false; gps_active = false;
_location->stop(); // Releases periph_power via RefCountedDigitalPin
board.periph_power.release();
} }
} }

View File

@@ -28,6 +28,7 @@ public:
const char* getSettingName(int i) const override; const char* getSettingName(int i) const override;
const char* getSettingValue(int i) const override; const char* getSettingValue(int i) const override;
bool setSettingValue(const char* name, const char* value) override; bool setSettingValue(const char* name, const char* value) override;
LocationProvider* getLocationProvider() override { return _location; }
}; };
extern HeltecV3Board board; extern HeltecV3Board board;

View File

@@ -6,18 +6,26 @@ void HeltecTrackerV2Board::begin() {
pinMode(PIN_ADC_CTRL, OUTPUT); pinMode(PIN_ADC_CTRL, OUTPUT);
digitalWrite(PIN_ADC_CTRL, LOW); // Initially inactive digitalWrite(PIN_ADC_CTRL, LOW); // Initially inactive
// Set up digital GPIO registers before releasing RTC hold. The hold latches
// the pad state including function select, so register writes accumulate
// without affecting the pad. On hold release, all changes apply atomically
// (IO MUX switches to digital GPIO with output already HIGH — no glitch).
pinMode(P_LORA_PA_POWER, OUTPUT); pinMode(P_LORA_PA_POWER, OUTPUT);
digitalWrite(P_LORA_PA_POWER,HIGH); digitalWrite(P_LORA_PA_POWER,HIGH);
rtc_gpio_hold_dis((gpio_num_t)P_LORA_PA_POWER);
rtc_gpio_hold_dis((gpio_num_t)P_LORA_PA_EN);
pinMode(P_LORA_PA_EN, OUTPUT); pinMode(P_LORA_PA_EN, OUTPUT);
digitalWrite(P_LORA_PA_EN,HIGH); digitalWrite(P_LORA_PA_EN,HIGH);
rtc_gpio_hold_dis((gpio_num_t)P_LORA_PA_EN);
pinMode(P_LORA_PA_TX_EN, OUTPUT); pinMode(P_LORA_PA_TX_EN, OUTPUT);
digitalWrite(P_LORA_PA_TX_EN,LOW); digitalWrite(P_LORA_PA_TX_EN,LOW);
periph_power.begin();
esp_reset_reason_t reason = esp_reset_reason(); esp_reset_reason_t reason = esp_reset_reason();
if (reason != ESP_RST_DEEPSLEEP) {
delay(1); // GC1109 startup time after cold power-on
}
periph_power.begin();
if (reason == ESP_RST_DEEPSLEEP) { if (reason == ESP_RST_DEEPSLEEP) {
long wakeup_source = esp_sleep_get_ext1_wakeup_status(); long wakeup_source = esp_sleep_get_ext1_wakeup_status();
if (wakeup_source & (1 << P_LORA_DIO_1)) { // received a LoRa packet (while in deep sleep) if (wakeup_source & (1 << P_LORA_DIO_1)) { // received a LoRa packet (while in deep sleep)
@@ -48,7 +56,9 @@ void HeltecTrackerV2Board::begin() {
rtc_gpio_hold_en((gpio_num_t)P_LORA_NSS); rtc_gpio_hold_en((gpio_num_t)P_LORA_NSS);
rtc_gpio_hold_en((gpio_num_t)P_LORA_PA_EN); //It also needs to be enabled in receive mode // Hold GC1109 FEM pins during sleep to keep LNA active for RX wake
rtc_gpio_hold_en((gpio_num_t)P_LORA_PA_POWER);
rtc_gpio_hold_en((gpio_num_t)P_LORA_PA_EN);
if (pin_wake_btn < 0) { if (pin_wake_btn < 0) {
esp_sleep_enable_ext1_wakeup( (1L << P_LORA_DIO_1), ESP_EXT1_WAKEUP_ANY_HIGH); // wake up on: recv LoRa packet esp_sleep_enable_ext1_wakeup( (1L << P_LORA_DIO_1), ESP_EXT1_WAKEUP_ANY_HIGH); // wake up on: recv LoRa packet

View File

@@ -17,11 +17,11 @@ build_flags =
-D P_LORA_SCLK=9 -D P_LORA_SCLK=9
-D P_LORA_MISO=11 -D P_LORA_MISO=11
-D P_LORA_MOSI=10 -D P_LORA_MOSI=10
-D P_LORA_PA_POWER=7 ;power en -D P_LORA_PA_POWER=7 ; VFEM_Ctrl - GC1109 LDO power enable
-D P_LORA_PA_EN=4 -D P_LORA_PA_EN=4 ; CSD - GC1109 chip enable (HIGH=on)
-D P_LORA_PA_TX_EN=46 ;enable tx -D P_LORA_PA_TX_EN=46 ; CPS - GC1109 PA mode (HIGH=full PA, LOW=bypass)
-D LORA_TX_POWER=10 ;If it is configured as 10 here, the final output will be 22 dbm. -D LORA_TX_POWER=10 ; 10dBm + ~11dB GC1109 gain = ~21dBm output
-D MAX_LORA_TX_POWER=22 ;Max SX1262 output -D MAX_LORA_TX_POWER=22 ; Max SX1262 output -> ~28dBm at antenna
-D SX126X_DIO2_AS_RF_SWITCH=true -D SX126X_DIO2_AS_RF_SWITCH=true
-D SX126X_DIO3_TCXO_VOLTAGE=1.8 -D SX126X_DIO3_TCXO_VOLTAGE=1.8
-D SX126X_CURRENT_LIMIT=140 -D SX126X_CURRENT_LIMIT=140

View File

@@ -7,19 +7,26 @@ void HeltecV4Board::begin() {
pinMode(PIN_ADC_CTRL, OUTPUT); pinMode(PIN_ADC_CTRL, OUTPUT);
digitalWrite(PIN_ADC_CTRL, LOW); // Initially inactive digitalWrite(PIN_ADC_CTRL, LOW); // Initially inactive
// Set up digital GPIO registers before releasing RTC hold. The hold latches
// the pad state including function select, so register writes accumulate
// without affecting the pad. On hold release, all changes apply atomically
// (IO MUX switches to digital GPIO with output already HIGH — no glitch).
pinMode(P_LORA_PA_POWER, OUTPUT); pinMode(P_LORA_PA_POWER, OUTPUT);
digitalWrite(P_LORA_PA_POWER,HIGH); digitalWrite(P_LORA_PA_POWER,HIGH);
rtc_gpio_hold_dis((gpio_num_t)P_LORA_PA_POWER);
rtc_gpio_hold_dis((gpio_num_t)P_LORA_PA_EN);
pinMode(P_LORA_PA_EN, OUTPUT); pinMode(P_LORA_PA_EN, OUTPUT);
digitalWrite(P_LORA_PA_EN,HIGH); digitalWrite(P_LORA_PA_EN,HIGH);
rtc_gpio_hold_dis((gpio_num_t)P_LORA_PA_EN);
pinMode(P_LORA_PA_TX_EN, OUTPUT); pinMode(P_LORA_PA_TX_EN, OUTPUT);
digitalWrite(P_LORA_PA_TX_EN,LOW); digitalWrite(P_LORA_PA_TX_EN,LOW);
esp_reset_reason_t reason = esp_reset_reason();
if (reason != ESP_RST_DEEPSLEEP) {
delay(1); // GC1109 startup time after cold power-on
}
periph_power.begin(); periph_power.begin();
esp_reset_reason_t reason = esp_reset_reason();
if (reason == ESP_RST_DEEPSLEEP) { if (reason == ESP_RST_DEEPSLEEP) {
long wakeup_source = esp_sleep_get_ext1_wakeup_status(); long wakeup_source = esp_sleep_get_ext1_wakeup_status();
if (wakeup_source & (1 << P_LORA_DIO_1)) { // received a LoRa packet (while in deep sleep) if (wakeup_source & (1 << P_LORA_DIO_1)) { // received a LoRa packet (while in deep sleep)
@@ -50,7 +57,9 @@ void HeltecV4Board::begin() {
rtc_gpio_hold_en((gpio_num_t)P_LORA_NSS); rtc_gpio_hold_en((gpio_num_t)P_LORA_NSS);
rtc_gpio_hold_en((gpio_num_t)P_LORA_PA_EN); //It also needs to be enabled in receive mode // Hold GC1109 FEM pins during sleep to keep LNA active for RX wake
rtc_gpio_hold_en((gpio_num_t)P_LORA_PA_POWER);
rtc_gpio_hold_en((gpio_num_t)P_LORA_PA_EN);
if (pin_wake_btn < 0) { if (pin_wake_btn < 0) {
esp_sleep_enable_ext1_wakeup( (1L << P_LORA_DIO_1), ESP_EXT1_WAKEUP_ANY_HIGH); // wake up on: recv LoRa packet esp_sleep_enable_ext1_wakeup( (1L << P_LORA_DIO_1), ESP_EXT1_WAKEUP_ANY_HIGH); // wake up on: recv LoRa packet

View File

@@ -22,7 +22,7 @@ build_flags =
-D P_LORA_PA_TX_EN=46 ; PA CPS - GC1109 TX PA full(High) / bypass(Low) -D P_LORA_PA_TX_EN=46 ; PA CPS - GC1109 TX PA full(High) / bypass(Low)
-D PIN_USER_BTN=0 -D PIN_USER_BTN=0
-D PIN_VEXT_EN=36 -D PIN_VEXT_EN=36
-D PIN_VEXT_EN_ACTIVE=LOW -D PIN_VEXT_EN_ACTIVE=HIGH
-D LORA_TX_POWER=10 ;If it is configured as 10 here, the final output will be 22 dbm. -D LORA_TX_POWER=10 ;If it is configured as 10 here, the final output will be 22 dbm.
-D MAX_LORA_TX_POWER=22 ; Max SX1262 output -D MAX_LORA_TX_POWER=22 ; Max SX1262 output
-D SX126X_REGISTER_PATCH=1 ; Patch register 0x8B5 for improved RX -D SX126X_REGISTER_PATCH=1 ; Patch register 0x8B5 for improved RX
@@ -54,8 +54,6 @@ build_flags =
-D PIN_BOARD_SDA=17 -D PIN_BOARD_SDA=17
-D PIN_BOARD_SCL=18 -D PIN_BOARD_SCL=18
-D PIN_OLED_RESET=21 -D PIN_OLED_RESET=21
-D ENV_PIN_SDA=4
-D ENV_PIN_SCL=3
build_src_filter= ${Heltec_lora32_v4.build_src_filter} build_src_filter= ${Heltec_lora32_v4.build_src_filter}
lib_deps = ${Heltec_lora32_v4.lib_deps} lib_deps = ${Heltec_lora32_v4.lib_deps}

View File

@@ -24,7 +24,7 @@ AutoDiscoverRTCClock rtc_clock(fallback_clock);
#endif #endif
#ifdef DISPLAY_CLASS #ifdef DISPLAY_CLASS
DISPLAY_CLASS display(&(board.periph_power)); DISPLAY_CLASS display(NULL);
MomentaryButton user_btn(PIN_USER_BTN, 1000, true); MomentaryButton user_btn(PIN_USER_BTN, 1000, true);
#endif #endif

View File

@@ -26,7 +26,9 @@ build_src_filter = ${esp32_base.build_src_filter}
+<helpers/ui/SH1106Display.cpp> +<helpers/ui/SH1106Display.cpp>
+<helpers/esp32/TBeamBoard.cpp> +<helpers/esp32/TBeamBoard.cpp>
+<helpers/sensors> +<helpers/sensors>
board_build.partitions = min_spiffs.csv ; get around 4mb flash limit board_build.partitions = default_8MB.csv
board_upload.flash_size = 8MB
board_upload.maximum_size = 8388608
lib_deps = lib_deps =
${esp32_base.lib_deps} ${esp32_base.lib_deps}
lewisxhe/XPowersLib @ ^0.2.7 lewisxhe/XPowersLib @ ^0.2.7
@@ -131,3 +133,27 @@ build_src_filter = ${T_Beam_S3_Supreme_SX1262.build_src_filter}
lib_deps = lib_deps =
${T_Beam_S3_Supreme_SX1262.lib_deps} ${T_Beam_S3_Supreme_SX1262.lib_deps}
densaugeo/base64 @ ~1.4.0 densaugeo/base64 @ ~1.4.0
[env:T_Beam_S3_Supreme_SX1262_companion_radio_wifi]
extends = T_Beam_S3_Supreme_SX1262
build_flags =
${T_Beam_S3_Supreme_SX1262.build_flags}
-I examples/companion_radio/ui-new
-D MAX_CONTACTS=350
-D MAX_GROUP_CHANNELS=40
-D OFFLINE_QUEUE_SIZE=256
-D WIFI_SSID='"WIFI_SSID"'
-D WIFI_PWD='"Password"'
; -D WIFI_DEBUG_LOGGING=1
; -D MESH_PACKET_LOGGING=8
; -D MESH_DEBUG=1
; -D ARDUHAL_LOG_LEVEL=4
; -D CORE_DEBUG_LEVEL=4
build_src_filter = ${T_Beam_S3_Supreme_SX1262.build_src_filter}
+<helpers/esp32/*.cpp>
+<helpers/ui/MomentaryButton.cpp>
+<../examples/companion_radio/*.cpp>
+<../examples/companion_radio/ui-new/*.cpp>
lib_deps =
${T_Beam_S3_Supreme_SX1262.lib_deps}
densaugeo/base64 @ ~1.4.0

View File

@@ -94,6 +94,8 @@ build_flags = ${M5Stack_Unit_C6L.build_flags}
-D MAX_CONTACTS=350 -D MAX_CONTACTS=350
-D MAX_GROUP_CHANNELS=40 -D MAX_GROUP_CHANNELS=40
-D OFFLINE_QUEUE_SIZE=256 -D OFFLINE_QUEUE_SIZE=256
-D ARDUINO_USB_CDC_ON_BOOT=1
-D ARDUINO_USB_MODE=1
build_src_filter = ${M5Stack_Unit_C6L.build_src_filter} build_src_filter = ${M5Stack_Unit_C6L.build_src_filter}
+<helpers/esp32/*.cpp> +<helpers/esp32/*.cpp>
-<helpers/esp32/ESPNOWRadio.cpp> -<helpers/esp32/ESPNOWRadio.cpp>

View File

@@ -20,13 +20,29 @@ void RAK3401Board::begin() {
Wire.begin(); Wire.begin();
// PIN_3V3_EN (WB_IO2, P0.34) controls the 3V3_S switched peripheral rail
// AND the 5V boost regulator (U5) on the RAK13302 that powers the SKY66122 PA.
// Must stay HIGH during radio operation — do not toggle for power saving.
pinMode(PIN_3V3_EN, OUTPUT); pinMode(PIN_3V3_EN, OUTPUT);
digitalWrite(PIN_3V3_EN, HIGH); digitalWrite(PIN_3V3_EN, HIGH);
#ifdef P_LORA_PA_EN // Enable SKY66122-11 FEM on the RAK13302 module.
// Initialize RAK13302 1W LoRa transceiver module PA control pin // CSD and CPS are tied together on the RAK13302 PCB, routed to IO3 (P0.21).
pinMode(P_LORA_PA_EN, OUTPUT); // HIGH = FEM active (LNA for RX, PA path available for TX).
digitalWrite(P_LORA_PA_EN, LOW); // Start with PA disabled // TX/RX switching (CTX) is handled by SX1262 DIO2 via SetDIO2AsRfSwitchCtrl.
delay(10); // Allow PA module to initialize pinMode(SX126X_POWER_EN, OUTPUT);
digitalWrite(SX126X_POWER_EN, HIGH);
delay(1); // SKY66122 turn-on settling time (tON = 3us typ)
}
#ifdef NRF52_POWER_MANAGEMENT
void RAK3401Board::initiateShutdown(uint8_t reason) {
// Disable SKY66122 FEM (CSD+CPS LOW = shutdown, <1 uA)
digitalWrite(SX126X_POWER_EN, LOW);
// Disable 3V3 switched peripherals and 5V boost
digitalWrite(PIN_3V3_EN, LOW);
enterSystemOff(reason);
}
#endif #endif
}

View File

@@ -38,13 +38,6 @@ public:
return "RAK 3401"; return "RAK 3401";
} }
#ifdef P_LORA_PA_EN // TX/RX switching is handled by SX1262 DIO2 -> SKY66122 CTX (hardware-timed).
void onBeforeTransmit() override { // No onBeforeTransmit/onAfterTransmit overrides needed.
digitalWrite(P_LORA_PA_EN, HIGH); // Enable PA before transmission
}
void onAfterTransmit() override {
digitalWrite(P_LORA_PA_EN, LOW); // Disable PA after transmission to save power
}
#endif
}; };

View File

@@ -11,6 +11,7 @@ build_flags = ${nrf52_base.build_flags}
-D LORA_TX_POWER=22 -D LORA_TX_POWER=22
-D SX126X_CURRENT_LIMIT=140 -D SX126X_CURRENT_LIMIT=140
-D SX126X_RX_BOOSTED_GAIN=1 -D SX126X_RX_BOOSTED_GAIN=1
-D SX126X_REGISTER_PATCH=1 ; Patch register 0x8B5 for improved RX with SKY66122 FEM
build_src_filter = ${nrf52_base.build_src_filter} build_src_filter = ${nrf52_base.build_src_filter}
+<../variants/rak3401> +<../variants/rak3401>
+<helpers/sensors> +<helpers/sensors>

View File

@@ -147,8 +147,15 @@ static const uint8_t AREF = PIN_AREF;
#define SX126X_BUSY (9) #define SX126X_BUSY (9)
#define SX126X_RESET (4) #define SX126X_RESET (4)
#define SX126X_POWER_EN (21) // SKY66122-11 FEM control on the RAK13302 module:
// DIO2 controlls an antenna switch and the TCXO voltage is controlled by DIO3 // CSD + CPS are tied together on the PCB, routed to WisBlock IO3 (P0.21).
// Setting IO3 HIGH enables the FEM (LNA for RX, PA path for TX).
// CTX is connected to SX1262 DIO2 — the radio handles TX/RX switching
// in hardware via SetDIO2AsRfSwitchCtrl (microsecond-accurate, no GPIO needed).
// The 5V boost for the PA is enabled by WB_IO2 (P0.34 = PIN_3V3_EN).
#define SX126X_POWER_EN (21) // P0.21 = IO3 -> SKY66122 CSD+CPS (FEM enable)
// CTX is driven by SX1262 DIO2, not a GPIO
#define SX126X_DIO2_AS_RF_SWITCH #define SX126X_DIO2_AS_RF_SWITCH
#define SX126X_DIO3_TCXO_VOLTAGE 1.8 #define SX126X_DIO3_TCXO_VOLTAGE 1.8
@@ -159,7 +166,6 @@ static const uint8_t AREF = PIN_AREF;
#define P_LORA_DIO_1 SX126X_DIO1 #define P_LORA_DIO_1 SX126X_DIO1
#define P_LORA_BUSY SX126X_BUSY #define P_LORA_BUSY SX126X_BUSY
#define P_LORA_RESET SX126X_RESET #define P_LORA_RESET SX126X_RESET
#define P_LORA_PA_EN 31
// enables 3.3V periphery like GPS or IO Module // enables 3.3V periphery like GPS or IO Module
// Do not toggle this for GPS power savings // Do not toggle this for GPS power savings

View File

@@ -106,7 +106,7 @@ extern "C"
// Power management boot protection threshold (millivolts) // Power management boot protection threshold (millivolts)
// Set to 0 to disable boot protection // Set to 0 to disable boot protection
#define PWRMGT_VOLTAGE_BOOTLOCK 3300 // Won't boot below this voltage (mV) #define PWRMGT_VOLTAGE_BOOTLOCK 0 // Won't boot below this voltage (mV)
// LPCOMP wake configuration (voltage recovery from SYSTEMOFF) // LPCOMP wake configuration (voltage recovery from SYSTEMOFF)
// AIN3 = P0.05 = PIN_A0 / PIN_VBAT_READ // AIN3 = P0.05 = PIN_A0 / PIN_VBAT_READ
#define PWRMGT_LPCOMP_AIN 3 #define PWRMGT_LPCOMP_AIN 3