mirror of
https://github.com/meshtastic/firmware.git
synced 2026-05-19 06:14:12 -04:00
feat: add Nordic nRF54L15-DK variant (Zephyr + BLE + LoRa) (#10193)
* feat: add Nordic nRF54L15-DK variant (Zephyr + BLE + LoRa)
Adds a community hardware variant for the Nordic nRF54L15-DK (PCA10156)
with an external EBYTE E22-900M30S (SX1262) LoRa module. First Meshtastic
port running on the Zephyr RTOS; all other Nordic targets use the nRF5
SoftDevice stack.
Scope
-----
- New Zephyr-based platform layer under src/platform/nrf54l15/ providing
Arduino-compatible shims (Arduino.h, SPI, Wire, Print, Stream) over the
Zephyr APIs plus a LittleFS-backed InternalFileSystem on SPIM20.
- Bluetooth LE peripheral (NRF54L15Bluetooth.*) built on the Zephyr BT
host stack, exposing the Meshtastic GATT service with legacy
connectable advertising, just-works pairing, dynamic MTU exchange
(up to 247 bytes), and iOS connection-parameter tweaks.
- Variant directory variants/nrf54l15/nrf54l15dk/ with pin map for the
E22 module on connector J1, PlatformIO env (nrf54l15dk), Zephyr
DT overlay and a wiring README.
- Zephyr project config (zephyr/prj.conf + board overlay) tuned for
BT + LoRa: 16 KB main stack, 4 KB BT RX thread, RTT logging in
immediate mode, newlib-nano heap sized to leave room for the GATT
pools while still allowing ATT MTU=247.
- extra_scripts/nrf54l15_linker.py works around a PlatformIO + old Ninja
issue where Zephyr's two-pass linker script generation does not run
automatically; the post-script parses build.ninja and invokes the
gcc -E step directly before the final link.
- boards/nrf54l15dk.json board definition (PlatformIO needs it for the
DK; the Seeed platform only ships the XIAO variants).
- variants/rp2350/rp2350.ini excludes platform/nrf54l15/ from RP2350
build_src_filter so the shared platform tree does not leak between
targets.
- .gitignore: add nRF J-Link / RTT debug artifacts (flash.jlink,
rtt_*.txt).
Shared source changes
---------------------
- src/main.{cpp,h}, src/RedirectablePrint.cpp, src/FSCommon.{cpp,h},
src/mesh/{Channels,NodeDB,RadioLibInterface,MeshService,PhoneAPI}.cpp,
src/mesh/RadioLibInterface.h, src/modules/AdminModule.cpp: add small
guards / helpers so the Zephyr build compiles alongside the Arduino
targets. Behavior on existing boards is unchanged.
Hardware model
--------------
HW_VENDOR maps to meshtastic_HardwareModel_PRIVATE_HW until a dedicated
protobuf enum value is assigned upstream. The variant declares
custom_meshtastic_hw_model = 132 so the maintainers can wire the new
enum value through the protobufs repo after merge.
Hardware note
-------------
The E22-900M30S does not connect its DIO2 pin to TXEN internally — a
wire/solder bridge between DIO2 and TXEN on the module is required for
TX to work. Details and full pin map are in the variant README.
Validation
----------
Built clean against develop. On real hardware (April 2026) the port
passes end-to-end: iOS companion app pairs and connects, configuration
round-trip works, LoRa TX/RX reaches a canonical tbeam on the same mesh
channel, NodeDB updates propagate both ways, and traceroute completes.
* fix(nrf54l15): use atomic fs_rename instead of copy fallback
Zephyr LittleFS on nrf54l15 supports fs_rename natively, so route it
through the same atomic path as ESP32. The previous copyFile+remove
fallback truncated the destination before copying, leaving 0-byte files
if interrupted mid-write.
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
* fix(nrf54l15): expand storage_partition from 36KB to 700KB
LittleFS on the default 9-block (36KB) storage_partition ran out of
space during copy-on-write of config.proto, causing fs_write to return
ENOSPC and pb_encode to surface "io error" when saving configuration
via the mobile app.
Reclaim slot1_partition (the MCUboot secondary slot — unused since we
flash directly via J-Link) and grow storage_partition to span
0xb6000..0x165000 (~175 blocks).
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
* fix(nrf54l15): drop USERPREFS_LORACONFIG_* so LoRa config stays mutable
NodeDB rewrites LoRa config from USERPREFS_LORACONFIG_* on every boot,
which prevented reconfiguration via the BLE/serial app. Drop the
variant-level defaults; users configure region and modem preset through
the app like every other variant.
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
* fix(nrf54l15): enforce MITM passkey pairing on GATT service
- Add MESH_PERM_READ/MESH_PERM_WRITE macros (READ_AUTHEN/WRITE_AUTHEN)
on all mesh service characteristics so clients must complete passkey
exchange before accessing fromNum/fromRadio/toRadio/logRadio.
- Wire FIXED_PIN mode to bt_passkey_set() so the device advertises a
known PIN (config.bluetooth.fixed_pin); RANDOM_PIN keeps default
per-pairing random passkey.
- Reduce BleDeferredThread HARD_WATCHDOG_MS from 3min to 1min.
- prj.conf: CONFIG_BT_SMP_ENFORCE_MITM=y, CONFIG_BT_FIXED_PASSKEY=y,
CONFIG_BT_SMP_SC_PAIR_ONLY=n (legacy fallback for clients that abort
SC pairing with reason 0x01 within 150ms).
* fix(nrf54l15): resolve develop-merge conflict + cppcheck warnings
The `Merge branch 'develop'` left two ~RadioLibInterface() declarations
in src/mesh/RadioLibInterface.h: the inline version added upstream by
PR #10254 (which independently applied the same UAF guard this PR was
carrying) and the out-of-line version this PR introduced. GCC rejects
the duplicate, breaking every platform build. Drop the out-of-line
declaration + definition; keep upstream's inline form.
Also silence the 13 cppcheck low warnings introduced by the new
nrf54l15 Arduino shim — Arduino's `String`/`SPISettings` API contract
relies on implicit single-arg constructors used pervasively by
existing Meshtastic code, so suppress `noExplicitConstructor` inline
with a comment instead of breaking the API. The few mechanical wins
(`const tmp[2]`, `const uint32_t *sp`) are applied directly.
* fmt: fix Trunk Check lint issues on nrf54l15-port
- extra_scripts/nrf54l15_linker.py: move regular imports above
Import("env") to silence E402, add trunk-ignore-all(F821) for the
PIO/SCons SConstruct injection (matches esp32_pre.py / nrf52_extra.py
convention)
- src/platform/nrf54l15/NRF54L15Bluetooth.cpp: clang-format 16.0.3
- boards/nrf54l15dk.json + variants/nrf54l15/nrf54l15dk/README.md:
prettier 3.8.3 (also resolves markdownlint MD060 on README tables)
No behavior change.
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
* fix(nrf54l15): address Copilot review comments + correct clang-format style
Six review threads from the 2026-04-30 Copilot review:
- src/platform/nrf54l15/nrf54l15_main.cpp: validate PSP against the nRF54L15
SRAM range (0x20000000..0x20040000) and 4-byte alignment before walking the
faulting thread's stack, and clamp the walk so it never reads past the end
of RAM. Prevents a second fault inside the fatal handler when PSP is
corrupted (common in real faults).
- src/platform/nrf54l15/nrf54l15_arduino.cpp: gate the bring-up printk traces
in digitalWrite/digitalRead (CS/NRESET toggle log, BUSY-before-NRESET
snapshot, BUSY periodic timeline) behind a new -DNRF54L15_GPIO_DEBUG flag
that is off by default. The "dev NOT READY" message stays unconditional —
it indicates a genuine hardware/DTS misconfig.
- src/modules/AdminModule.cpp: don't mutate config.device.output_gpio_enabled
from handleGetConfig(). Reflect the live pin state in the response payload
only — a getter must not write back to disk-persisted state.
- src/platform/nrf54l15/InternalFileSystem.h: derive totalBytes() from
FIXED_PARTITION_SIZE(storage_partition) at compile time so it tracks the
DK overlay's ~700 KB partition instead of the stale 36 KB hard-coded value.
Updated the file header comment accordingly.
- extra_scripts/nrf54l15_linker.py: make _extract_gcc_command() handle the
POSIX Ninja COMMAND format (no `cmd.exe /C "..."` wrapper) in addition to
the Windows form, so the script doesn't hard-fail on Linux/macOS hosts.
- src/platform/nrf54l15/NRF54L15Bluetooth.cpp: clamp NO_PIN to RANDOM_PIN
with a one-shot LOG_WARN. The mesh GATT permissions are declared with
BT_GATT_PERM_*_AUTHEN and prj.conf sets CONFIG_BT_SMP_ENFORCE_MITM=y, so
NO_PIN with no auth callbacks would leave every characteristic returning
BT_ATT_ERR_AUTHENTICATION. Falling back to RANDOM_PIN keeps the link
usable instead of silently broken. Also re-formatted this file with the
project's .trunk/configs/.clang-format (Linux braces, 4-space indent,
130-col) — the previous lint-fix commit a2aca3234 accidentally used the
default LLVM style here, which CI's clang-format would have rejected.
Build verified: pio run -e nrf54l15dk passes, RAM 47.4%, Flash 28.6%.
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
* fix(nrf54l15): address remaining Copilot review threads
Round 2/3 review fixes — bugs first, then docs/portability:
BLE concurrency (NRF54L15Bluetooth.cpp):
- onNowHasData / sendLog / BleDeferredThread / shutdown: acquire
active_conn under ble_mutex via new acquire_active_conn() helper so
disconnected_cb can't free the conn between the null check and
bt_conn_ref/bt_gatt_notify (use-after-unref).
- write_toradio: reject writes that exceed MAX_TO_FROM_RADIO_SIZE with
ATT_ERR_INVALID_ATTRIBUTE_LEN instead of returning success and silently
dropping the payload (would hide failed config writes from the phone).
- start_advertising: truncate the device name to fit the 31-byte legacy
scan-response limit and switch to BT_DATA_NAME_SHORTENED so
bt_le_adv_start() doesn't reject the payload when the name approaches
CONFIG_BT_DEVICE_NAME_MAX=32.
Linker / portability:
- main.h: drop the rp2040Loop() forward declaration that had no
definition and no callers — would surface as a link error if any RP2040
build added a call to the symbol.
- nrf54l15_arduino.cpp: transfer16() now uses static __aligned(4) DMA
buffers (matching transfer()), removing the EasyDMA-reachability hazard
of caller-stack buffers on this part.
Filesystem (InternalFileSystem.h):
- usedBytes(): return real usage from fs_statvfs() instead of 0 so OTA
/ range-test free-space guards work.
- rewindDirectory(): close the dir before reopening — Zephyr fs_dir_t has
no rewind, and re-fs_opendir on an open handle leaks LittleFS state.
Crash handler (nrf54l15_main.cpp):
- After the stack walk, busy-wait 50 ms to flush RTT/printk and call
sys_reboot(SYS_REBOOT_COLD) directly so the saved_crash record is
actually reported on the next boot. Default Zephyr config has
RESET_ON_FATAL_ERROR=n, so the previous k_fatal_halt() spun forever.
Generalization / config:
- PhoneAPI.cpp: replace the NRF54L15_DK ifdef with a
MESHTASTIC_EXCLUDE_FILES_MANIFEST capability flag (defined in the
nrf54l15dk env) so future variants can opt in/out without touching
shared code.
- variants/nrf54l15/nrf54l15.ini: parameterize libdeps include paths via
${PIOENV} so additional nRF54L15 envs sharing nrf54l15_base don't break.
- prj.conf: drop the stale "36 KB storage_partition" comments — the DK
overlay reclaims slot1 to ~700 KB and runtime size comes from
FIXED_PARTITION_SIZE.
- nrf54l15dk overlay: remove the zephyr,console / zephyr,shell-uart
chosen entries that conflicted with CONFIG_UART_CONSOLE=n + RTT
console; keep uart30 enabled so swapping the console is one Kconfig
flip away.
Build: nrf54l15dk SUCCESS (flash 28.6%, RAM 47.4%); wiznet_5500_evb_pico2
SUCCESS (verifies the shared main.h change).
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
* fix(nrf54l15dk): use PRIVATE_HW (255) for custom_meshtastic_hw_model
Per @thebentern's review: the nRF54L15-DK is a development kit, not a
canonical Meshtastic SKU, so it falls under HardwareModel::PRIVATE_HW
(255) — the same enum value already used at runtime via HW_VENDOR. The
placeholder 132 is removed; no dedicated enum number will be assigned
for DK boards. Slug stays NRF54L15_DK as a human-readable identifier.
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
* fix(nrf54l15): unstarve bt_long_wq so SC pairing completes
bt_pub_key_gen() runs the ECC P256 key generation on bt_long_wq. At default
prio=10 (preemptible) and stack=1400 it gets starved by Meshtastic app
threads at boot — sc_public_key stays NULL for minutes, smp_public_key()
defers with SMP_FLAG_PKEY_SEND, and every SC pairing attempt stalls right
after the public-key exchange. iOS shows "Connecting…" forever with no
PIN prompt; bleak/CLI fails the first CCC notify write with
"Protocol Error 0x05: Insufficient Authentication".
Set CONFIG_BT_LONG_WQ_PRIO=0 (highest preemptible, ties with main) and
CONFIG_BT_LONG_WQ_STACK_SIZE=4096 (margin for the P256M driver frames).
Validated E2E with iOS Meshtastic app: bt_smp_pkey_ready fires within ~40 s
of boot, 20 SC Passkey Entry rounds complete with matching pcnf/cfm,
encrypt 0x01 / sec_level 0x04 (Authenticated MITM), bonded=1.
* feat(nrf54l15): hardware I2C bus via TWIM30 + sensor telemetry
Adds the Arduino TwoWire layer for the nRF54L15-DK so Meshtastic's
sensor drivers can talk to external I2C devices over the hardware
TWIM30 peripheral.
Bus binding:
- &uart30 disabled in the board overlay (peripheral instance 30 is
shared between UARTE30 / TWIM30 / SPIM30 — pick one). Console stays
on RTT via CONFIG_RTT_CONSOLE.
- New i2c30_default / i2c30_sleep pinctrl with SDA=P0.03 / SCL=P0.04.
External 4.7 kOhm pull-ups required on both lines.
- &i2c30 enabled at I2C_BITRATE_FAST (400 kHz).
- button_3 (SW3, P0.04) deleted from DTS so the pad can be claimed by
i2c30 pinctrl; SW3 is still wired to the pad on the DK, do not press
it during I2C use or it will short SCL to GND.
Arduino layer:
- src/platform/nrf54l15/Wire.cpp resolves the DT node at compile time
via DEVICE_DT_GET(DT_NODELABEL(i2c30)) and dispatches Arduino's
beginTransmission / write / endTransmission / requestFrom to
i2c_write / i2c_write_read / i2c_read. Buffer is sized to 256 bytes
for forward compatibility with the SE050 secure element on the
custom PCB.
- Wire.h drops the prior compile-only stubs and exposes the real
TwoWire surface.
- Arduino.h: BitOrder becomes an enum (not #define) so Adafruit_BusIO's
`typedef BitOrder BusIOBitOrder;` compiles.
Variant + build flags:
- nrf54l15.ini flips HAS_WIRE / HAS_SENSOR / HAS_TELEMETRY from 0 to 1
and cherry-picks the sensor libs Meshtastic needs (BusIO, Sensor,
BMP280, BME280, INA219/226/260/3221, SHT4X). The full
environmental_base group is avoided because it pulls
Adafruit_SSD1306 / Adafruit_GFX which rely on Arduino pin macros the
Zephyr shim does not implement.
- nrf54l15dk variant.h defines PIN_WIRE_SDA / PIN_WIRE_SCL for parity
with the Arduino convention used by other variants. The actual bus
wiring is fixed by the overlay pinctrl above.
Validated 2026-05-14/15 on the DK with BMP280 @ 0x76 (temperature +
barometric pressure) and INA3221 @ 0x42 (rail voltage / current);
EnvironmentTelemetry / PowerTelemetry packets transmit successfully
over LoRa.
Footprint cost on nrf54l15dk: +45 KB flash, +1.7 KB RAM.
* feat(nodedb): honor USERPREFS for environment telemetry on first boot
installDefaultConfig() now respects two new compile-time prefs:
USERPREFS_CONFIG_ENV_TELEM_UPDATE_INTERVAL
USERPREFS_CONFIG_ENVIRONMENT_MEASUREMENT_ENABLED
The mobile apps enforce a 30 min floor on environment_update_interval
in the settings UI, which makes short-interval bring-up testing of new
sensor hardware painful — you have to wait half an hour for the first
LoRa packet to confirm wiring + driver. With these prefs baked into
the variant, the firmware can ship a freshly-flashed device that
broadcasts on a shorter cadence (e.g. 900 s) the moment storage_partition
is empty.
Both prefs are gated on #ifdef so the behavior is unchanged for any
variant that does not opt in. Documented in userPrefs.jsonc with the
existing telemetry-interval pref block.
* fix(nrf54l15): allow multiple bonded BLE peers
CONFIG_BT_MAX_PAIRED defaults to 1, so once the first peer (e.g. an
iOS phone) has paired and bonded, every subsequent pairing attempt
from a different MAC fails inside bt_keys_get_addr() with no free
key slot — the host returns BT_SECURITY_ERR_KEY_DOES_NOT_EXIST and
the second peer never gets past SMP.
Raise the slot count to 4 so the device can simultaneously hold an
iOS phone, a Windows host, a Linux host, and one spare bond. Add
BT_KEYS_OVERWRITE_OLDEST so that once the table fills, the LRU peer
is evicted on the next pairing rather than rejecting the new peer.
This matches the behavior other Meshtastic ports already provide
(nRF52 uses CONFIG_BT_PERIPHERAL_PRIO_CONN with similar semantics).
Discovered while bringing up the Python CLI on Windows alongside
the existing iOS bond.
* fix(nrf54l15): zero-initialize TwoWire buffers + clang-format Wire
cppcheck on every CI target (esp32s3, rp2040, rp2350, nrf52840, ...) was
failing the build with two `uninitMemberVar` warnings on TwoWire's
constructor: `txBuf` and `rxBuf` (256-byte arrays) were not initialized.
Even though the buffers are only read after txLen/rxLen is set, leaving
them uninitialized is a footgun if any future caller bypasses the
len-set step. Use C++11 value-initialization in the member initializer
list — costs ~512 B of memset at boot, gains a clean cppcheck pass and
defensive-against-future-changes semantics.
Also reformat Wire.{cpp,h} with the project's `.trunk/configs/.clang-format`
config so the Trunk Check Runner passes — clang-format moved the
`<errno.h>` include before the Zephyr-namespaced ones in Wire.cpp and
collapsed two inline overloads to single lines in Wire.h.
* fix(AdminModule): remove dead OUTPUT_GPIO_PIN/GpioOutputModule references
OUTPUT_GPIO_PIN is never defined and modules/GpioOutputModule.h doesn't
exist in the codebase; all #ifdef OUTPUT_GPIO_PIN branches were dead code
introduced by the nRF54L15-DK variant commit. Strips the include, the
output_gpio_enabled OFF→ON/ON→OFF transition logic in handleSetConfig(),
and the digitalRead() reflection in handleGetConfig().
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
---------
Co-authored-by: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
Co-authored-by: Ben Meadors <benmmeadors@gmail.com>
This commit is contained in:
4
.gitignore
vendored
4
.gitignore
vendored
@@ -47,6 +47,10 @@ data/boot/logo.*
|
||||
managed_components/*
|
||||
arduino-lib-builder*
|
||||
dependencies.lock
|
||||
|
||||
# JLink / RTT debug artifacts (nRF SoCs)
|
||||
flash.jlink
|
||||
rtt_*.txt
|
||||
idf_component.yml
|
||||
CMakeLists.txt
|
||||
/sdkconfig.*
|
||||
|
||||
26
boards/nrf54l15dk.json
Normal file
26
boards/nrf54l15dk.json
Normal file
@@ -0,0 +1,26 @@
|
||||
{
|
||||
"build": {
|
||||
"cpu": "cortex-m33",
|
||||
"f_cpu": "128000000L",
|
||||
"mcu": "nrf54l15",
|
||||
"zephyr": {
|
||||
"variant": "nrf54l15dk/nrf54l15/cpuapp"
|
||||
}
|
||||
},
|
||||
"connectivity": ["bluetooth"],
|
||||
"debug": {
|
||||
"default_tools": ["jlink"],
|
||||
"jlink_device": "nRF54L15_M33",
|
||||
"svd_path": "nrf54l15.svd"
|
||||
},
|
||||
"frameworks": ["zephyr"],
|
||||
"name": "Nordic nRF54L15-DK (PCA10156)",
|
||||
"upload": {
|
||||
"maximum_ram_size": 262144,
|
||||
"maximum_size": 1572864,
|
||||
"protocol": "jlink",
|
||||
"protocols": ["jlink"]
|
||||
},
|
||||
"url": "https://www.nordicsemi.com/Products/nRF54L15",
|
||||
"vendor": "Nordic Semiconductor"
|
||||
}
|
||||
140
extra_scripts/nrf54l15_linker.py
Normal file
140
extra_scripts/nrf54l15_linker.py
Normal file
@@ -0,0 +1,140 @@
|
||||
#!/usr/bin/env python3
|
||||
# trunk-ignore-all(ruff/F821)
|
||||
# trunk-ignore-all(flake8/F821): For SConstruct imports
|
||||
#
|
||||
# post:extra_scripts/nrf54l15_linker.py
|
||||
#
|
||||
# Fix for Zephyr two-pass link on nRF54L15:
|
||||
# platformio-build.py registers env.Depends("$PROG_PATH", final_ld_script) but
|
||||
# the SCons dependency chain is broken (final_ld_script Command never runs).
|
||||
# This script adds a PreAction on the final firmware binary that runs the gcc
|
||||
# preprocessing command directly (extracted from build.ninja) to generate
|
||||
# zephyr/linker.cmd before the link step.
|
||||
#
|
||||
# PlatformIO bundles an old Ninja that can't handle multi-output depslog rules,
|
||||
# so we parse the COMMAND line from build.ninja and run just the gcc -E part,
|
||||
# skipping the cmake_transform_depfile step (only needed for Ninja deps tracking).
|
||||
|
||||
import os
|
||||
import re
|
||||
import subprocess
|
||||
|
||||
Import("env")
|
||||
|
||||
if env.get("PIOENV") != "nrf54l15dk":
|
||||
pass # Only for the nrf54l15dk environment
|
||||
else:
|
||||
|
||||
def _extract_gcc_command(ninja_build):
|
||||
"""Parse build.ninja to find the gcc -E command that generates linker.cmd.
|
||||
|
||||
The rule format depends on the host:
|
||||
Windows (CMake's RunCMake wraps every command):
|
||||
COMMAND = cmd.exe /C "cd /D DIR && arm-none-eabi-gcc.exe ... -o linker.cmd && cmake.exe -E cmake_transform_depfile ..."
|
||||
POSIX (Linux/macOS — no wrapper):
|
||||
COMMAND = cd DIR && arm-none-eabi-gcc ... -o linker.cmd && cmake -E cmake_transform_depfile ...
|
||||
|
||||
Returns (gcc_cmd_string, cwd_path) or raises RuntimeError.
|
||||
"""
|
||||
in_rule = False
|
||||
with open(ninja_build, "r", encoding="utf-8", errors="replace") as f:
|
||||
for line in f:
|
||||
# Detect start of the linker.cmd custom command rule
|
||||
if not in_rule:
|
||||
if "build zephyr/linker.cmd" in line and "CUSTOM_COMMAND" in line:
|
||||
in_rule = True
|
||||
continue
|
||||
|
||||
stripped = line.strip()
|
||||
if not stripped.startswith("COMMAND = "):
|
||||
continue
|
||||
|
||||
command_val = stripped[len("COMMAND = ") :]
|
||||
|
||||
# On Windows the value is wrapped in `cmd.exe /C "..."` — strip
|
||||
# the wrapper. On POSIX hosts the inner sequence is the value
|
||||
# itself (no quoting layer).
|
||||
m = re.search(r'/C\s+"(.*)"\s*$', command_val)
|
||||
inner = m.group(1) if m else command_val
|
||||
parts = inner.split(" && ")
|
||||
|
||||
cwd = None
|
||||
gcc_cmd = None
|
||||
for part in parts:
|
||||
part = part.strip()
|
||||
if part.startswith("cd /D "): # Windows form
|
||||
cwd = part[len("cd /D ") :]
|
||||
elif part.startswith("cd "): # POSIX form
|
||||
cwd = part[len("cd ") :]
|
||||
elif "arm-none-eabi-gcc" in part:
|
||||
gcc_cmd = part
|
||||
|
||||
if not gcc_cmd:
|
||||
raise RuntimeError(
|
||||
"nRF54L15 linker fix: arm-none-eabi-gcc command not found in:\n%s"
|
||||
% inner[:400]
|
||||
)
|
||||
|
||||
return gcc_cmd, cwd
|
||||
|
||||
raise RuntimeError(
|
||||
"nRF54L15 linker fix: 'build zephyr/linker.cmd' rule not found in build.ninja"
|
||||
)
|
||||
|
||||
def _generate_linker_cmd(target, source, env):
|
||||
"""Generate zephyr/linker.cmd via direct gcc invocation before the final link."""
|
||||
build_dir = env.subst("$BUILD_DIR")
|
||||
zephyr_dir = os.path.join(build_dir, "zephyr")
|
||||
linker_cmd = os.path.join(zephyr_dir, "linker.cmd")
|
||||
|
||||
if os.path.exists(linker_cmd):
|
||||
return # Already present — nothing to do
|
||||
|
||||
ninja_build = os.path.join(build_dir, "build.ninja")
|
||||
if not os.path.exists(ninja_build):
|
||||
raise RuntimeError(
|
||||
"nRF54L15 linker fix: build.ninja not found at %s\n"
|
||||
"Run a full build first so CMake generates the Ninja files."
|
||||
% ninja_build
|
||||
)
|
||||
|
||||
gcc_cmd, cwd = _extract_gcc_command(ninja_build)
|
||||
run_cwd = cwd if cwd else zephyr_dir
|
||||
|
||||
print(
|
||||
"==> nRF54L15: Generating zephyr/linker.cmd (LINKER_ZEPHYR_FINAL) via GCC"
|
||||
)
|
||||
# gcc_cmd comes verbatim from our own build.ninja (never user input) and
|
||||
# contains Windows-style paths with spaces that cannot be safely argv-split
|
||||
# with shlex, so we run it via the platform shell. nosec/nosemgrep below
|
||||
# acknowledge this deliberate, scoped use of shell=True.
|
||||
result = subprocess.run( # nosec B602
|
||||
gcc_cmd,
|
||||
shell=True, # nosemgrep: python.lang.security.audit.subprocess-shell-true.subprocess-shell-true
|
||||
cwd=run_cwd,
|
||||
capture_output=True,
|
||||
text=True,
|
||||
)
|
||||
if result.returncode != 0:
|
||||
print("GCC stdout:", result.stdout[:2000])
|
||||
print("GCC stderr:", result.stderr[:2000])
|
||||
raise RuntimeError(
|
||||
"nRF54L15 linker fix: GCC failed to generate linker.cmd (rc=%d)"
|
||||
% result.returncode
|
||||
)
|
||||
if not os.path.exists(linker_cmd):
|
||||
raise RuntimeError(
|
||||
"nRF54L15 linker fix: GCC returned 0 but linker.cmd was not created at %s"
|
||||
% linker_cmd
|
||||
)
|
||||
print("==> linker.cmd generated successfully")
|
||||
|
||||
# Use PIOMAINPROG (set by ZephyrBuildProgram) to get the exact SCons node
|
||||
prog = env.get("PIOMAINPROG")
|
||||
if prog:
|
||||
env.AddPreAction(prog, _generate_linker_cmd)
|
||||
else:
|
||||
print(
|
||||
"[nrf54l15_linker] WARNING: PIOMAINPROG not set, falling back to $PROG_PATH"
|
||||
)
|
||||
env.AddPreAction(env.subst("$PROG_PATH"), _generate_linker_cmd)
|
||||
@@ -17,6 +17,7 @@ test_build_src = true
|
||||
extra_scripts =
|
||||
pre:bin/platformio-pre.py
|
||||
bin/platformio-custom.py
|
||||
post:extra_scripts/nrf54l15_linker.py
|
||||
; note: we add src to our include search path so that lmic_project_config can override
|
||||
; note: TINYGPS_OPTION_NO_CUSTOM_FIELDS is VERY important. We don't use custom fields and somewhere in that pile
|
||||
; of code is a heap corruption bug!
|
||||
|
||||
@@ -48,6 +48,14 @@ using namespace STM32_LittleFS_Namespace;
|
||||
using namespace Adafruit_LittleFS_Namespace;
|
||||
#endif
|
||||
|
||||
#if defined(ARCH_NRF54L15)
|
||||
// nRF54L15 — Zephyr LittleFS on 36 KB storage_partition (internal RRAM)
|
||||
#include "InternalFileSystem.h"
|
||||
#define FSCom InternalFS
|
||||
#define FSBegin() FSCom.begin()
|
||||
using namespace Adafruit_LittleFS_Namespace;
|
||||
#endif
|
||||
|
||||
void fsInit();
|
||||
void fsListFiles();
|
||||
bool copyFile(const char *from, const char *to);
|
||||
|
||||
@@ -225,6 +225,8 @@ void RedirectablePrint::log_to_ble(const char *logLevel, const char *format, va_
|
||||
isBleConnected = nimbleBluetooth && nimbleBluetooth->isActive() && nimbleBluetooth->isConnected();
|
||||
#elif defined(ARCH_NRF52)
|
||||
isBleConnected = nrf52Bluetooth != nullptr && nrf52Bluetooth->isConnected();
|
||||
#elif defined(ARCH_NRF54L15)
|
||||
isBleConnected = nrf54l15Bluetooth != nullptr && nrf54l15Bluetooth->isConnected();
|
||||
#endif
|
||||
if (isBleConnected) {
|
||||
auto thread = concurrency::OSThread::currentThread;
|
||||
@@ -241,6 +243,8 @@ void RedirectablePrint::log_to_ble(const char *logLevel, const char *format, va_
|
||||
nimbleBluetooth->sendLog(buffer.get(), size);
|
||||
#elif defined(ARCH_NRF52)
|
||||
nrf52Bluetooth->sendLog(buffer.get(), size);
|
||||
#elif defined(ARCH_NRF54L15)
|
||||
nrf54l15Bluetooth->sendLog(buffer.get(), size);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
15
src/main.cpp
15
src/main.cpp
@@ -2,6 +2,9 @@
|
||||
#if !MESHTASTIC_EXCLUDE_GPS
|
||||
#include "GPS.h"
|
||||
#endif
|
||||
#if !MESHTASTIC_EXCLUDE_INPUTBROKER
|
||||
#include "input/InputBroker.h"
|
||||
#endif
|
||||
#include "MeshRadio.h"
|
||||
#include "MeshService.h"
|
||||
#include "NodeDB.h"
|
||||
@@ -59,6 +62,12 @@ NimbleBluetooth *nimbleBluetooth = nullptr;
|
||||
NRF52Bluetooth *nrf52Bluetooth = nullptr;
|
||||
#endif
|
||||
|
||||
#ifdef ARCH_NRF54L15
|
||||
void nrf54l15Setup();
|
||||
void nrf54l15Loop();
|
||||
NRF54L15Bluetooth *nrf54l15Bluetooth = nullptr;
|
||||
#endif
|
||||
|
||||
#if HAS_WIFI || defined(USE_WS5500) || defined(USE_CH390D)
|
||||
#include "mesh/api/WiFiServerAPI.h"
|
||||
#include "mesh/wifi/WiFiAPClient.h"
|
||||
@@ -696,6 +705,9 @@ void setup()
|
||||
#ifdef ARCH_NRF52
|
||||
nrf52Setup();
|
||||
#endif
|
||||
#ifdef ARCH_NRF54L15
|
||||
nrf54l15Setup();
|
||||
#endif
|
||||
|
||||
#ifdef ARCH_RP2040
|
||||
rp2040Setup();
|
||||
@@ -1126,6 +1138,9 @@ void loop()
|
||||
#endif
|
||||
#ifdef ARCH_NRF52
|
||||
nrf52Loop();
|
||||
#endif
|
||||
#ifdef ARCH_NRF54L15
|
||||
nrf54l15Loop();
|
||||
#endif
|
||||
power->powerCommandsCheck();
|
||||
|
||||
|
||||
@@ -19,6 +19,10 @@ extern NimbleBluetooth *nimbleBluetooth;
|
||||
#include "NRF52Bluetooth.h"
|
||||
extern NRF52Bluetooth *nrf52Bluetooth;
|
||||
#endif
|
||||
#ifdef ARCH_NRF54L15
|
||||
#include "NRF54L15Bluetooth.h"
|
||||
extern NRF54L15Bluetooth *nrf54l15Bluetooth;
|
||||
#endif
|
||||
#if !MESHTASTIC_EXCLUDE_I2C
|
||||
#include "detect/ScanI2CTwoWire.h"
|
||||
#endif
|
||||
|
||||
@@ -93,6 +93,23 @@ void Channels::initDefaultLoraConfig()
|
||||
#ifdef USERPREFS_LORACONFIG_CHANNEL_NUM
|
||||
loraConfig.channel_num = USERPREFS_LORACONFIG_CHANNEL_NUM;
|
||||
#endif
|
||||
|
||||
// Apply any hardcoded USERPREFS overrides for custom modem config (e.g. region-locked boards)
|
||||
#ifdef USERPREFS_LORACONFIG_USE_PRESET
|
||||
loraConfig.use_preset = USERPREFS_LORACONFIG_USE_PRESET;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_BANDWIDTH
|
||||
loraConfig.bandwidth = USERPREFS_LORACONFIG_BANDWIDTH;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_SPREAD_FACTOR
|
||||
loraConfig.spread_factor = USERPREFS_LORACONFIG_SPREAD_FACTOR;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_CODING_RATE
|
||||
loraConfig.coding_rate = USERPREFS_LORACONFIG_CODING_RATE;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_OVERRIDE_FREQUENCY
|
||||
loraConfig.override_frequency = USERPREFS_LORACONFIG_OVERRIDE_FREQUENCY;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool Channels::ensureLicensedOperation()
|
||||
|
||||
@@ -334,7 +334,9 @@ void MeshService::sendToPhone(meshtastic_MeshPacket *p)
|
||||
|
||||
if (toPhoneQueue.enqueue(p, 0) == false) {
|
||||
LOG_CRIT("Failed to queue a packet into toPhoneQueue!");
|
||||
abort();
|
||||
releaseToPool(p);
|
||||
fromNum++; // notify observers so phone can resync
|
||||
return;
|
||||
}
|
||||
fromNum++;
|
||||
}
|
||||
@@ -351,7 +353,8 @@ void MeshService::sendMqttMessageToClientProxy(meshtastic_MqttClientProxyMessage
|
||||
|
||||
if (toPhoneMqttProxyQueue.enqueue(m, 0) == false) {
|
||||
LOG_CRIT("Failed to queue a packet into toPhoneMqttProxyQueue!");
|
||||
abort();
|
||||
releaseMqttClientProxyMessageToPool(m);
|
||||
return;
|
||||
}
|
||||
fromNum++;
|
||||
}
|
||||
@@ -383,7 +386,8 @@ void MeshService::sendClientNotification(meshtastic_ClientNotification *n)
|
||||
|
||||
if (toPhoneClientNotificationQueue.enqueue(n, 0) == false) {
|
||||
LOG_CRIT("Failed to queue a notification into toPhoneClientNotificationQueue!");
|
||||
abort();
|
||||
releaseClientNotificationToPool(n);
|
||||
return;
|
||||
}
|
||||
fromNum++;
|
||||
}
|
||||
|
||||
@@ -393,6 +393,13 @@ NodeDB::NodeDB()
|
||||
} else {
|
||||
LOG_WARN("Failed to read unique id from efuse");
|
||||
}
|
||||
#elif defined(ARCH_NRF54L15)
|
||||
// nRF54L15: DEVICEID is under FICR->INFO sub-struct (not top-level as on nRF52)
|
||||
uint64_t device_id_start = ((uint64_t)NRF_FICR->INFO.DEVICEID[1] << 32) | NRF_FICR->INFO.DEVICEID[0];
|
||||
uint64_t device_id_end = ((uint64_t)NRF_FICR->DEVICEADDR[1] << 32) | NRF_FICR->DEVICEADDR[0];
|
||||
memcpy(myNodeInfo.device_id.bytes, &device_id_start, sizeof(device_id_start));
|
||||
memcpy(myNodeInfo.device_id.bytes + sizeof(device_id_start), &device_id_end, sizeof(device_id_end));
|
||||
myNodeInfo.device_id.size = 16;
|
||||
#elif defined(ARCH_NRF52)
|
||||
// Nordic applies a FIPS compliant Random ID to each chip at the factory
|
||||
// We concatenate the device address to the Random ID to create a unique ID for now
|
||||
@@ -826,6 +833,23 @@ void NodeDB::installDefaultConfig(bool preserveKey = false)
|
||||
config.lora.modem_preset = USERPREFS_LORACONFIG_MODEM_PRESET;
|
||||
#else
|
||||
config.lora.modem_preset = meshtastic_Config_LoRaConfig_ModemPreset_LONG_FAST;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_USE_PRESET
|
||||
config.lora.use_preset = USERPREFS_LORACONFIG_USE_PRESET;
|
||||
#else
|
||||
config.lora.use_preset = true;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_BANDWIDTH
|
||||
config.lora.bandwidth = USERPREFS_LORACONFIG_BANDWIDTH;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_SPREAD_FACTOR
|
||||
config.lora.spread_factor = USERPREFS_LORACONFIG_SPREAD_FACTOR;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_CODING_RATE
|
||||
config.lora.coding_rate = USERPREFS_LORACONFIG_CODING_RATE;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_OVERRIDE_FREQUENCY
|
||||
config.lora.override_frequency = USERPREFS_LORACONFIG_OVERRIDE_FREQUENCY;
|
||||
#endif
|
||||
config.lora.hop_limit = HOP_RELIABLE;
|
||||
#ifdef USERPREFS_CONFIG_LORA_IGNORE_MQTT
|
||||
@@ -1217,7 +1241,14 @@ void NodeDB::initModuleConfigIntervals()
|
||||
#else
|
||||
moduleConfig.telemetry.device_update_interval = MAX_INTERVAL;
|
||||
#endif
|
||||
#ifdef USERPREFS_CONFIG_ENV_TELEM_UPDATE_INTERVAL
|
||||
moduleConfig.telemetry.environment_update_interval = USERPREFS_CONFIG_ENV_TELEM_UPDATE_INTERVAL;
|
||||
#else
|
||||
moduleConfig.telemetry.environment_update_interval = 0;
|
||||
#endif
|
||||
#ifdef USERPREFS_CONFIG_ENVIRONMENT_MEASUREMENT_ENABLED
|
||||
moduleConfig.telemetry.environment_measurement_enabled = USERPREFS_CONFIG_ENVIRONMENT_MEASUREMENT_ENABLED;
|
||||
#endif
|
||||
moduleConfig.telemetry.air_quality_interval = 0;
|
||||
moduleConfig.telemetry.power_update_interval = 0;
|
||||
moduleConfig.telemetry.health_update_interval = 0;
|
||||
@@ -1726,6 +1757,28 @@ void NodeDB::loadFromDisk()
|
||||
config.lora.tx_enabled = false;
|
||||
#endif
|
||||
|
||||
// Always-apply LoRa overrides: applied after loading saved config so they
|
||||
// take effect even when NVS already has a valid config (e.g. region-locked
|
||||
// dev boards with no BLE/serial to set the region at runtime).
|
||||
#ifdef USERPREFS_CONFIG_LORA_REGION
|
||||
config.lora.region = USERPREFS_CONFIG_LORA_REGION;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_USE_PRESET
|
||||
config.lora.use_preset = USERPREFS_LORACONFIG_USE_PRESET;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_BANDWIDTH
|
||||
config.lora.bandwidth = USERPREFS_LORACONFIG_BANDWIDTH;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_SPREAD_FACTOR
|
||||
config.lora.spread_factor = USERPREFS_LORACONFIG_SPREAD_FACTOR;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_CODING_RATE
|
||||
config.lora.coding_rate = USERPREFS_LORACONFIG_CODING_RATE;
|
||||
#endif
|
||||
#ifdef USERPREFS_LORACONFIG_OVERRIDE_FREQUENCY
|
||||
config.lora.override_frequency = USERPREFS_LORACONFIG_OVERRIDE_FREQUENCY;
|
||||
#endif
|
||||
|
||||
if (backupSecurity.private_key.size > 0) {
|
||||
LOG_DEBUG("Restoring backup of security config");
|
||||
config.security = backupSecurity;
|
||||
|
||||
@@ -71,7 +71,15 @@ void PhoneAPI::handleStartConfig()
|
||||
}
|
||||
pauseBluetoothLogging = true;
|
||||
spiLock->lock();
|
||||
#if defined(MESHTASTIC_EXCLUDE_FILES_MANIFEST)
|
||||
// Skip the recursive FS walk. Used by platforms whose Zephyr LittleFS
|
||||
// backend can't safely traverse a deep tree (e.g. nRF54L15) and platforms
|
||||
// that don't support OTA browsing — the manifest is only consumed by
|
||||
// companion apps for those flows.
|
||||
filesManifest.clear();
|
||||
#else
|
||||
filesManifest = getFiles("/", 10);
|
||||
#endif
|
||||
spiLock->unlock();
|
||||
LOG_DEBUG("Got %d files in manifest", filesManifest.size());
|
||||
|
||||
|
||||
@@ -46,16 +46,6 @@ RadioLibInterface::RadioLibInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE c
|
||||
#endif
|
||||
}
|
||||
|
||||
RadioLibInterface::~RadioLibInterface()
|
||||
{
|
||||
// If the static `instance` pointer still references us, clear it.
|
||||
// A later successful init() may have replaced `instance` with a newer
|
||||
// interface — don't clobber that case.
|
||||
if (instance == this) {
|
||||
instance = nullptr;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef ARCH_ESP32
|
||||
// ESP32 doesn't use that flag
|
||||
#define YIELD_FROM_ISR(x) portYIELD_FROM_ISR()
|
||||
@@ -555,6 +545,9 @@ void RadioLibInterface::pollMissedIrqs()
|
||||
if (isReceiving) {
|
||||
checkRxDoneIrqFlag();
|
||||
}
|
||||
if (sendingPacket) {
|
||||
checkTxDoneIrqFlag();
|
||||
}
|
||||
}
|
||||
|
||||
void RadioLibInterface::resetAGC()
|
||||
@@ -570,6 +563,14 @@ void RadioLibInterface::checkRxDoneIrqFlag()
|
||||
}
|
||||
}
|
||||
|
||||
void RadioLibInterface::checkTxDoneIrqFlag()
|
||||
{
|
||||
if (iface->checkIrq(RADIOLIB_IRQ_TX_DONE)) {
|
||||
LOG_WARN("caught missed TX_DONE");
|
||||
notify(ISR_TX, true);
|
||||
}
|
||||
}
|
||||
|
||||
void RadioLibInterface::configHardwareForSend()
|
||||
{
|
||||
powerMon->setState(meshtastic_PowerMon_State_Lora_TXOn);
|
||||
|
||||
@@ -104,6 +104,13 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
|
||||
*/
|
||||
static RadioLibInterface *instance;
|
||||
|
||||
/** Clear instance on destruction so stale pointer checks in loop() are safe */
|
||||
virtual ~RadioLibInterface()
|
||||
{
|
||||
if (instance == this)
|
||||
instance = nullptr;
|
||||
}
|
||||
|
||||
/**
|
||||
* Glue functions called from ISR land
|
||||
*/
|
||||
@@ -136,13 +143,6 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
|
||||
RadioLibInterface(LockingArduinoHal *hal, RADIOLIB_PIN_TYPE cs, RADIOLIB_PIN_TYPE irq, RADIOLIB_PIN_TYPE rst,
|
||||
RADIOLIB_PIN_TYPE busy, PhysicalLayer *iface = NULL);
|
||||
|
||||
/**
|
||||
* Clear the static `instance` pointer if it still points at us, so callers
|
||||
* that check `RadioLibInterface::instance != nullptr` don't dereference a
|
||||
* freed object after a failed init() + unique_ptr reset.
|
||||
*/
|
||||
virtual ~RadioLibInterface();
|
||||
|
||||
virtual ErrorCode send(meshtastic_MeshPacket *p) override;
|
||||
|
||||
/**
|
||||
@@ -293,4 +293,5 @@ class RadioLibInterface : public RadioInterface, protected concurrency::Notified
|
||||
bool removePendingTXPacket(NodeNum from, PacketId id, uint32_t hop_limit_lt) override;
|
||||
|
||||
void checkRxDoneIrqFlag();
|
||||
void checkTxDoneIrqFlag();
|
||||
};
|
||||
|
||||
@@ -666,7 +666,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c, bool fromOthers)
|
||||
bool requiresReboot = true;
|
||||
|
||||
switch (c.which_payload_variant) {
|
||||
case meshtastic_Config_device_tag:
|
||||
case meshtastic_Config_device_tag: {
|
||||
LOG_INFO("Set config: Device");
|
||||
config.has_device = true;
|
||||
#if !defined(ARCH_PORTDUINO) && !defined(ARCH_STM32WL) && !MESHTASTIC_EXCLUDE_ENVIRONMENTAL_SENSOR && \
|
||||
@@ -720,6 +720,7 @@ void AdminModule::handleSetConfig(const meshtastic_Config &c, bool fromOthers)
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
} // case meshtastic_Config_device_tag
|
||||
case meshtastic_Config_position_tag:
|
||||
LOG_INFO("Set config: Position");
|
||||
config.has_position = true;
|
||||
@@ -1345,6 +1346,10 @@ void AdminModule::handleGetDeviceConnectionStatus(const meshtastic_MeshPacket &r
|
||||
if (config.bluetooth.enabled && nrf52Bluetooth) {
|
||||
conn.bluetooth.is_connected = nrf52Bluetooth->isConnected();
|
||||
}
|
||||
#elif defined(ARCH_NRF54L15)
|
||||
if (config.bluetooth.enabled && nrf54l15Bluetooth) {
|
||||
conn.bluetooth.is_connected = nrf54l15Bluetooth->isConnected();
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
conn.has_serial = true; // No serial-less devices
|
||||
@@ -1605,6 +1610,9 @@ void disableBluetooth()
|
||||
#elif defined(ARCH_NRF52)
|
||||
if (nrf52Bluetooth)
|
||||
nrf52Bluetooth->shutdown();
|
||||
#elif defined(ARCH_NRF54L15)
|
||||
if (nrf54l15Bluetooth)
|
||||
nrf54l15Bluetooth->shutdown();
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
824
src/platform/nrf54l15/Arduino.h
Normal file
824
src/platform/nrf54l15/Arduino.h
Normal file
@@ -0,0 +1,824 @@
|
||||
/**
|
||||
* Arduino.h — Zephyr compatibility shim for nRF54L15
|
||||
*
|
||||
* Provides the Arduino API surface expected by Meshtastic, backed by
|
||||
* Zephyr primitives. Only the subset actually used by Meshtastic is
|
||||
* implemented; the rest compiles as no-ops / stubs for now.
|
||||
*
|
||||
* Phase 2: compile only. Real GPIO / SPI / Wire implementations follow
|
||||
* in Phase 3 once the build is clean.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
#ifndef Arduino_h
|
||||
#define Arduino_h
|
||||
|
||||
// ── C standard headers ───────────────────────────────────────────────────────
|
||||
#include <math.h>
|
||||
#include <stdbool.h>
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <strings.h> /* strcasecmp, strncasecmp */
|
||||
|
||||
// ── Zephyr kernel ────────────────────────────────────────────────────────────
|
||||
#include <zephyr/kernel.h>
|
||||
#include <zephyr/sys/reboot.h>
|
||||
|
||||
// ── Basic Arduino types ──────────────────────────────────────────────────────
|
||||
typedef bool boolean;
|
||||
typedef uint8_t byte;
|
||||
typedef uint16_t word;
|
||||
|
||||
// ── Pin / digital constants ──────────────────────────────────────────────────
|
||||
#define INPUT 0u
|
||||
#define OUTPUT 1u
|
||||
#define INPUT_PULLUP 2u
|
||||
#define INPUT_PULLDOWN 3u
|
||||
#define OUTPUT_OPENDRAIN 4u
|
||||
|
||||
#define HIGH 1u
|
||||
#define LOW 0u
|
||||
|
||||
#define CHANGE 1
|
||||
#define FALLING 2
|
||||
#define RISING 3
|
||||
|
||||
#ifndef LED_BUILTIN
|
||||
#define LED_BUILTIN -1
|
||||
#endif
|
||||
|
||||
// ── Math / trig constants ────────────────────────────────────────────────────
|
||||
#ifndef PI
|
||||
#define PI 3.14159265358979323846
|
||||
#endif
|
||||
#define HALF_PI 1.57079632679489661923
|
||||
#define TWO_PI 6.28318530717958647693
|
||||
#define DEG_TO_RAD 0.01745329251994329576
|
||||
#define RAD_TO_DEG 57.2957795130823208767
|
||||
#define EULER 2.71828182845904523536
|
||||
|
||||
// ── Bit utilities ────────────────────────────────────────────────────────────
|
||||
#define bitRead(v, b) (((v) >> (b)) & 1)
|
||||
#define bitSet(v, b) ((v) |= (1UL << (b)))
|
||||
#define bitClear(v, b) ((v) &= ~(1UL << (b)))
|
||||
#define bitToggle(v, b) ((v) ^= (1UL << (b)))
|
||||
#define bitWrite(v, b, x) ((x) ? bitSet(v, b) : bitClear(v, b))
|
||||
#define bit(b) (1UL << (b))
|
||||
#define lowByte(w) ((uint8_t)((w)&0xff))
|
||||
#define highByte(w) ((uint8_t)((w) >> 8))
|
||||
// word(h,l) — only define if not already defined (conflicts with typedef above)
|
||||
#undef word
|
||||
#define word(h, l) ((uint16_t)(((h) << 8) | (l)))
|
||||
|
||||
// ── UART config constants ─────────────────────────────────────────────────────
|
||||
#define SERIAL_8N1 0x800001cu
|
||||
#define SERIAL_8N2 0x8000001eu
|
||||
#define SERIAL_8E1 0x8000001eu
|
||||
#define SERIAL_7E1 0x8000001cu
|
||||
|
||||
// ── Integer order ────────────────────────────────────────────────────────────
|
||||
// Adafruit BusIO's SPIDevice.h has `typedef BitOrder BusIOBitOrder;` which
|
||||
// requires BitOrder to be a *type*, not a macro. Mirror the ArduinoCore-API
|
||||
// enum definition rather than #defines.
|
||||
enum BitOrder : uint8_t {
|
||||
LSBFIRST = 0,
|
||||
MSBFIRST = 1,
|
||||
};
|
||||
|
||||
// ── pgmspace compatibility (no-ops on Cortex-M) ──────────────────────────────
|
||||
#define PROGMEM
|
||||
#define PSTR(s) (s)
|
||||
#define F(s) (s)
|
||||
#define pgm_read_byte(addr) (*((const uint8_t *)(addr)))
|
||||
#define pgm_read_word(addr) (*((const uint16_t *)(addr)))
|
||||
#define pgm_read_dword(addr) (*((const uint32_t *)(addr)))
|
||||
#define pgm_read_float(addr) (*((const float *)(addr)))
|
||||
#define pgm_read_ptr(addr) (*((const void **)(addr)))
|
||||
#define strlen_P(s) strlen(s)
|
||||
#define strcpy_P(d, s) strcpy(d, s)
|
||||
#define strncpy_P(d, s, n) strncpy(d, s, n)
|
||||
#define strcmp_P(a, b) strcmp(a, b)
|
||||
#define memcpy_P(d, s, n) memcpy(d, s, n)
|
||||
#define sprintf_P sprintf
|
||||
typedef const char *PGM_P;
|
||||
typedef const char *PGM_VOID_P;
|
||||
|
||||
// ── Arduino numeric base constants (used by Print, RadioLib, etc.) ───────────
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
|
||||
// ── ulong / uint typedef (used by RadioLibInterface, etc.) ───────────────────
|
||||
typedef unsigned long ulong;
|
||||
typedef unsigned int uint;
|
||||
|
||||
// ── Interrupt stubs ──────────────────────────────────────────────────────────
|
||||
static inline void interrupts() {}
|
||||
static inline void noInterrupts() {}
|
||||
#define digitalPinToInterrupt(p) (p)
|
||||
|
||||
// ── portMAX_DELAY — freertosinc.h also defines this; let it win ──────────────
|
||||
// We intentionally do NOT define portMAX_DELAY here. freertosinc.h defines
|
||||
// it for the FreeRTOS / Meshtastic threading layer and must not be overridden.
|
||||
|
||||
// ── Timing & system functions — declared with C linkage ──────────────────────
|
||||
// buzz.cpp and others forward-declare delay() as extern "C"; keep linkage
|
||||
// consistent by wrapping in extern "C" here.
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
void NVIC_SystemReset(void);
|
||||
uint32_t millis(void);
|
||||
uint32_t micros(void);
|
||||
void delay(uint32_t ms);
|
||||
void delayMicroseconds(uint32_t us);
|
||||
void yield(void);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
#include <cctype>
|
||||
#include <cstdarg>
|
||||
|
||||
// ── C++ STL — include BEFORE defining any min/max helpers ───────────────────
|
||||
// Include algorithm first so its min/max templates are in scope.
|
||||
// We must NOT define min/max as function-like macros: the C++ STL uses
|
||||
// 3-argument versions (min(a,b,comp)) that the preprocessor would treat as
|
||||
// calling a 2-arg macro with 3 args.
|
||||
#include <algorithm>
|
||||
// Bring 2-arg std::min / std::max into the global namespace as unqualified
|
||||
// names so that Arduino code calling min(a,b) continues to compile.
|
||||
// (Arduino convention; kept minimal to avoid surprises.)
|
||||
#undef min
|
||||
#undef max
|
||||
using std::max;
|
||||
using std::min;
|
||||
|
||||
// ── Arduino math helpers (macros safe for mixed-type / C calls) ──────────────
|
||||
#ifndef abs
|
||||
#define abs(x) ((x) >= 0 ? (x) : -(x))
|
||||
#endif
|
||||
#define constrain(x, l, h) ((x) < (l) ? (l) : ((x) > (h) ? (h) : (x)))
|
||||
#define round(x) ((x) >= 0 ? (long)((x) + 0.5) : (long)((x)-0.5))
|
||||
#define radians(d) ((d)*DEG_TO_RAD)
|
||||
#define degrees(r) ((r)*RAD_TO_DEG)
|
||||
#define sq(x) ((x) * (x))
|
||||
|
||||
// ── Random ───────────────────────────────────────────────────────────────────
|
||||
static inline void randomSeed(unsigned long seed)
|
||||
{
|
||||
srand((unsigned int)seed);
|
||||
}
|
||||
static inline long random(void)
|
||||
{
|
||||
return (long)rand();
|
||||
}
|
||||
static inline long random(long bound)
|
||||
{
|
||||
return bound > 0 ? (rand() % bound) : 0;
|
||||
}
|
||||
static inline long random(long lo, long hi)
|
||||
{
|
||||
return hi > lo ? lo + rand() % (hi - lo) : lo;
|
||||
}
|
||||
|
||||
// ── GPIO — real Zephyr implementation (Phase 3) ──────────────────────────────
|
||||
// Implemented in nrf54l15_arduino.cpp using Zephyr GPIO/SPI APIs.
|
||||
// Pin numbering: P0.n = n, P1.n = 16+n, P2.n = 32+n
|
||||
void pinMode(uint32_t pin, uint32_t mode);
|
||||
void digitalWrite(uint32_t pin, uint32_t value);
|
||||
int digitalRead(uint32_t pin);
|
||||
static inline void digitalToggle(uint32_t pin)
|
||||
{
|
||||
digitalWrite(pin, !digitalRead(pin));
|
||||
}
|
||||
static inline uint32_t analogRead(uint32_t)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
static inline void analogWrite(uint32_t, uint32_t) {}
|
||||
static inline void analogReadResolution(int) {}
|
||||
static inline void analogWriteResolution(int) {}
|
||||
|
||||
// ── __WFI — provided by CMSIS core_cm33.h; do NOT redefine here ─────────────
|
||||
|
||||
// ── __FlashStringHelper — Arduino PROGMEM string class (no-op on Cortex-M) ──
|
||||
class __FlashStringHelper;
|
||||
|
||||
// ── attachInterrupt / detachInterrupt — real Zephyr GPIO interrupt impl ──────
|
||||
typedef void (*voidFuncPtr)(void);
|
||||
void attachInterrupt(uint32_t pin, voidFuncPtr cb, int mode);
|
||||
void detachInterrupt(uint32_t pin);
|
||||
|
||||
// ── Forward declaration of String (needed by Print / Stream) ─────────────────
|
||||
class String;
|
||||
|
||||
// ── Print base class ─────────────────────────────────────────────────────────
|
||||
class Print
|
||||
{
|
||||
public:
|
||||
virtual size_t write(uint8_t c) = 0;
|
||||
virtual size_t write(const uint8_t *buf, size_t n)
|
||||
{
|
||||
size_t written = 0;
|
||||
while (n--)
|
||||
written += write(*buf++);
|
||||
return written;
|
||||
}
|
||||
size_t write(const char *s) { return s ? write((const uint8_t *)s, strlen(s)) : 0; }
|
||||
size_t write(const char *s, size_t n) { return write((const uint8_t *)s, n); }
|
||||
|
||||
size_t print(const char *s) { return s ? write((const uint8_t *)s, strlen(s)) : 0; }
|
||||
int printf(const char *fmt, ...) __attribute__((format(printf, 2, 3)));
|
||||
|
||||
size_t print(char c) { return write((uint8_t)c); }
|
||||
size_t print(const String &s);
|
||||
size_t print(unsigned char n, int base = 10);
|
||||
size_t print(int n, int base = 10);
|
||||
size_t print(long n, int base = 10);
|
||||
size_t print(unsigned int n, int base = 10);
|
||||
size_t print(unsigned long n, int base = 10);
|
||||
size_t print(float n, int digits = 2);
|
||||
size_t print(double n, int digits = 2);
|
||||
size_t print(bool b) { return print(b ? "true" : "false"); }
|
||||
|
||||
size_t println() { return write((uint8_t)'\n'); }
|
||||
size_t println(const char *s)
|
||||
{
|
||||
size_t r = print(s);
|
||||
return r + println();
|
||||
}
|
||||
size_t println(char c)
|
||||
{
|
||||
size_t r = print(c);
|
||||
return r + println();
|
||||
}
|
||||
size_t println(const String &s);
|
||||
size_t println(int n, int base = 10)
|
||||
{
|
||||
size_t r = print(n, base);
|
||||
return r + println();
|
||||
}
|
||||
size_t println(long n, int base = 10)
|
||||
{
|
||||
size_t r = print(n, base);
|
||||
return r + println();
|
||||
}
|
||||
size_t println(unsigned long n, int base = 10)
|
||||
{
|
||||
size_t r = print(n, base);
|
||||
return r + println();
|
||||
}
|
||||
size_t println(unsigned int n, int base = 10)
|
||||
{
|
||||
size_t r = print(n, base);
|
||||
return r + println();
|
||||
}
|
||||
size_t println(float n, int d = 2)
|
||||
{
|
||||
size_t r = print(n, d);
|
||||
return r + println();
|
||||
}
|
||||
size_t println(double n, int d = 2)
|
||||
{
|
||||
size_t r = print(n, d);
|
||||
return r + println();
|
||||
}
|
||||
size_t println(bool b)
|
||||
{
|
||||
size_t r = print(b);
|
||||
return r + println();
|
||||
}
|
||||
|
||||
virtual void flush() {}
|
||||
};
|
||||
|
||||
// ── Stream base class ────────────────────────────────────────────────────────
|
||||
class Stream : public Print
|
||||
{
|
||||
public:
|
||||
virtual int available() = 0;
|
||||
virtual int read() = 0;
|
||||
virtual int peek() = 0;
|
||||
virtual void setTimeout(unsigned long) {}
|
||||
virtual bool find(const char *) { return false; }
|
||||
String readString();
|
||||
String readStringUntil(char terminator);
|
||||
};
|
||||
|
||||
// ── Minimal Arduino String class (backed by a char buffer) ───────────────────
|
||||
class String
|
||||
{
|
||||
public:
|
||||
String() : _buf(nullptr), _len(0), _cap(0) {}
|
||||
// Implicit conversion is part of the Arduino String contract, used pervasively across the codebase.
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(const char *cstr) : _buf(nullptr), _len(0), _cap(0)
|
||||
{
|
||||
if (cstr)
|
||||
assign(cstr, strlen(cstr));
|
||||
}
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(const String &s) : _buf(nullptr), _len(0), _cap(0) { assign(s._buf ? s._buf : "", s._len); }
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(char c) : _buf(nullptr), _len(0), _cap(0)
|
||||
{
|
||||
const char tmp[2] = {c, 0};
|
||||
assign(tmp, 1);
|
||||
}
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(int n) : _buf(nullptr), _len(0), _cap(0)
|
||||
{
|
||||
char tmp[16];
|
||||
snprintf(tmp, 16, "%d", n);
|
||||
assign(tmp, strlen(tmp));
|
||||
}
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(unsigned int n) : _buf(nullptr), _len(0), _cap(0)
|
||||
{
|
||||
char tmp[16];
|
||||
snprintf(tmp, 16, "%u", n);
|
||||
assign(tmp, strlen(tmp));
|
||||
}
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(long n) : _buf(nullptr), _len(0), _cap(0)
|
||||
{
|
||||
char tmp[24];
|
||||
snprintf(tmp, 24, "%ld", n);
|
||||
assign(tmp, strlen(tmp));
|
||||
}
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(unsigned long n) : _buf(nullptr), _len(0), _cap(0)
|
||||
{
|
||||
char tmp[24];
|
||||
snprintf(tmp, 24, "%lu", n);
|
||||
assign(tmp, strlen(tmp));
|
||||
}
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(float n, int d = 2) : _buf(nullptr), _len(0), _cap(0)
|
||||
{
|
||||
char tmp[32];
|
||||
snprintf(tmp, 32, "%.*f", d, n);
|
||||
assign(tmp, strlen(tmp));
|
||||
}
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
String(double n, int d = 2) : _buf(nullptr), _len(0), _cap(0)
|
||||
{
|
||||
char tmp[32];
|
||||
snprintf(tmp, 32, "%.*f", d, (double)n);
|
||||
assign(tmp, strlen(tmp));
|
||||
}
|
||||
~String() { free(_buf); }
|
||||
|
||||
String &operator=(const String &s)
|
||||
{
|
||||
assign(s._buf ? s._buf : "", s._len);
|
||||
return *this;
|
||||
}
|
||||
String &operator=(const char *s)
|
||||
{
|
||||
assign(s ? s : "", s ? strlen(s) : 0);
|
||||
return *this;
|
||||
}
|
||||
String &operator=(char c)
|
||||
{
|
||||
const char tmp[2] = {c, 0};
|
||||
assign(tmp, 1);
|
||||
return *this;
|
||||
}
|
||||
|
||||
String &operator+=(const String &s)
|
||||
{
|
||||
concat(s._buf ? s._buf : "", s._len);
|
||||
return *this;
|
||||
}
|
||||
String &operator+=(const char *s)
|
||||
{
|
||||
if (s)
|
||||
concat(s, strlen(s));
|
||||
return *this;
|
||||
}
|
||||
String &operator+=(char c)
|
||||
{
|
||||
concat(&c, 1);
|
||||
return *this;
|
||||
}
|
||||
String &operator+=(int n) { return *this += String(n); }
|
||||
String &operator+=(unsigned long n) { return *this += String(n); }
|
||||
|
||||
String operator+(const String &rhs) const
|
||||
{
|
||||
String r(*this);
|
||||
r += rhs;
|
||||
return r;
|
||||
}
|
||||
String operator+(const char *rhs) const
|
||||
{
|
||||
String r(*this);
|
||||
r += rhs;
|
||||
return r;
|
||||
}
|
||||
String operator+(char rhs) const
|
||||
{
|
||||
String r(*this);
|
||||
r += rhs;
|
||||
return r;
|
||||
}
|
||||
|
||||
bool operator==(const String &s) const { return _len == s._len && (_len == 0 || strcmp(_buf, s._buf) == 0); }
|
||||
bool operator==(const char *s) const { return s && strcmp(c_str(), s) == 0; }
|
||||
bool operator!=(const String &s) const { return !(*this == s); }
|
||||
bool operator!=(const char *s) const { return !(*this == s); }
|
||||
bool operator<(const String &s) const { return strcmp(c_str(), s.c_str()) < 0; }
|
||||
bool operator>(const String &s) const { return strcmp(c_str(), s.c_str()) > 0; }
|
||||
|
||||
char operator[](unsigned int i) const { return (_buf && i < _len) ? _buf[i] : 0; }
|
||||
char &operator[](unsigned int i)
|
||||
{
|
||||
static char dummy = 0;
|
||||
return (_buf && i < _len) ? _buf[i] : dummy;
|
||||
}
|
||||
|
||||
const char *c_str() const { return _buf ? _buf : ""; }
|
||||
unsigned int length() const { return _len; }
|
||||
bool isEmpty() const { return _len == 0; }
|
||||
bool equals(const String &s) const { return *this == s; }
|
||||
bool equals(const char *s) const { return *this == s; }
|
||||
bool equalsIgnoreCase(const String &s) const
|
||||
{
|
||||
if (_len != s._len)
|
||||
return false;
|
||||
for (unsigned i = 0; i < _len; i++)
|
||||
if (std::tolower(_buf[i]) != std::tolower(s._buf[i]))
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
bool startsWith(const String &pfx) const
|
||||
{
|
||||
if (pfx._len > _len)
|
||||
return false;
|
||||
return strncmp(c_str(), pfx.c_str(), pfx._len) == 0;
|
||||
}
|
||||
bool startsWith(const char *pfx) const
|
||||
{
|
||||
if (!pfx)
|
||||
return false;
|
||||
size_t pl = strlen(pfx);
|
||||
return pl <= _len && strncmp(c_str(), pfx, pl) == 0;
|
||||
}
|
||||
bool endsWith(const String &sfx) const
|
||||
{
|
||||
if (sfx._len > _len)
|
||||
return false;
|
||||
return strcmp(c_str() + _len - sfx._len, sfx.c_str()) == 0;
|
||||
}
|
||||
int indexOf(char c, unsigned from = 0) const
|
||||
{
|
||||
if (!_buf)
|
||||
return -1;
|
||||
const char *p = strchr(_buf + from, c);
|
||||
return p ? (int)(p - _buf) : -1;
|
||||
}
|
||||
int indexOf(const String &s, unsigned from = 0) const
|
||||
{
|
||||
if (!_buf)
|
||||
return -1;
|
||||
const char *p = strstr(_buf + from, s.c_str());
|
||||
return p ? (int)(p - _buf) : -1;
|
||||
}
|
||||
int lastIndexOf(char c) const
|
||||
{
|
||||
if (!_buf)
|
||||
return -1;
|
||||
const char *p = strrchr(_buf, c);
|
||||
return p ? (int)(p - _buf) : -1;
|
||||
}
|
||||
String substring(unsigned beginIndex) const
|
||||
{
|
||||
if (!_buf || beginIndex >= _len)
|
||||
return String();
|
||||
return String(_buf + beginIndex);
|
||||
}
|
||||
String substring(unsigned beginIndex, unsigned endIndex) const
|
||||
{
|
||||
if (!_buf || beginIndex >= _len)
|
||||
return String();
|
||||
if (endIndex > _len)
|
||||
endIndex = _len;
|
||||
if (endIndex <= beginIndex)
|
||||
return String();
|
||||
String r;
|
||||
r.assign(_buf + beginIndex, endIndex - beginIndex);
|
||||
return r;
|
||||
}
|
||||
void toUpperCase()
|
||||
{
|
||||
if (_buf)
|
||||
for (unsigned i = 0; i < _len; i++)
|
||||
_buf[i] = (char)std::toupper(_buf[i]);
|
||||
}
|
||||
void toLowerCase()
|
||||
{
|
||||
if (_buf)
|
||||
for (unsigned i = 0; i < _len; i++)
|
||||
_buf[i] = (char)std::tolower(_buf[i]);
|
||||
}
|
||||
void trim()
|
||||
{
|
||||
if (!_buf || _len == 0)
|
||||
return;
|
||||
unsigned s = 0;
|
||||
while (s < _len && std::isspace(_buf[s]))
|
||||
s++;
|
||||
unsigned e = _len;
|
||||
while (e > s && std::isspace(_buf[e - 1]))
|
||||
e--;
|
||||
if (s > 0 || e < _len) {
|
||||
memmove(_buf, _buf + s, e - s);
|
||||
_len = e - s;
|
||||
_buf[_len] = 0;
|
||||
}
|
||||
}
|
||||
void replace(char from, char to)
|
||||
{
|
||||
if (_buf)
|
||||
for (unsigned i = 0; i < _len; i++)
|
||||
if (_buf[i] == from)
|
||||
_buf[i] = to;
|
||||
}
|
||||
void replace(const String &from, const String &to);
|
||||
bool remove(unsigned index, unsigned count = 1)
|
||||
{
|
||||
if (!_buf || index >= _len)
|
||||
return false;
|
||||
if (index + count > _len)
|
||||
count = _len - index;
|
||||
memmove(_buf + index, _buf + index + count, _len - index - count + 1);
|
||||
_len -= count;
|
||||
return true;
|
||||
}
|
||||
void clear()
|
||||
{
|
||||
_len = 0;
|
||||
if (_buf)
|
||||
_buf[0] = 0;
|
||||
}
|
||||
char charAt(unsigned i) const { return (*this)[i]; }
|
||||
void setCharAt(unsigned i, char c)
|
||||
{
|
||||
if (_buf && i < _len)
|
||||
_buf[i] = c;
|
||||
}
|
||||
void toCharArray(char *buf, unsigned int bufsize, unsigned int index = 0) const
|
||||
{
|
||||
if (!buf || bufsize == 0)
|
||||
return;
|
||||
unsigned int avail = (_buf && _len > index) ? (_len - index) : 0;
|
||||
unsigned int copy = avail < bufsize - 1 ? avail : bufsize - 1;
|
||||
if (copy > 0)
|
||||
memcpy(buf, _buf + index, copy);
|
||||
buf[copy] = '\0';
|
||||
}
|
||||
void concat(const String &s) { *this += s; }
|
||||
void concat(const char *s) { *this += s; }
|
||||
long toInt() const { return _buf ? atol(_buf) : 0; }
|
||||
float toFloat() const { return _buf ? (float)atof(_buf) : 0.0f; }
|
||||
double toDouble() const { return _buf ? atof(_buf) : 0.0; }
|
||||
|
||||
private:
|
||||
char *_buf;
|
||||
unsigned int _len;
|
||||
unsigned int _cap;
|
||||
|
||||
void assign(const char *s, unsigned int n)
|
||||
{
|
||||
if (n >= _cap)
|
||||
reserve(n + 1);
|
||||
if (_buf) {
|
||||
memcpy(_buf, s, n);
|
||||
_buf[n] = 0;
|
||||
_len = n;
|
||||
}
|
||||
}
|
||||
void concat(const char *s, unsigned int n)
|
||||
{
|
||||
if (!s || n == 0)
|
||||
return;
|
||||
unsigned newlen = _len + n;
|
||||
if (newlen >= _cap)
|
||||
reserve(newlen + 1);
|
||||
if (_buf) {
|
||||
memcpy(_buf + _len, s, n);
|
||||
_len = newlen;
|
||||
_buf[_len] = 0;
|
||||
}
|
||||
}
|
||||
void reserve(unsigned int n)
|
||||
{
|
||||
char *b = (char *)realloc(_buf, n);
|
||||
if (b) {
|
||||
_buf = b;
|
||||
_cap = n;
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
inline String operator+(const char *lhs, const String &rhs)
|
||||
{
|
||||
return String(lhs) + rhs;
|
||||
}
|
||||
inline String operator+(char lhs, const String &rhs)
|
||||
{
|
||||
return String(lhs) + rhs;
|
||||
}
|
||||
|
||||
// ── Print inline definitions that need String ────────────────────────────────
|
||||
inline size_t Print::print(const String &s)
|
||||
{
|
||||
return write((const uint8_t *)s.c_str(), s.length());
|
||||
}
|
||||
inline size_t Print::println(const String &s)
|
||||
{
|
||||
size_t r = print(s);
|
||||
return r + println();
|
||||
}
|
||||
|
||||
// ── Stream inline definitions that need String ───────────────────────────────
|
||||
inline String Stream::readString()
|
||||
{
|
||||
return String();
|
||||
}
|
||||
inline String Stream::readStringUntil(char)
|
||||
{
|
||||
return String();
|
||||
}
|
||||
|
||||
// ── HardwareSerial ───────────────────────────────────────────────────────────
|
||||
class HardwareSerial : public Stream
|
||||
{
|
||||
public:
|
||||
void begin(unsigned long) {}
|
||||
void begin(unsigned long, uint16_t) {}
|
||||
void end() {}
|
||||
void setPins(int rx, int tx) {}
|
||||
void setPinout(int tx, int rx) {}
|
||||
void setFIFOSize(size_t) {}
|
||||
void setRxBufferSize(size_t) {}
|
||||
void begin(unsigned long baud, uint32_t config, int8_t rx = -1, int8_t tx = -1, bool invert = false) {}
|
||||
int available() override { return 0; }
|
||||
int read() override { return -1; }
|
||||
int peek() override { return -1; }
|
||||
size_t write(uint8_t c) override;
|
||||
size_t write(const uint8_t *buf, size_t n) override;
|
||||
using Print::write; // un-hide base class write(const char*)
|
||||
size_t readBytes(uint8_t *buf, size_t len) { return 0; }
|
||||
size_t readBytes(char *buf, size_t len) { return 0; }
|
||||
operator bool() const { return true; }
|
||||
void flush() override {}
|
||||
String readString() { return String(); }
|
||||
String readStringUntil(char) { return String(); }
|
||||
};
|
||||
|
||||
// Uart — nRF52 BSP alias for HardwareSerial (used by GPS.h when ARCH_NRF52)
|
||||
typedef HardwareSerial Uart;
|
||||
|
||||
extern HardwareSerial Serial;
|
||||
extern HardwareSerial Serial1;
|
||||
extern HardwareSerial Serial2;
|
||||
|
||||
// ── map() utility ────────────────────────────────────────────────────────────
|
||||
static inline long map(long x, long in_min, long in_max, long out_min, long out_max)
|
||||
{
|
||||
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
|
||||
}
|
||||
|
||||
// ── shiftIn / shiftOut stubs ─────────────────────────────────────────────────
|
||||
static inline uint8_t shiftIn(uint8_t, uint8_t, uint8_t)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
static inline void shiftOut(uint8_t, uint8_t, uint8_t, uint8_t) {}
|
||||
|
||||
// ── tone / noTone stubs ──────────────────────────────────────────────────────
|
||||
static inline void tone(uint8_t, unsigned int, unsigned long = 0) {}
|
||||
static inline void noTone(uint8_t) {}
|
||||
|
||||
// ── pulseIn stub ─────────────────────────────────────────────────────────────
|
||||
static inline unsigned long pulseIn(uint8_t, uint8_t, unsigned long = 1000000UL)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
// ── strdup / stpcpy — POSIX extensions not in Zephyr newlib ─────────────────
|
||||
#ifndef strdup
|
||||
static inline char *strdup(const char *s)
|
||||
{
|
||||
size_t n = strlen(s) + 1;
|
||||
char *d = (char *)malloc(n);
|
||||
if (d)
|
||||
memcpy(d, s, n);
|
||||
return d;
|
||||
}
|
||||
#endif
|
||||
#ifndef stpcpy
|
||||
static inline char *stpcpy(char *dst, const char *src)
|
||||
{
|
||||
while ((*dst++ = *src++) != '\0') {
|
||||
}
|
||||
return dst - 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
// ── strnstr — BSD extension not in Zephyr libc; defined in meshUtils.cpp ─────
|
||||
// Declare here so callers (GPS.cpp etc.) don't need ARCH_PORTDUINO.
|
||||
#ifndef STRNSTR
|
||||
#define STRNSTR
|
||||
char *strnstr(const char *s, const char *find, size_t slen);
|
||||
#endif
|
||||
|
||||
// ── strlcpy — BSD extension; implementation in nrf54l15_arduino.cpp ──────────
|
||||
#ifndef HAVE_STRLCPY
|
||||
#define HAVE_STRLCPY
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
size_t strlcpy(char *dst, const char *src, size_t size);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// ── setenv / getenv / tzset — Zephyr stubs for timezone support ──────────────
|
||||
#include <stdlib.h>
|
||||
static inline int setenv(const char *, const char *, int)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
static inline void tzset(void) {}
|
||||
|
||||
// ── dbgHeapFree / dbgHeapTotal — nRF52 BSP heap diagnostics ─────────────────
|
||||
// Used by memGet.cpp when ARCH_NRF52 is defined. Return 0 for Phase 2.
|
||||
static inline uint32_t dbgHeapFree(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
static inline uint32_t dbgHeapTotal(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
// ── WCharacter helpers ───────────────────────────────────────────────────────
|
||||
static inline bool isAlpha(char c)
|
||||
{
|
||||
return std::isalpha((unsigned char)c) != 0;
|
||||
}
|
||||
static inline bool isAlphaNumeric(char c)
|
||||
{
|
||||
return std::isalnum((unsigned char)c) != 0;
|
||||
}
|
||||
static inline bool isDigit(char c)
|
||||
{
|
||||
return std::isdigit((unsigned char)c) != 0;
|
||||
}
|
||||
static inline bool isSpace(char c)
|
||||
{
|
||||
return std::isspace((unsigned char)c) != 0;
|
||||
}
|
||||
static inline bool isUpperCase(char c)
|
||||
{
|
||||
return std::isupper((unsigned char)c) != 0;
|
||||
}
|
||||
static inline bool isLowerCase(char c)
|
||||
{
|
||||
return std::islower((unsigned char)c) != 0;
|
||||
}
|
||||
static inline char toUpperCase(char c)
|
||||
{
|
||||
return (char)std::toupper((unsigned char)c);
|
||||
}
|
||||
static inline char toLowerCase(char c)
|
||||
{
|
||||
return (char)std::tolower((unsigned char)c);
|
||||
}
|
||||
|
||||
#else /* C only */
|
||||
#ifndef min
|
||||
#define min(a, b) ((a) < (b) ? (a) : (b))
|
||||
#endif
|
||||
#ifndef max
|
||||
#define max(a, b) ((a) > (b) ? (a) : (b))
|
||||
#endif
|
||||
#ifndef abs
|
||||
#define abs(x) ((x) >= 0 ? (x) : -(x))
|
||||
#endif
|
||||
#define constrain(x, l, h) ((x) < (l) ? (l) : ((x) > (h) ? (h) : (x)))
|
||||
#define round(x) ((x) >= 0 ? (long)((x) + 0.5) : (long)((x)-0.5))
|
||||
#endif /* __cplusplus */
|
||||
|
||||
#endif /* Arduino_h */
|
||||
34
src/platform/nrf54l15/IPAddress.h
Normal file
34
src/platform/nrf54l15/IPAddress.h
Normal file
@@ -0,0 +1,34 @@
|
||||
// IPAddress.h — stub for nRF54L15/Zephyr
|
||||
// MQTT.cpp includes this for IPv4 address representation.
|
||||
// Phase 2: compile-only stub.
|
||||
#pragma once
|
||||
#include <stdint.h>
|
||||
|
||||
class IPAddress
|
||||
{
|
||||
public:
|
||||
IPAddress() : _addr(0) {}
|
||||
explicit IPAddress(uint32_t addr) : _addr(addr) {}
|
||||
IPAddress(uint8_t a, uint8_t b, uint8_t c, uint8_t d)
|
||||
: _addr(((uint32_t)a) | ((uint32_t)b << 8) | ((uint32_t)c << 16) | ((uint32_t)d << 24))
|
||||
{
|
||||
}
|
||||
|
||||
uint8_t operator[](int i) const { return reinterpret_cast<const uint8_t *>(&_addr)[i]; }
|
||||
operator uint32_t() const { return _addr; }
|
||||
bool operator==(const IPAddress &o) const { return _addr == o._addr; }
|
||||
bool operator!=(const IPAddress &o) const { return _addr != o._addr; }
|
||||
|
||||
bool fromString(const char *addr)
|
||||
{
|
||||
unsigned a, b, c, d;
|
||||
if (sscanf(addr, "%u.%u.%u.%u", &a, &b, &c, &d) == 4 && a <= 255 && b <= 255 && c <= 255 && d <= 255) {
|
||||
_addr = a | (b << 8) | (c << 16) | (d << 24);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
private:
|
||||
uint32_t _addr;
|
||||
};
|
||||
274
src/platform/nrf54l15/InternalFileSystem.cpp
Normal file
274
src/platform/nrf54l15/InternalFileSystem.cpp
Normal file
@@ -0,0 +1,274 @@
|
||||
// InternalFileSystem.cpp — Zephyr LittleFS backend for nRF54L15
|
||||
//
|
||||
// Implements Adafruit_LittleFS_Namespace used by FSCommon.h/cpp.
|
||||
// Storage: 36 KB storage_partition in nRF54L15 internal RRAM (defined in
|
||||
// zephyr/dts/nordic/nrf54l15_partition.dtsi, included by the board DTS).
|
||||
|
||||
#include "InternalFileSystem.h"
|
||||
#include "configuration.h"
|
||||
|
||||
#include <zephyr/fs/fs.h>
|
||||
#include <zephyr/fs/littlefs.h>
|
||||
#include <zephyr/storage/flash_map.h>
|
||||
|
||||
using namespace Adafruit_LittleFS_Namespace;
|
||||
|
||||
// ── LittleFS mount ────────────────────────────────────────────────────────
|
||||
|
||||
FS_LITTLEFS_DECLARE_DEFAULT_CONFIG(nrf54l15_lfs_data);
|
||||
|
||||
static struct fs_mount_t _lfs_mnt = {
|
||||
.type = FS_LITTLEFS,
|
||||
.mnt_point = NRF54L15_FS_MOUNT,
|
||||
.fs_data = &nrf54l15_lfs_data,
|
||||
.storage_dev = (void *)(uintptr_t)FIXED_PARTITION_ID(storage_partition),
|
||||
.flags = 0,
|
||||
};
|
||||
|
||||
// ── Global singleton ──────────────────────────────────────────────────────
|
||||
|
||||
Adafruit_LittleFS_Namespace::InternalFileSystem InternalFS;
|
||||
|
||||
// ── Path helpers ──────────────────────────────────────────────────────────
|
||||
|
||||
void InternalFileSystem::toabs(const char *rel, char *abs, size_t abssz)
|
||||
{
|
||||
// Root "/" maps to the mount point itself (no trailing slash)
|
||||
if (rel[0] == '/' && rel[1] == '\0') {
|
||||
strncpy(abs, NRF54L15_FS_MOUNT, abssz - 1);
|
||||
abs[abssz - 1] = '\0';
|
||||
} else if (rel[0] == '/') {
|
||||
snprintf(abs, abssz, "%s%s", NRF54L15_FS_MOUNT, rel);
|
||||
} else {
|
||||
snprintf(abs, abssz, "%s/%s", NRF54L15_FS_MOUNT, rel);
|
||||
}
|
||||
}
|
||||
|
||||
// Strip mount-point prefix to get the FS-root-relative path ("/prefs/...").
|
||||
static void torel(const char *abs, char *rel, size_t relsz)
|
||||
{
|
||||
const char *mp = NRF54L15_FS_MOUNT;
|
||||
size_t mplen = strlen(mp);
|
||||
if (strncmp(abs, mp, mplen) == 0) {
|
||||
const char *suffix = abs + mplen;
|
||||
if (suffix[0] == '\0') {
|
||||
strncpy(rel, "/", relsz);
|
||||
} else {
|
||||
strncpy(rel, suffix, relsz - 1);
|
||||
rel[relsz - 1] = '\0';
|
||||
}
|
||||
} else {
|
||||
strncpy(rel, abs, relsz - 1);
|
||||
rel[relsz - 1] = '\0';
|
||||
}
|
||||
}
|
||||
|
||||
// ── InternalFileSystem methods ────────────────────────────────────────────
|
||||
|
||||
bool InternalFileSystem::begin()
|
||||
{
|
||||
if (_mounted)
|
||||
return true;
|
||||
|
||||
int rc = fs_mount(&_lfs_mnt);
|
||||
if (rc == 0) {
|
||||
_mounted = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// Mount failed: attempt to format (creates a fresh LittleFS)
|
||||
LOG_WARN("LittleFS mount failed (%d), formatting storage partition...", rc);
|
||||
int fmt_rc = fs_mkfs(FS_LITTLEFS, (uintptr_t)FIXED_PARTITION_ID(storage_partition), NULL, 0);
|
||||
if (fmt_rc != 0) {
|
||||
LOG_ERROR("LittleFS format failed (%d)", fmt_rc);
|
||||
return false;
|
||||
}
|
||||
|
||||
rc = fs_mount(&_lfs_mnt);
|
||||
if (rc == 0) {
|
||||
_mounted = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
LOG_ERROR("LittleFS mount failed after format (%d)", rc);
|
||||
return false;
|
||||
}
|
||||
|
||||
File InternalFileSystem::open(const char *path, const char *mode)
|
||||
{
|
||||
if (!_mounted)
|
||||
return File();
|
||||
|
||||
char abs[NRF54L15_FS_PATHLEN];
|
||||
toabs(path, abs, sizeof(abs));
|
||||
|
||||
auto s = std::make_shared<NRF54L15FileState>();
|
||||
if (!s)
|
||||
return File();
|
||||
|
||||
strncpy(s->fullpath, abs, sizeof(s->fullpath) - 1);
|
||||
torel(abs, s->relpath, sizeof(s->relpath));
|
||||
|
||||
// Check whether the path is a directory
|
||||
struct fs_dirent entry;
|
||||
int stat_rc = fs_stat(abs, &entry);
|
||||
if (stat_rc == 0 && entry.type == FS_DIR_ENTRY_DIR) {
|
||||
s->is_dir = true;
|
||||
if (fs_opendir(&s->dir, abs) == 0) {
|
||||
s->valid = true;
|
||||
return File(s);
|
||||
}
|
||||
return File();
|
||||
}
|
||||
|
||||
// Open as a regular file
|
||||
fs_mode_t flags;
|
||||
if (strcmp(mode, FILE_O_WRITE) == 0) {
|
||||
// Truncate on write — unlink first to ensure a clean start
|
||||
fs_unlink(abs);
|
||||
flags = FS_O_WRITE | FS_O_CREATE;
|
||||
} else {
|
||||
flags = FS_O_READ;
|
||||
}
|
||||
|
||||
if (fs_open(&s->file, abs, flags) == 0) {
|
||||
s->is_dir = false;
|
||||
s->valid = true;
|
||||
return File(s);
|
||||
}
|
||||
|
||||
return File();
|
||||
}
|
||||
|
||||
bool InternalFileSystem::exists(const char *path)
|
||||
{
|
||||
if (!_mounted)
|
||||
return false;
|
||||
char abs[NRF54L15_FS_PATHLEN];
|
||||
toabs(path, abs, sizeof(abs));
|
||||
struct fs_dirent entry;
|
||||
return fs_stat(abs, &entry) == 0;
|
||||
}
|
||||
|
||||
bool InternalFileSystem::remove(const char *path)
|
||||
{
|
||||
if (!_mounted)
|
||||
return false;
|
||||
char abs[NRF54L15_FS_PATHLEN];
|
||||
toabs(path, abs, sizeof(abs));
|
||||
return fs_unlink(abs) == 0;
|
||||
}
|
||||
|
||||
bool InternalFileSystem::rename(const char *from, const char *to)
|
||||
{
|
||||
if (!_mounted)
|
||||
return false;
|
||||
char absfrom[NRF54L15_FS_PATHLEN], absto[NRF54L15_FS_PATHLEN];
|
||||
toabs(from, absfrom, sizeof(absfrom));
|
||||
toabs(to, absto, sizeof(absto));
|
||||
return fs_rename(absfrom, absto) == 0;
|
||||
}
|
||||
|
||||
bool InternalFileSystem::mkdir(const char *path)
|
||||
{
|
||||
if (!_mounted)
|
||||
return false;
|
||||
char abs[NRF54L15_FS_PATHLEN];
|
||||
toabs(path, abs, sizeof(abs));
|
||||
int rc = fs_mkdir(abs);
|
||||
return rc == 0 || rc == -EEXIST;
|
||||
}
|
||||
|
||||
bool InternalFileSystem::rmdir(const char *path)
|
||||
{
|
||||
if (!_mounted)
|
||||
return false;
|
||||
char abs[NRF54L15_FS_PATHLEN];
|
||||
toabs(path, abs, sizeof(abs));
|
||||
return fs_unlink(abs) == 0;
|
||||
}
|
||||
|
||||
bool InternalFileSystem::rmdir_r(const char *path)
|
||||
{
|
||||
if (!_mounted)
|
||||
return false;
|
||||
char abs[NRF54L15_FS_PATHLEN];
|
||||
toabs(path, abs, sizeof(abs));
|
||||
|
||||
struct fs_dir_t dir;
|
||||
fs_dir_t_init(&dir);
|
||||
if (fs_opendir(&dir, abs) != 0) {
|
||||
// Not a directory — try to delete as file
|
||||
return fs_unlink(abs) == 0;
|
||||
}
|
||||
|
||||
struct fs_dirent entry;
|
||||
char child[NRF54L15_FS_PATHLEN];
|
||||
while (fs_readdir(&dir, &entry) == 0 && entry.name[0] != '\0') {
|
||||
snprintf(child, sizeof(child), "%s/%s", abs, entry.name);
|
||||
if (entry.type == FS_DIR_ENTRY_DIR) {
|
||||
// Recurse: pass the absolute path stripped of mount prefix
|
||||
char childrel[NRF54L15_FS_PATHLEN];
|
||||
torel(child, childrel, sizeof(childrel));
|
||||
rmdir_r(childrel);
|
||||
} else {
|
||||
fs_unlink(child);
|
||||
}
|
||||
}
|
||||
fs_closedir(&dir);
|
||||
return fs_unlink(abs) == 0;
|
||||
}
|
||||
|
||||
bool InternalFileSystem::format()
|
||||
{
|
||||
if (_mounted) {
|
||||
fs_unmount(&_lfs_mnt);
|
||||
_mounted = false;
|
||||
}
|
||||
int rc = fs_mkfs(FS_LITTLEFS, (uintptr_t)FIXED_PARTITION_ID(storage_partition), NULL, 0);
|
||||
if (rc != 0) {
|
||||
LOG_ERROR("LittleFS format failed (%d)", rc);
|
||||
return false;
|
||||
}
|
||||
return begin();
|
||||
}
|
||||
|
||||
// ── File::openNextFile ────────────────────────────────────────────────────
|
||||
// Defined here because it accesses Zephyr fs_readdir/fs_open APIs.
|
||||
|
||||
File File::openNextFile()
|
||||
{
|
||||
if (!_s || !_s->valid || !_s->is_dir)
|
||||
return File();
|
||||
|
||||
struct fs_dirent entry;
|
||||
if (fs_readdir(&_s->dir, &entry) != 0)
|
||||
return File();
|
||||
if (entry.name[0] == '\0')
|
||||
return File(); // end of directory
|
||||
|
||||
char childabs[NRF54L15_FS_PATHLEN];
|
||||
snprintf(childabs, sizeof(childabs), "%s/%s", _s->fullpath, entry.name);
|
||||
|
||||
auto s = std::make_shared<NRF54L15FileState>();
|
||||
if (!s)
|
||||
return File();
|
||||
|
||||
strncpy(s->fullpath, childabs, sizeof(s->fullpath) - 1);
|
||||
torel(childabs, s->relpath, sizeof(s->relpath));
|
||||
|
||||
if (entry.type == FS_DIR_ENTRY_DIR) {
|
||||
s->is_dir = true;
|
||||
if (fs_opendir(&s->dir, childabs) == 0) {
|
||||
s->valid = true;
|
||||
return File(s);
|
||||
}
|
||||
} else {
|
||||
s->is_dir = false;
|
||||
if (fs_open(&s->file, childabs, FS_O_READ) == 0) {
|
||||
s->valid = true;
|
||||
return File(s);
|
||||
}
|
||||
}
|
||||
return File();
|
||||
}
|
||||
212
src/platform/nrf54l15/InternalFileSystem.h
Normal file
212
src/platform/nrf54l15/InternalFileSystem.h
Normal file
@@ -0,0 +1,212 @@
|
||||
// InternalFileSystem.h — Zephyr LittleFS backend for nRF54L15
|
||||
//
|
||||
// Implements the Adafruit InternalFileSystem API subset used by Meshtastic,
|
||||
// backed by Zephyr's fs/littlefs on the storage_partition of the nRF54L15's
|
||||
// internal RRAM. Partition size is taken from the DTS at compile time via
|
||||
// FIXED_PARTITION_SIZE(storage_partition) — the DK overlay currently maps
|
||||
// ~700 KB into slot1 (see zephyr/boards/nrf54l15dk_nrf54l15_cpuapp.overlay).
|
||||
//
|
||||
// Mount point: /lfs
|
||||
// All paths passed to open/exists/mkdir etc. are relative to the FS root
|
||||
// (e.g. "/prefs/config.proto") and are prepended with "/lfs" internally.
|
||||
//
|
||||
// File objects are copyable via std::shared_ptr<NRF54L15FileState>.
|
||||
// The underlying Zephyr handle is closed when the last copy is destroyed.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <zephyr/fs/fs.h>
|
||||
#include <zephyr/storage/flash_map.h>
|
||||
|
||||
#ifndef FILE_O_READ
|
||||
#define FILE_O_READ "r"
|
||||
#define FILE_O_WRITE "w"
|
||||
#endif
|
||||
|
||||
#define NRF54L15_FS_MOUNT "/lfs"
|
||||
#define NRF54L15_FS_PATHLEN 256
|
||||
|
||||
namespace Adafruit_LittleFS_Namespace
|
||||
{
|
||||
|
||||
class InternalFileSystem; // forward
|
||||
|
||||
// ── Internal file/dir state ───────────────────────────────────────────────
|
||||
|
||||
struct NRF54L15FileState {
|
||||
bool valid = false;
|
||||
bool is_dir = false;
|
||||
|
||||
// Absolute Zephyr path, e.g. "/lfs/prefs/config.proto"
|
||||
char fullpath[NRF54L15_FS_PATHLEN] = {0};
|
||||
// Path from FS root, e.g. "/prefs/config.proto" (returned by name())
|
||||
char relpath[NRF54L15_FS_PATHLEN] = {0};
|
||||
|
||||
struct fs_file_t file;
|
||||
struct fs_dir_t dir;
|
||||
|
||||
NRF54L15FileState()
|
||||
{
|
||||
fs_file_t_init(&file);
|
||||
fs_dir_t_init(&dir);
|
||||
}
|
||||
|
||||
~NRF54L15FileState()
|
||||
{
|
||||
if (valid) {
|
||||
if (is_dir)
|
||||
fs_closedir(&dir);
|
||||
else
|
||||
fs_close(&file);
|
||||
valid = false;
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
// ── File ─────────────────────────────────────────────────────────────────
|
||||
|
||||
class File
|
||||
{
|
||||
public:
|
||||
File() = default;
|
||||
explicit File(InternalFileSystem &) {} // nRF52 compat constructor
|
||||
|
||||
explicit operator bool() const { return _s && _s->valid; }
|
||||
|
||||
int read(void *buf, uint16_t nbyte)
|
||||
{
|
||||
if (!_s || !_s->valid || _s->is_dir)
|
||||
return -1;
|
||||
ssize_t n = fs_read(&_s->file, buf, nbyte);
|
||||
return n < 0 ? -1 : (int)n;
|
||||
}
|
||||
|
||||
int read()
|
||||
{
|
||||
uint8_t b;
|
||||
return read(&b, 1) == 1 ? (int)b : -1;
|
||||
}
|
||||
|
||||
size_t write(const uint8_t *buf, size_t len)
|
||||
{
|
||||
if (!_s || !_s->valid || _s->is_dir)
|
||||
return 0;
|
||||
ssize_t n = fs_write(&_s->file, buf, len);
|
||||
return n < 0 ? 0 : (size_t)n;
|
||||
}
|
||||
|
||||
size_t write(uint8_t b) { return write(&b, 1); }
|
||||
|
||||
void flush()
|
||||
{
|
||||
if (_s && _s->valid && !_s->is_dir)
|
||||
fs_sync(&_s->file);
|
||||
}
|
||||
|
||||
void close() { _s.reset(); }
|
||||
|
||||
size_t size()
|
||||
{
|
||||
if (!_s || !_s->valid || _s->is_dir)
|
||||
return 0;
|
||||
struct fs_dirent entry;
|
||||
if (fs_stat(_s->fullpath, &entry) == 0)
|
||||
return (size_t)entry.size;
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool isDirectory() { return _s && _s->valid && _s->is_dir; }
|
||||
|
||||
// Returns path from FS root, e.g. "/prefs/config.proto"
|
||||
const char *name() { return _s ? _s->relpath : ""; }
|
||||
|
||||
// Returns the next entry in a directory. Modifies the dir stream in _s.
|
||||
File openNextFile();
|
||||
|
||||
void rewindDirectory()
|
||||
{
|
||||
if (!_s || !_s->valid || !_s->is_dir)
|
||||
return;
|
||||
// Zephyr has no rewinddir(); close + reopen the same handle. Skipping
|
||||
// the close would leak the LittleFS dir state and the next openNextFile
|
||||
// could return stale entries on some Zephyr versions.
|
||||
fs_closedir(&_s->dir);
|
||||
fs_dir_t_init(&_s->dir);
|
||||
if (fs_opendir(&_s->dir, _s->fullpath) != 0) {
|
||||
_s->valid = false;
|
||||
}
|
||||
}
|
||||
|
||||
bool seek(uint32_t pos)
|
||||
{
|
||||
if (!_s || !_s->valid || _s->is_dir)
|
||||
return false;
|
||||
return fs_seek(&_s->file, (off_t)pos, FS_SEEK_SET) == 0;
|
||||
}
|
||||
|
||||
int available()
|
||||
{
|
||||
if (!_s || !_s->valid || _s->is_dir)
|
||||
return 0;
|
||||
off_t pos = fs_tell(&_s->file);
|
||||
if (pos < 0)
|
||||
return 0;
|
||||
struct fs_dirent entry;
|
||||
if (fs_stat(_s->fullpath, &entry) != 0)
|
||||
return 0;
|
||||
long rem = (long)entry.size - (long)pos;
|
||||
return rem > 0 ? (int)rem : 0;
|
||||
}
|
||||
|
||||
int peek() { return -1; }
|
||||
|
||||
// Internal: constructed by InternalFileSystem and openNextFile()
|
||||
explicit File(std::shared_ptr<NRF54L15FileState> s) : _s(std::move(s)) {}
|
||||
|
||||
private:
|
||||
std::shared_ptr<NRF54L15FileState> _s;
|
||||
};
|
||||
|
||||
// ── InternalFileSystem ────────────────────────────────────────────────────
|
||||
|
||||
class InternalFileSystem
|
||||
{
|
||||
public:
|
||||
bool begin();
|
||||
File open(const char *path, const char *mode);
|
||||
bool exists(const char *path);
|
||||
bool remove(const char *path);
|
||||
bool rename(const char *from, const char *to);
|
||||
bool mkdir(const char *path);
|
||||
bool rmdir(const char *path);
|
||||
bool rmdir_r(const char *path); // recursive delete (used by FSCommon rmDir)
|
||||
uint32_t usedBytes()
|
||||
{
|
||||
struct fs_statvfs st = {};
|
||||
if (fs_statvfs(NRF54L15_FS_MOUNT, &st) != 0)
|
||||
return 0;
|
||||
// Zephyr returns block counts; convert to bytes. f_frsize is the
|
||||
// fundamental fragment size (LittleFS reports it equal to the block
|
||||
// size). used = (total - free) * frag_size.
|
||||
if (st.f_blocks <= st.f_bfree)
|
||||
return 0;
|
||||
return (uint32_t)((st.f_blocks - st.f_bfree) * st.f_frsize);
|
||||
}
|
||||
uint32_t totalBytes() { return (uint32_t)FIXED_PARTITION_SIZE(storage_partition); }
|
||||
bool format();
|
||||
|
||||
// Convert a FS-root-relative path to an absolute Zephyr path.
|
||||
static void toabs(const char *rel, char *abs, size_t abssz);
|
||||
|
||||
private:
|
||||
bool _mounted = false;
|
||||
};
|
||||
|
||||
} // namespace Adafruit_LittleFS_Namespace
|
||||
|
||||
extern Adafruit_LittleFS_Namespace::InternalFileSystem InternalFS;
|
||||
18
src/platform/nrf54l15/NRF52Bluetooth.h
Normal file
18
src/platform/nrf54l15/NRF52Bluetooth.h
Normal file
@@ -0,0 +1,18 @@
|
||||
// NRF52Bluetooth.h — stub for nRF54L15/Zephyr
|
||||
// main.h includes this when ARCH_NRF52 is defined.
|
||||
// Bluetooth is excluded (MESHTASTIC_EXCLUDE_BLUETOOTH=1); this satisfies the
|
||||
// include chain without pulling in the nRF52 Bluefruit SDK.
|
||||
#pragma once
|
||||
|
||||
class NRF52Bluetooth
|
||||
{
|
||||
public:
|
||||
void setup() {}
|
||||
void shutdown() {}
|
||||
void startDisabled() {}
|
||||
void resumeAdvertising() {}
|
||||
void clearBonds() {}
|
||||
bool isConnected() { return false; }
|
||||
int getRssi() { return 0; }
|
||||
void sendLog(const uint8_t *, size_t) {}
|
||||
};
|
||||
805
src/platform/nrf54l15/NRF54L15Bluetooth.cpp
Normal file
805
src/platform/nrf54l15/NRF54L15Bluetooth.cpp
Normal file
@@ -0,0 +1,805 @@
|
||||
// NRF54L15Bluetooth.cpp — Zephyr BLE GATT peripheral for Meshtastic nRF54L15
|
||||
//
|
||||
// GATT profile (identical UUIDs to the nRF52 / NimBLE implementations):
|
||||
// Service: 6ba1b218-15a8-461f-9fa8-5dcae273eafd
|
||||
// fromNum: ed9da18c-a800-4f66-a670-aa7547e34453 READ | NOTIFY
|
||||
// fromRadio: 2c55e69e-4993-11ed-b878-0242ac120002 READ
|
||||
// toRadio: f75c76d2-129e-4dad-a1dd-7866124401e7 WRITE
|
||||
// logRadio: 5a3d6e49-06e6-4423-9944-e9de8cdf9547 READ | NOTIFY | INDICATE
|
||||
//
|
||||
// Threading model:
|
||||
// - BT RX thread: connected_cb / disconnected_cb / GATT read_/write_
|
||||
// callbacks
|
||||
// - Meshtastic OSThread scheduler (cooperative, main thread):
|
||||
// BleDeferredThread
|
||||
// polls pendingToRadio and runs the zombie-connection watchdog every 100 ms
|
||||
// - PhoneAPI::onNowHasData: sends fromNum notify synchronously from whichever
|
||||
// thread pushed the packet (bt_gatt_notify is thread-safe in Zephyr)
|
||||
// - active_conn protected by ble_mutex where needed
|
||||
|
||||
#include "NRF54L15Bluetooth.h"
|
||||
#include "BluetoothCommon.h"
|
||||
#include "BluetoothStatus.h"
|
||||
#include "PowerFSM.h"
|
||||
#include "concurrency/OSThread.h"
|
||||
#include "configuration.h"
|
||||
#include "main.h"
|
||||
#include "mesh/PhoneAPI.h"
|
||||
#include "mesh/mesh-pb-constants.h"
|
||||
|
||||
#include <zephyr/bluetooth/bluetooth.h>
|
||||
#include <zephyr/bluetooth/conn.h>
|
||||
#include <zephyr/bluetooth/gatt.h>
|
||||
#include <zephyr/bluetooth/hci.h>
|
||||
#include <zephyr/bluetooth/uuid.h>
|
||||
#include <zephyr/kernel.h>
|
||||
#include <zephyr/settings/settings.h>
|
||||
#include <zephyr/sys/reboot.h>
|
||||
|
||||
// ── UUID definitions (little-endian per Bluetooth spec)
|
||||
// ─────────────────────── Syntax: replace hyphens with commas, prefix 0x —
|
||||
// matches BT_UUID_128_ENCODE doc.
|
||||
|
||||
#define MESH_SVC_UUID_VAL BT_UUID_128_ENCODE(0x6ba1b218, 0x15a8, 0x461f, 0x9fa8, 0x5dcae273eafd)
|
||||
#define FROMNUM_UUID_VAL BT_UUID_128_ENCODE(0xed9da18c, 0xa800, 0x4f66, 0xa670, 0xaa7547e34453)
|
||||
#define FROMRADIO_UUID_VAL BT_UUID_128_ENCODE(0x2c55e69e, 0x4993, 0x11ed, 0xb878, 0x0242ac120002)
|
||||
#define TORADIO_UUID_VAL BT_UUID_128_ENCODE(0xf75c76d2, 0x129e, 0x4dad, 0xa1dd, 0x7866124401e7)
|
||||
#define LOGRADIO_UUID_VAL BT_UUID_128_ENCODE(0x5a3d6e49, 0x06e6, 0x4423, 0x9944, 0xe9de8cdf9547)
|
||||
|
||||
static const struct bt_uuid_128 mesh_svc_uuid = BT_UUID_INIT_128(MESH_SVC_UUID_VAL);
|
||||
static const struct bt_uuid_128 fromnum_uuid = BT_UUID_INIT_128(FROMNUM_UUID_VAL);
|
||||
static const struct bt_uuid_128 fromradio_uuid = BT_UUID_INIT_128(FROMRADIO_UUID_VAL);
|
||||
static const struct bt_uuid_128 toradio_uuid = BT_UUID_INIT_128(TORADIO_UUID_VAL);
|
||||
static const struct bt_uuid_128 logradio_uuid = BT_UUID_INIT_128(LOGRADIO_UUID_VAL);
|
||||
|
||||
// ── Module state ─────────────────────────────────────────────────────────────
|
||||
|
||||
static struct bt_conn *active_conn = nullptr;
|
||||
static K_MUTEX_DEFINE(ble_mutex);
|
||||
|
||||
// Take a reference to active_conn under ble_mutex. Returns nullptr if there is
|
||||
// no active connection. Caller MUST bt_conn_unref() when done.
|
||||
//
|
||||
// Reading `active_conn` outside this lock races with disconnected_cb which can
|
||||
// unref + null it on the BT RX thread — touching the freed pointer (even just
|
||||
// to bt_conn_ref it) is a use-after-free.
|
||||
static struct bt_conn *acquire_active_conn()
|
||||
{
|
||||
struct bt_conn *conn = nullptr;
|
||||
k_mutex_lock(&ble_mutex, K_FOREVER);
|
||||
if (active_conn) {
|
||||
conn = bt_conn_ref(active_conn);
|
||||
}
|
||||
k_mutex_unlock(&ble_mutex);
|
||||
return conn;
|
||||
}
|
||||
|
||||
static bool bt_initialized = false; // bt_enable() called at most once
|
||||
static bool ble_enabled = false; // set by setup(), cleared by shutdown()
|
||||
|
||||
// Forward declarations — BT_GATT_SERVICE_DEFINE(mesh_svc, ...) is below, but
|
||||
// read_fromradio() (defined earlier) needs to reference the service to notify
|
||||
// on fromNum after each non-empty read.
|
||||
#define FROMNUM_ATTR_IDX 2
|
||||
#define LOGRADIO_ATTR_IDX 9
|
||||
extern const struct bt_gatt_service_static mesh_svc;
|
||||
|
||||
static void start_advertising(); // forward declaration (defined in advertising
|
||||
// section below)
|
||||
|
||||
// Work item for advertising restart after disconnect.
|
||||
//
|
||||
// disconnected_cb runs on the BT RX thread (the same thread that processes
|
||||
// HCI Command Complete events). Calling bt_le_adv_start() →
|
||||
// bt_hci_cmd_send_sync() directly from that thread deadlocks: the thread blocks
|
||||
// on k_sem_take waiting for Command Complete, but it is the very thread that
|
||||
// would process it. After 10 s the host panics with "Controller unresponsive,
|
||||
// opcode 0x2006 timeout".
|
||||
//
|
||||
// Fix: submit a k_work item. The system workqueue runs bt_adv_restart_work_fn
|
||||
// on its own thread → no deadlock.
|
||||
static struct k_work adv_restart_work;
|
||||
|
||||
static void adv_restart_work_fn(struct k_work *work)
|
||||
{
|
||||
if (ble_enabled) {
|
||||
start_advertising();
|
||||
}
|
||||
}
|
||||
|
||||
// CCC state: 0=off, BT_GATT_CCC_NOTIFY=notify, BT_GATT_CCC_INDICATE=indicate
|
||||
static uint16_t fromnum_ccc_val = 0;
|
||||
static uint16_t logradio_ccc_val = 0;
|
||||
|
||||
// Scratch buffers — only one BLE operation at a time
|
||||
static uint8_t fromRadioBytes[meshtastic_FromRadio_size];
|
||||
static size_t fromRadioLen = 0;
|
||||
static uint8_t toRadioBytes[meshtastic_ToRadio_size];
|
||||
static uint8_t lastToRadio[MAX_TO_FROM_RADIO_SIZE];
|
||||
static uint32_t fromNumValue = 0;
|
||||
|
||||
// Deferred ToRadio processing
|
||||
//
|
||||
// write_toradio() runs on the BT RX workqueue thread (6 KB stack). Calling
|
||||
// phoneAPI->handleToRadio() directly triggers handleStartConfig →
|
||||
// getFiles("/", 10) → nanopb encode, which overflows the stack on the exact
|
||||
// "Client wants config" write. Instead we copy the payload into a pending
|
||||
// buffer under a mutex and let BleDeferredThread (running on the Meshtastic
|
||||
// OSThread scheduler, 24 KB stack) do the actual call outside the lock.
|
||||
//
|
||||
// The mutex makes the producer/consumer handoff race-free — producer may
|
||||
// overwrite a pending buffer the consumer hasn't read yet (dropped packet),
|
||||
// but partial reads / torn writes are impossible.
|
||||
K_MUTEX_DEFINE(pendingToRadioMutex);
|
||||
static uint8_t pendingToRadioBuf[MAX_TO_FROM_RADIO_SIZE];
|
||||
static size_t pendingToRadioLen = 0;
|
||||
static bool pendingToRadio = false;
|
||||
|
||||
// Zombie-connection watchdog state.
|
||||
//
|
||||
// The nRF54L15 Zephyr 4.2.1 SW-LL occasionally fails to forward an
|
||||
// LE Disconnection Complete event to the host: when iOS tears down the link
|
||||
// (either explicitly by the user or via supervision timeout), the LL layer
|
||||
// drops the connection but disconnected_cb never fires, active_conn stays
|
||||
// non-null and advertising never restarts — the device vanishes from scans
|
||||
// until power cycle. Track the connected timestamp and the last time we
|
||||
// observed ATT traffic; a long ATT idle on an "active" connection means we
|
||||
// are zombied. A cold reboot is the only path that reliably recovers (any
|
||||
// bt_hci_cmd_send_sync after this state, e.g. bt_le_adv_start or
|
||||
// bt_conn_disconnect, hangs in k_sem_take and later panics with "Controller
|
||||
// unresponsive, opcode 0x2006 timeout").
|
||||
static uint32_t connect_time_ms = 0;
|
||||
static uint32_t last_att_time_ms = 0;
|
||||
|
||||
// ── BluetoothPhoneAPI
|
||||
// ─────────────────────────────────────────────────────────
|
||||
|
||||
class BluetoothPhoneAPI : public PhoneAPI
|
||||
{
|
||||
virtual void onNowHasData(uint32_t fromRadioNum) override;
|
||||
virtual bool checkIsConnected() override;
|
||||
|
||||
public:
|
||||
BluetoothPhoneAPI() { api_type = TYPE_BLE; }
|
||||
};
|
||||
|
||||
static BluetoothPhoneAPI *phoneAPI = nullptr;
|
||||
|
||||
// ── CCC change callbacks
|
||||
// ──────────────────────────────────────────────────────
|
||||
|
||||
static void fromnum_ccc_changed(const struct bt_gatt_attr *attr, uint16_t value)
|
||||
{
|
||||
fromnum_ccc_val = value;
|
||||
LOG_INFO("BLE fromNum CCC: %u", value);
|
||||
}
|
||||
|
||||
static void logradio_ccc_changed(const struct bt_gatt_attr *attr, uint16_t value)
|
||||
{
|
||||
logradio_ccc_val = value;
|
||||
LOG_INFO("BLE logRadio CCC: %u", value);
|
||||
}
|
||||
|
||||
// ── GATT attribute callbacks
|
||||
// ──────────────────────────────────────────────────
|
||||
|
||||
static ssize_t read_fromnum(struct bt_conn *conn, const struct bt_gatt_attr *attr, void *buf, uint16_t len, uint16_t offset)
|
||||
{
|
||||
LOG_INFO("GATT read_fromnum: fromNum=%u offset=%u", fromNumValue, offset);
|
||||
return bt_gatt_attr_read(conn, attr, buf, len, offset, &fromNumValue, sizeof(fromNumValue));
|
||||
}
|
||||
|
||||
static ssize_t read_fromradio(struct bt_conn *conn, const struct bt_gatt_attr *attr, void *buf, uint16_t len, uint16_t offset)
|
||||
{
|
||||
if (offset == 0) {
|
||||
// First chunk: pull the next packet from the queue.
|
||||
// Subsequent chunks (offset > 0) are ATT_READ_BLOB continuations of the
|
||||
// same value and must reuse fromRadioBytes untouched.
|
||||
fromRadioLen = phoneAPI ? phoneAPI->getFromRadio(fromRadioBytes) : 0;
|
||||
LOG_DEBUG("GATT read_fromradio len=%u", (unsigned)fromRadioLen);
|
||||
}
|
||||
last_att_time_ms = k_uptime_get_32();
|
||||
return bt_gatt_attr_read(conn, attr, buf, len, offset, fromRadioBytes, fromRadioLen);
|
||||
}
|
||||
|
||||
static ssize_t read_logradio(struct bt_conn *conn, const struct bt_gatt_attr *attr, void *buf, uint16_t len, uint16_t offset)
|
||||
{
|
||||
// logRadio is write-only from the device side (notify/indicate).
|
||||
// Return an empty read so GATT discovery doesn't fail with NOT_PERMITTED.
|
||||
return bt_gatt_attr_read(conn, attr, buf, len, offset, NULL, 0);
|
||||
}
|
||||
|
||||
static ssize_t write_toradio(struct bt_conn *conn, const struct bt_gatt_attr *attr, const void *buf, uint16_t len,
|
||||
uint16_t offset, uint8_t flags)
|
||||
{
|
||||
// Writes >MTU-3 arrive here with offset=0 and
|
||||
// flags=BT_GATT_WRITE_FLAG_EXECUTE after Zephyr reassembles the ATT Prepare
|
||||
// Write fragments (CONFIG_BT_ATT_PREPARE_COUNT>0). Single writes arrive with
|
||||
// flags=0.
|
||||
LOG_DEBUG("GATT write_toradio len=%u flags=0x%x", len, flags);
|
||||
if (offset != 0) {
|
||||
return BT_GATT_ERR(BT_ATT_ERR_INVALID_OFFSET);
|
||||
}
|
||||
// Reject any write that won't fit in the dedup buffer (lastToRadio) or the
|
||||
// pending handoff buffer (pendingToRadioBuf), both sized
|
||||
// MAX_TO_FROM_RADIO_SIZE. Returning success while silently dropping a
|
||||
// payload would let the phone believe a config write was applied.
|
||||
if (len > sizeof(toRadioBytes) || len > MAX_TO_FROM_RADIO_SIZE) {
|
||||
return BT_GATT_ERR(BT_ATT_ERR_INVALID_ATTRIBUTE_LEN);
|
||||
}
|
||||
|
||||
// Deduplicate — drop packet if identical to the last one we processed
|
||||
if (memcmp(lastToRadio, buf, len) != 0) {
|
||||
memcpy(lastToRadio, buf, len);
|
||||
if (len < MAX_TO_FROM_RADIO_SIZE) {
|
||||
memset(lastToRadio + len, 0, MAX_TO_FROM_RADIO_SIZE - len);
|
||||
}
|
||||
// Defer handleToRadio() to BleDeferredThread (24 KB stack).
|
||||
// Running it here on bt_workq (6 KB) overflows during handleStartConfig.
|
||||
// Always overwrite pending — we already dedup'd above via lastToRadio,
|
||||
// so any new write here is genuinely new data that must be delivered.
|
||||
k_mutex_lock(&pendingToRadioMutex, K_FOREVER);
|
||||
memcpy(pendingToRadioBuf, buf, len);
|
||||
pendingToRadioLen = len;
|
||||
pendingToRadio = true;
|
||||
k_mutex_unlock(&pendingToRadioMutex);
|
||||
}
|
||||
last_att_time_ms = k_uptime_get_32();
|
||||
return (ssize_t)len;
|
||||
}
|
||||
|
||||
// ── GATT service definition (static, linked at compile time)
|
||||
// ──────────────────
|
||||
//
|
||||
// Attribute indices (0-based):
|
||||
// [0] Primary Service declaration
|
||||
// [1] fromNum characteristic declaration
|
||||
// [2] fromNum value ← notify target (FROMNUM_ATTR_IDX)
|
||||
// [3] fromNum CCC descriptor
|
||||
// [4] fromRadio characteristic declaration
|
||||
// [5] fromRadio value
|
||||
// [6] toRadio characteristic declaration
|
||||
// [7] toRadio value
|
||||
// [8] logRadio characteristic declaration
|
||||
// [9] logRadio value ← notify target (LOGRADIO_ATTR_IDX)
|
||||
// [10] logRadio CCC descriptor
|
||||
|
||||
// All user characteristics require authenticated encryption (MITM passkey)
|
||||
// before the client can read/write. This mirrors the nrf52
|
||||
// SECMODE_ENC_WITH_MITM service permission. The stack returns "Insufficient
|
||||
// Authentication" on the first access attempt, prompting the client to pair
|
||||
// with the configured PIN.
|
||||
#define MESH_PERM_READ (BT_GATT_PERM_READ | BT_GATT_PERM_READ_AUTHEN)
|
||||
#define MESH_PERM_WRITE (BT_GATT_PERM_WRITE | BT_GATT_PERM_WRITE_AUTHEN)
|
||||
|
||||
BT_GATT_SERVICE_DEFINE(mesh_svc, BT_GATT_PRIMARY_SERVICE(&mesh_svc_uuid.uuid),
|
||||
|
||||
// fromNum: READ | NOTIFY — packet-counter triggers phone to read fromRadio
|
||||
BT_GATT_CHARACTERISTIC(&fromnum_uuid.uuid, BT_GATT_CHRC_READ | BT_GATT_CHRC_NOTIFY, MESH_PERM_READ,
|
||||
read_fromnum, NULL, &fromNumValue),
|
||||
BT_GATT_CCC(fromnum_ccc_changed, MESH_PERM_READ | MESH_PERM_WRITE),
|
||||
|
||||
// fromRadio: READ — phone polls this after receiving a fromNum notification
|
||||
BT_GATT_CHARACTERISTIC(&fromradio_uuid.uuid, BT_GATT_CHRC_READ, MESH_PERM_READ, read_fromradio, NULL,
|
||||
NULL),
|
||||
|
||||
// toRadio: WRITE — phone sends protobuf packets to the device
|
||||
BT_GATT_CHARACTERISTIC(&toradio_uuid.uuid, BT_GATT_CHRC_WRITE, MESH_PERM_WRITE, NULL, write_toradio, NULL),
|
||||
|
||||
// logRadio: READ | NOTIFY | INDICATE — log stream to phone when connected
|
||||
BT_GATT_CHARACTERISTIC(&logradio_uuid.uuid,
|
||||
BT_GATT_CHRC_READ | BT_GATT_CHRC_NOTIFY | BT_GATT_CHRC_INDICATE, MESH_PERM_READ,
|
||||
read_logradio, NULL, NULL),
|
||||
BT_GATT_CCC(logradio_ccc_changed, MESH_PERM_READ | MESH_PERM_WRITE), );
|
||||
|
||||
// ── Advertising
|
||||
// ───────────────────────────────────────────────────────────────
|
||||
//
|
||||
// Use legacy advertising (bt_le_adv_start / HCI 0x2006 path).
|
||||
//
|
||||
// History: we previously used bt_le_ext_adv_create (true extended advertising)
|
||||
// because bt_le_adv_start() with CONFIG_BT_EXT_ADV=y was translated internally
|
||||
// to the extended HCI path with LEGACY-bit (0x2036), which produced
|
||||
// non-connectable PDUs on the nRF54L15 SW-LL. The true extended path
|
||||
// (0x203x, AUX_ADV_IND) was connectable but caused two problems:
|
||||
// 1. iOS CoreBluetooth does not reliably complete GATT after connecting via
|
||||
// extended advertising (zero ATT PDUs observed in all test sessions).
|
||||
// 2. After each connection the controller auto-stops the advertising set, and
|
||||
// the subsequent bt_le_ext_adv_delete() sends LE Remove Advertising Set
|
||||
// (0x203c) which times out → kernel oops at hci_core.c:506.
|
||||
//
|
||||
// With CONFIG_BT_EXT_ADV=n the host uses pure legacy HCI commands — the same
|
||||
// path Nordic NCS uses in all nRF54L15 examples (peripheral_uart,
|
||||
// peripheral_lbs) and which is universally iOS-compatible. The legacy data
|
||||
// payload is 31 bytes:
|
||||
// FLAGS (3B) + UUID128 (18B) = 21B in adv; NAME in scan-response (17B).
|
||||
|
||||
static void start_advertising()
|
||||
{
|
||||
// IMPORTANT: BT_DATA_BYTES() uses C99 compound literals that GCC C++ treats
|
||||
// as temporaries; with -Os the compiler may elide writes, leaving stack
|
||||
// uninitialized. Use static const arrays for stable data (flags, UUID)
|
||||
// and a runtime pointer for the dynamic device name.
|
||||
static const uint8_t adv_flags_val[] = {BT_LE_AD_GENERAL | BT_LE_AD_NO_BREDR};
|
||||
static const uint8_t adv_uuid128_val[] = {MESH_SVC_UUID_VAL};
|
||||
|
||||
const char *name = bt_get_name();
|
||||
size_t full_name_len = strlen(name);
|
||||
|
||||
// Legacy scan-response payload is 31 bytes total. Each AD entry costs 2
|
||||
// bytes (length + type), leaving 29 bytes for the name. With
|
||||
// CONFIG_BT_DEVICE_NAME_MAX=32 the name can exceed that — truncate and
|
||||
// mark as SHORTENED so bt_le_adv_start() doesn't reject the payload.
|
||||
constexpr size_t LEGACY_SCAN_RSP_NAME_MAX = 31 - 2;
|
||||
bool name_shortened = full_name_len > LEGACY_SCAN_RSP_NAME_MAX;
|
||||
uint8_t name_len = (uint8_t)(name_shortened ? LEGACY_SCAN_RSP_NAME_MAX : full_name_len);
|
||||
|
||||
// Primary advertising data: FLAGS + Meshtastic service UUID128 (21 bytes
|
||||
// total)
|
||||
struct bt_data ad[] = {
|
||||
{BT_DATA_FLAGS, sizeof(adv_flags_val), adv_flags_val},
|
||||
{BT_DATA_UUID128_ALL, sizeof(adv_uuid128_val), adv_uuid128_val},
|
||||
};
|
||||
// Scan response: device name (discovered after scan request)
|
||||
struct bt_data sd[] = {
|
||||
{(uint8_t)(name_shortened ? BT_DATA_NAME_SHORTENED : BT_DATA_NAME_COMPLETE), name_len, (const uint8_t *)name},
|
||||
};
|
||||
|
||||
// BT_LE_ADV_OPT_CONN = connectable legacy ADV_IND + stops after first
|
||||
// connection (replaces deprecated
|
||||
// CONNECTABLE|ONE_TIME in Zephyr 4.2.1;
|
||||
// BT_LE_ADV_OPT_CONN = BIT(0)|BIT(1))
|
||||
// BT_LE_ADV_OPT_USE_IDENTITY = use static random identity address (stable
|
||||
// across reboots) Advertising restart after disconnect is via
|
||||
// adv_restart_work (system workqueue) so calling bt_le_adv_start() from the
|
||||
// BT RX thread context is avoided.
|
||||
int err = bt_le_adv_start(BT_LE_ADV_PARAM(BT_LE_ADV_OPT_CONN | BT_LE_ADV_OPT_USE_IDENTITY, BT_GAP_ADV_FAST_INT_MIN_2,
|
||||
BT_GAP_ADV_FAST_INT_MAX_2, NULL),
|
||||
ad, ARRAY_SIZE(ad), sd, ARRAY_SIZE(sd));
|
||||
|
||||
if (err == -EALREADY) {
|
||||
return;
|
||||
}
|
||||
if (err) {
|
||||
LOG_WARN("BLE adv start failed: %d", err);
|
||||
} else {
|
||||
LOG_INFO("BLE advertising as '%s'", bt_get_name());
|
||||
}
|
||||
}
|
||||
|
||||
static void stop_advertising()
|
||||
{
|
||||
bt_le_adv_stop();
|
||||
}
|
||||
|
||||
// ── Connection callbacks
|
||||
// ──────────────────────────────────────────────────────
|
||||
|
||||
static void connected_cb(struct bt_conn *conn, uint8_t err)
|
||||
{
|
||||
if (err) {
|
||||
LOG_WARN("BLE connection failed, err=0x%02x", err);
|
||||
return;
|
||||
}
|
||||
|
||||
k_mutex_lock(&ble_mutex, K_FOREVER);
|
||||
active_conn = bt_conn_ref(conn);
|
||||
k_mutex_unlock(&ble_mutex);
|
||||
|
||||
memset(lastToRadio, 0, sizeof(lastToRadio));
|
||||
connect_time_ms = k_uptime_get_32();
|
||||
last_att_time_ms = connect_time_ms;
|
||||
|
||||
char addr[BT_ADDR_LE_STR_LEN];
|
||||
bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));
|
||||
LOG_INFO("BLE connected: %s", addr);
|
||||
|
||||
meshtastic::BluetoothStatus newStatus(meshtastic::BluetoothStatus::ConnectionState::CONNECTED);
|
||||
bluetoothStatus->updateStatus(&newStatus);
|
||||
|
||||
// nRF54L15-DK has no screen — cannot display a PIN to the user.
|
||||
// Requesting BT_SECURITY_L2 causes the OS to show a pairing dialog that
|
||||
// the user dismisses, triggering disconnect + advertising restart failure.
|
||||
// Skip security negotiation; the Meshtastic app works over plain GATT.
|
||||
// (Security can be re-enabled once a display or NFC OOB path is available.)
|
||||
}
|
||||
|
||||
static void disconnected_cb(struct bt_conn *conn, uint8_t reason)
|
||||
{
|
||||
LOG_INFO("BLE disconnected, reason=0x%02x", reason);
|
||||
|
||||
k_mutex_lock(&ble_mutex, K_FOREVER);
|
||||
if (active_conn) {
|
||||
bt_conn_unref(active_conn);
|
||||
active_conn = nullptr;
|
||||
}
|
||||
k_mutex_unlock(&ble_mutex);
|
||||
|
||||
fromnum_ccc_val = 0;
|
||||
logradio_ccc_val = 0;
|
||||
connect_time_ms = 0;
|
||||
last_att_time_ms = 0;
|
||||
|
||||
if (phoneAPI) {
|
||||
phoneAPI->close();
|
||||
}
|
||||
memset(lastToRadio, 0, sizeof(lastToRadio));
|
||||
|
||||
meshtastic::BluetoothStatus newStatus(meshtastic::BluetoothStatus::ConnectionState::DISCONNECTED);
|
||||
bluetoothStatus->updateStatus(&newStatus);
|
||||
|
||||
// Schedule advertising restart via work queue — NOT from this callback
|
||||
// directly. disconnected_cb runs on the BT RX thread; calling
|
||||
// bt_le_adv_start() here would deadlock (see adv_restart_work comment above).
|
||||
if (ble_enabled) {
|
||||
k_work_submit(&adv_restart_work);
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(CONFIG_BT_SMP)
|
||||
static void security_changed_cb(struct bt_conn *conn, bt_security_t level, enum bt_security_err err)
|
||||
{
|
||||
if (err == BT_SECURITY_ERR_PIN_OR_KEY_MISSING) {
|
||||
// Phone has a stale bond (device was wiped/reflashed). Unpair the stale
|
||||
// entry so the phone re-pairs cleanly on the next connection attempt.
|
||||
LOG_WARN("BLE stale bond detected (key missing) — unpairing");
|
||||
bt_unpair(BT_ID_DEFAULT, bt_conn_get_dst(conn));
|
||||
bt_conn_disconnect(conn, BT_HCI_ERR_AUTH_FAIL);
|
||||
} else if (err) {
|
||||
LOG_WARN("BLE security change failed: level=%d err=%d", (int)level, (int)err);
|
||||
} else {
|
||||
LOG_INFO("BLE security level %d established", (int)level);
|
||||
}
|
||||
}
|
||||
#endif /* CONFIG_BT_SMP */
|
||||
|
||||
BT_CONN_CB_DEFINE(conn_callbacks) = {
|
||||
.connected = connected_cb,
|
||||
.disconnected = disconnected_cb,
|
||||
#if defined(CONFIG_BT_SMP)
|
||||
.security_changed = security_changed_cb,
|
||||
#endif
|
||||
};
|
||||
|
||||
// ── Pairing / auth callbacks
|
||||
// ──────────────────────────────────────────────────
|
||||
|
||||
#if defined(CONFIG_BT_SMP)
|
||||
static uint32_t configuredPasskey;
|
||||
|
||||
static void auth_passkey_display(struct bt_conn *conn, unsigned int passkey)
|
||||
{
|
||||
char passkey_str[7];
|
||||
snprintf(passkey_str, sizeof(passkey_str), "%06u", passkey);
|
||||
configuredPasskey = passkey;
|
||||
LOG_INFO("BLE pairing PIN: %s", passkey_str);
|
||||
powerFSM.trigger(EVENT_BLUETOOTH_PAIR);
|
||||
|
||||
std::string textkey(passkey_str);
|
||||
meshtastic::BluetoothStatus pairingStatus(textkey);
|
||||
bluetoothStatus->updateStatus(&pairingStatus);
|
||||
}
|
||||
|
||||
static void auth_cancel(struct bt_conn *conn)
|
||||
{
|
||||
LOG_WARN("BLE pairing cancelled");
|
||||
}
|
||||
|
||||
static struct bt_conn_auth_cb auth_cb = {
|
||||
.passkey_display = auth_passkey_display,
|
||||
.passkey_entry = NULL,
|
||||
.cancel = auth_cancel,
|
||||
};
|
||||
|
||||
static void pairing_complete_cb(struct bt_conn *conn, bool bonded)
|
||||
{
|
||||
LOG_INFO("BLE pairing complete, bonded=%d", (int)bonded);
|
||||
meshtastic::BluetoothStatus newStatus(meshtastic::BluetoothStatus::ConnectionState::CONNECTED);
|
||||
bluetoothStatus->updateStatus(&newStatus);
|
||||
}
|
||||
|
||||
static void pairing_failed_cb(struct bt_conn *conn, enum bt_security_err reason)
|
||||
{
|
||||
LOG_WARN("BLE pairing failed, reason=%d", (int)reason);
|
||||
meshtastic::BluetoothStatus newStatus(meshtastic::BluetoothStatus::ConnectionState::DISCONNECTED);
|
||||
bluetoothStatus->updateStatus(&newStatus);
|
||||
}
|
||||
|
||||
static struct bt_conn_auth_info_cb auth_info_cb = {
|
||||
.pairing_complete = pairing_complete_cb,
|
||||
.pairing_failed = pairing_failed_cb,
|
||||
};
|
||||
#endif /* CONFIG_BT_SMP */
|
||||
|
||||
// ── BluetoothPhoneAPI methods
|
||||
// ─────────────────────────────────────────────────
|
||||
|
||||
void BluetoothPhoneAPI::onNowHasData(uint32_t fromRadioNum)
|
||||
{
|
||||
PhoneAPI::onNowHasData(fromRadioNum);
|
||||
fromNumValue = fromRadioNum;
|
||||
|
||||
if (!(fromnum_ccc_val & BT_GATT_CCC_NOTIFY))
|
||||
return;
|
||||
|
||||
// active_conn may be torn down on another thread while we're dispatching
|
||||
// this notify — acquire under ble_mutex so disconnected_cb can't free the
|
||||
// conn between the null check and bt_conn_ref.
|
||||
struct bt_conn *conn = acquire_active_conn();
|
||||
if (!conn)
|
||||
return;
|
||||
bt_gatt_notify(conn, &mesh_svc.attrs[FROMNUM_ATTR_IDX], &fromNumValue, sizeof(fromNumValue));
|
||||
bt_conn_unref(conn);
|
||||
}
|
||||
|
||||
bool BluetoothPhoneAPI::checkIsConnected()
|
||||
{
|
||||
return active_conn != nullptr;
|
||||
}
|
||||
|
||||
// ── Deferred ToRadio processor + zombie-connection watchdog ──────────────────
|
||||
//
|
||||
// write_toradio() runs on the BT RX workqueue thread (CONFIG_BT_RX_STACK_SIZE)
|
||||
// and cannot execute phoneAPI->handleToRadio() directly: handleStartConfig
|
||||
// recurses through nanopb encode + state machine init and overflows the RX
|
||||
// stack. This thread runs on the Meshtastic OSThread scheduler (24 KB stack),
|
||||
// picks up the pending ToRadio buffer flagged by write_toradio(), and calls
|
||||
// handleToRadio() with plenty of headroom.
|
||||
//
|
||||
// Real-time fromNum notifications are sent synchronously from
|
||||
// BluetoothPhoneAPI::onNowHasData() (called by PhoneAPI when new data is
|
||||
// queued).
|
||||
//
|
||||
// Zombie-connection detection has two tiers:
|
||||
//
|
||||
// (1) Liveness probe. After IDLE_BEFORE_PROBE_MS without ATT traffic, send
|
||||
// a bt_gatt_notify to fromNum every PROBE_INTERVAL_MS. If the
|
||||
// controller replies -ENOTCONN the LL link is definitely dead but the
|
||||
// host didn't forward LE Disconnection Complete → reboot. We avoid
|
||||
// probing during normal activity so iOS isn't woken up unnecessarily
|
||||
// (each probe wakes iOS → triggers a zero-byte FromRadio drain).
|
||||
//
|
||||
// (2) Hard watchdog. Absolute HARD_WATCHDOG_MS ceiling on ATT idle as a
|
||||
// fallback if probes somehow don't detect the zombie.
|
||||
class BleDeferredThread : public concurrency::OSThread
|
||||
{
|
||||
static constexpr uint32_t IDLE_BEFORE_PROBE_MS = 30000; // 30 s: start probing
|
||||
static constexpr uint32_t PROBE_INTERVAL_MS = 5000; // 5 s: between probes
|
||||
static constexpr uint32_t HARD_WATCHDOG_MS = 60000; // 1 min: last resort
|
||||
|
||||
uint32_t last_probe_ms = 0;
|
||||
|
||||
public:
|
||||
BleDeferredThread() : concurrency::OSThread("BleDeferred") {}
|
||||
|
||||
protected:
|
||||
int32_t runOnce() override
|
||||
{
|
||||
// Snapshot the pending ToRadio buffer under the mutex, then release
|
||||
// the lock before calling into handleToRadio (which can be slow and
|
||||
// must not block the BT RX thread producer).
|
||||
uint8_t buf[MAX_TO_FROM_RADIO_SIZE];
|
||||
size_t n = 0;
|
||||
bool have_pending = false;
|
||||
k_mutex_lock(&pendingToRadioMutex, K_FOREVER);
|
||||
if (pendingToRadio) {
|
||||
memcpy(buf, pendingToRadioBuf, pendingToRadioLen);
|
||||
n = pendingToRadioLen;
|
||||
pendingToRadio = false;
|
||||
have_pending = true;
|
||||
}
|
||||
k_mutex_unlock(&pendingToRadioMutex);
|
||||
if (have_pending && phoneAPI) {
|
||||
phoneAPI->handleToRadio(buf, n);
|
||||
}
|
||||
|
||||
// Take a reference to active_conn so it can't be freed underneath us
|
||||
// if disconnected_cb fires on another thread while we're dispatching.
|
||||
struct bt_conn *conn = acquire_active_conn();
|
||||
if (!conn || connect_time_ms == 0) {
|
||||
if (conn)
|
||||
bt_conn_unref(conn);
|
||||
last_probe_ms = 0;
|
||||
return 100;
|
||||
}
|
||||
|
||||
uint32_t now = k_uptime_get_32();
|
||||
uint32_t att_idle = now - last_att_time_ms;
|
||||
|
||||
// Liveness probe — only when ATT has been quiet for a while.
|
||||
if (att_idle > IDLE_BEFORE_PROBE_MS && (now - last_probe_ms) >= PROBE_INTERVAL_MS &&
|
||||
(fromnum_ccc_val & BT_GATT_CCC_NOTIFY)) {
|
||||
last_probe_ms = now;
|
||||
int err = bt_gatt_notify(conn, &mesh_svc.attrs[FROMNUM_ATTR_IDX], &fromNumValue, sizeof(fromNumValue));
|
||||
if (err == -ENOTCONN) {
|
||||
LOG_WARN("BLE zombie (probe ENOTCONN); rebooting");
|
||||
bt_conn_unref(conn);
|
||||
k_sleep(K_MSEC(50)); // flush log
|
||||
sys_reboot(SYS_REBOOT_COLD);
|
||||
}
|
||||
}
|
||||
bt_conn_unref(conn);
|
||||
|
||||
// Hard ceiling — last-resort reboot if probes miss the zombie.
|
||||
if (att_idle > HARD_WATCHDOG_MS && (now - connect_time_ms) > HARD_WATCHDOG_MS) {
|
||||
LOG_WARN("BLE zombie (hard watchdog %us); rebooting", HARD_WATCHDOG_MS / 1000);
|
||||
k_sleep(K_MSEC(50));
|
||||
sys_reboot(SYS_REBOOT_COLD);
|
||||
}
|
||||
return 100;
|
||||
}
|
||||
};
|
||||
|
||||
static BleDeferredThread *bleDeferredThread = nullptr;
|
||||
|
||||
// ── BT stack pre-initializer (call from main thread before OSThreads start) ──
|
||||
//
|
||||
// bt_enable() requires substantially more stack than a Meshtastic OSThread
|
||||
// (PowerFSMThread) provides — calling it there causes a stack overflow.
|
||||
// Call this from nrf54l15Setup() (main Zephyr thread, CONFIG_MAIN_STACK_SIZE)
|
||||
// so that by the time NRF54L15Bluetooth::setup() runs from PowerFSMThread,
|
||||
// bt_initialized is already true and bt_enable() is skipped.
|
||||
|
||||
void nrf54l15_bt_preinit()
|
||||
{
|
||||
if (!bt_initialized) {
|
||||
int err = bt_enable(NULL);
|
||||
if (err) {
|
||||
LOG_ERROR("BLE pre-init failed: %d", err);
|
||||
return;
|
||||
}
|
||||
bt_initialized = true;
|
||||
LOG_INFO("BLE stack pre-initialized on main thread");
|
||||
|
||||
// Phase 7: load bonding keys from LittleFS (/lfs/bt_settings).
|
||||
// LittleFS is already mounted by fsInit() before nrf54l15Setup() runs.
|
||||
// On first boot the file doesn't exist — settings_load() returns 0 (OK).
|
||||
// On subsequent boots, previously bonded peers are restored so the
|
||||
// phone can reconnect without re-pairing.
|
||||
err = settings_load();
|
||||
if (err) {
|
||||
LOG_WARN("settings_load failed: %d (OK on first boot)", err);
|
||||
} else {
|
||||
LOG_INFO("BT settings loaded from /lfs/bt_settings");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// ── NRF54L15Bluetooth public methods ─────────────────────────────────────────
|
||||
|
||||
// Shared init: idempotent setup of work item, OSThread, auth callbacks,
|
||||
// bt_enable, and device name. Leaves advertising control to the caller.
|
||||
static bool nrf54l15_bt_init_common()
|
||||
{
|
||||
k_work_init(&adv_restart_work, adv_restart_work_fn);
|
||||
|
||||
if (!bleDeferredThread) {
|
||||
bleDeferredThread = new BleDeferredThread();
|
||||
}
|
||||
|
||||
if (!phoneAPI) {
|
||||
phoneAPI = new BluetoothPhoneAPI();
|
||||
}
|
||||
|
||||
#if defined(CONFIG_BT_SMP)
|
||||
// NO_PIN is unsupported on this platform: the mesh GATT permissions are
|
||||
// declared with BT_GATT_PERM_*_AUTHEN, prj.conf sets
|
||||
// CONFIG_BT_SMP_ENFORCE_MITM=y, and the build pulls in the SMP/passkey path.
|
||||
// If a user requested NO_PIN we'd register no auth callbacks → no display
|
||||
// path for the passkey → every GATT access returns BT_ATT_ERR_AUTHENTICATION
|
||||
// and the link is unusable. Fall back to RANDOM_PIN behavior with a warning
|
||||
// instead of leaving BLE silently broken.
|
||||
if (config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_NO_PIN) {
|
||||
LOG_WARN("BLE: NO_PIN not supported on nRF54L15-DK (MITM-only build); "
|
||||
"treating as RANDOM_PIN");
|
||||
}
|
||||
|
||||
bt_conn_auth_cb_register(&auth_cb);
|
||||
bt_conn_auth_info_cb_register(&auth_info_cb);
|
||||
|
||||
// FIXED_PIN — register the configured passkey so the mobile app prompts
|
||||
// the user for that specific number instead of a random display-only PIN.
|
||||
// RANDOM_PIN (and clamped NO_PIN) keeps the default behavior: Zephyr
|
||||
// generates a fresh passkey on each pairing attempt and fires
|
||||
// auth_passkey_display with it.
|
||||
if (config.bluetooth.mode == meshtastic_Config_BluetoothConfig_PairingMode_FIXED_PIN) {
|
||||
configuredPasskey = config.bluetooth.fixed_pin;
|
||||
int rc = bt_passkey_set(configuredPasskey);
|
||||
if (rc) {
|
||||
LOG_WARN("bt_passkey_set(%u) failed: %d", configuredPasskey, rc);
|
||||
} else {
|
||||
LOG_INFO("BLE fixed PIN: %06u", configuredPasskey);
|
||||
}
|
||||
} else {
|
||||
bt_passkey_set(BT_PASSKEY_INVALID); // random per-pair
|
||||
}
|
||||
#endif /* CONFIG_BT_SMP */
|
||||
|
||||
if (!bt_initialized) {
|
||||
int err = bt_enable(NULL);
|
||||
if (err) {
|
||||
LOG_ERROR("BLE enable failed: %d", err);
|
||||
return false;
|
||||
}
|
||||
bt_initialized = true;
|
||||
LOG_INFO("BLE stack enabled");
|
||||
}
|
||||
|
||||
bt_set_name(getDeviceName());
|
||||
return true;
|
||||
}
|
||||
|
||||
void NRF54L15Bluetooth::setup()
|
||||
{
|
||||
LOG_INFO("NRF54L15Bluetooth::setup()");
|
||||
if (!nrf54l15_bt_init_common()) {
|
||||
return;
|
||||
}
|
||||
ble_enabled = true;
|
||||
start_advertising();
|
||||
}
|
||||
|
||||
void NRF54L15Bluetooth::shutdown()
|
||||
{
|
||||
LOG_INFO("NRF54L15Bluetooth::shutdown()");
|
||||
ble_enabled = false;
|
||||
stop_advertising();
|
||||
|
||||
struct bt_conn *conn = acquire_active_conn();
|
||||
if (conn) {
|
||||
bt_conn_disconnect(conn, BT_HCI_ERR_REMOTE_USER_TERM_CONN);
|
||||
bt_conn_unref(conn);
|
||||
}
|
||||
}
|
||||
|
||||
void NRF54L15Bluetooth::startDisabled()
|
||||
{
|
||||
// Initialize BT stack but leave advertising off until resumeAdvertising().
|
||||
if (!nrf54l15_bt_init_common()) {
|
||||
return;
|
||||
}
|
||||
ble_enabled = false;
|
||||
LOG_INFO("BLE initialized, advertising stopped (startDisabled)");
|
||||
}
|
||||
|
||||
void NRF54L15Bluetooth::resumeAdvertising()
|
||||
{
|
||||
ble_enabled = true;
|
||||
start_advertising();
|
||||
}
|
||||
|
||||
void NRF54L15Bluetooth::clearBonds()
|
||||
{
|
||||
LOG_INFO("BLE clear bonds");
|
||||
bt_unpair(BT_ID_DEFAULT, BT_ADDR_LE_ANY);
|
||||
}
|
||||
|
||||
bool NRF54L15Bluetooth::isConnected()
|
||||
{
|
||||
return active_conn != nullptr;
|
||||
}
|
||||
|
||||
int NRF54L15Bluetooth::getRssi()
|
||||
{
|
||||
return 0; // TODO: Zephyr has no direct bt_conn_get_rssi; use HCI RSSI read
|
||||
// command
|
||||
}
|
||||
|
||||
void NRF54L15Bluetooth::sendLog(const uint8_t *logMessage, size_t length)
|
||||
{
|
||||
if (length > 512 || logradio_ccc_val == 0) {
|
||||
return;
|
||||
}
|
||||
// Acquire a reference under ble_mutex so disconnected_cb can't free the
|
||||
// connection between the null check and bt_gatt_notify.
|
||||
struct bt_conn *conn = acquire_active_conn();
|
||||
if (!conn) {
|
||||
return;
|
||||
}
|
||||
// Send as notify regardless of whether client subscribed to NOTIFY or
|
||||
// INDICATE — bt_gatt_indicate() requires a params struct with a callback;
|
||||
// notify is simpler and the app accepts both. Change to indicate if
|
||||
// compatibility issues arise.
|
||||
bt_gatt_notify(conn, &mesh_svc.attrs[LOGRADIO_ATTR_IDX], logMessage, (uint16_t)length);
|
||||
bt_conn_unref(conn);
|
||||
}
|
||||
29
src/platform/nrf54l15/NRF54L15Bluetooth.h
Normal file
29
src/platform/nrf54l15/NRF54L15Bluetooth.h
Normal file
@@ -0,0 +1,29 @@
|
||||
// NRF54L15Bluetooth.h — Zephyr BLE backend for nRF54L15
|
||||
//
|
||||
// Implements the same interface as NRF52Bluetooth (same method names and
|
||||
// signatures) so main.cpp and AdminModule can use nrf52Bluetooth pointer
|
||||
// without knowing the underlying implementation.
|
||||
//
|
||||
// GATT profile is identical to the nRF52 implementation:
|
||||
// Service: MESH_SERVICE_UUID
|
||||
// toRadio: TORADIO_UUID (WRITE)
|
||||
// fromRadio: FROMRADIO_UUID (READ)
|
||||
// fromNum: FROMNUM_UUID (READ | NOTIFY)
|
||||
// logRadio: LOGRADIO_UUID (READ | NOTIFY | INDICATE)
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "BluetoothCommon.h"
|
||||
|
||||
class NRF54L15Bluetooth : public BluetoothApi
|
||||
{
|
||||
public:
|
||||
void setup();
|
||||
void shutdown();
|
||||
void startDisabled();
|
||||
void resumeAdvertising();
|
||||
void clearBonds();
|
||||
bool isConnected();
|
||||
int getRssi();
|
||||
void sendLog(const uint8_t *logMessage, size_t length);
|
||||
};
|
||||
17
src/platform/nrf54l15/Nrf52SaadcLock.h
Normal file
17
src/platform/nrf54l15/Nrf52SaadcLock.h
Normal file
@@ -0,0 +1,17 @@
|
||||
// Nrf52SaadcLock.h — stub for nRF54L15/Zephyr
|
||||
// Power.cpp includes this when ARCH_NRF52 is defined.
|
||||
// Phase 2: compile-only stub.
|
||||
#pragma once
|
||||
|
||||
#ifdef ARCH_NRF52
|
||||
|
||||
#include "concurrency/Lock.h"
|
||||
|
||||
namespace concurrency
|
||||
{
|
||||
/** Shared mutex for SAADC configuration and reads (VDD + battery analog path).
|
||||
* On nRF54L15 ADC is handled differently; this is a compile-only stub. */
|
||||
extern Lock *nrf52SaadcLock;
|
||||
} // namespace concurrency
|
||||
|
||||
#endif
|
||||
4
src/platform/nrf54l15/Print.h
Normal file
4
src/platform/nrf54l15/Print.h
Normal file
@@ -0,0 +1,4 @@
|
||||
// Print.h — shim for nRF54L15/Zephyr
|
||||
// Meshtastic includes <Print.h> separately; redirect to our Arduino.h shim.
|
||||
#pragma once
|
||||
#include "Arduino.h"
|
||||
62
src/platform/nrf54l15/SPI.h
Normal file
62
src/platform/nrf54l15/SPI.h
Normal file
@@ -0,0 +1,62 @@
|
||||
/**
|
||||
* SPI.h — Arduino SPI shim for Zephyr/nRF54L15
|
||||
*
|
||||
* Provides the Arduino SPIClass interface backed by Zephyr's SPI API. The
|
||||
* backing controller is SPIM00 (HP domain, 3.0 V); the implementation in
|
||||
* nrf54l15_arduino.cpp binds to DEVICE_DT_GET(DT_NODELABEL(spi00)) and the
|
||||
* bus is configured in zephyr/boards/nrf54l15dk_nrf54l15_cpuapp.overlay.
|
||||
* RadioLib uses ArduinoHal which calls transfer() byte-by-byte.
|
||||
*
|
||||
* CS pin is handled by RadioLib via digitalWrite() — hardware CS is not used.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <stdint.h>
|
||||
|
||||
#define SPI_MODE0 0
|
||||
#define SPI_MODE1 1
|
||||
#define SPI_MODE2 2
|
||||
#define SPI_MODE3 3
|
||||
|
||||
struct SPISettings {
|
||||
uint32_t clock;
|
||||
uint8_t bitOrder;
|
||||
uint8_t dataMode;
|
||||
|
||||
// Arduino API allows `SPI.beginTransaction(SPISettings(8000000, MSBFIRST, SPI_MODE0))` — implicit form is intentional.
|
||||
// cppcheck-suppress noExplicitConstructor
|
||||
SPISettings(uint32_t clock = 4000000, uint8_t bitOrder = MSBFIRST, uint8_t dataMode = SPI_MODE0)
|
||||
: clock(clock), bitOrder(bitOrder), dataMode(dataMode)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
class SPIClass
|
||||
{
|
||||
public:
|
||||
void begin() {}
|
||||
void begin(uint8_t sck, uint8_t miso, uint8_t mosi, uint8_t ss = 0xFF) {}
|
||||
void end() {}
|
||||
void beginTransaction(SPISettings) {}
|
||||
void endTransaction() {}
|
||||
void setBitOrder(uint8_t order) {}
|
||||
void setDataMode(uint8_t mode) {}
|
||||
void setClockDivider(uint8_t div) {}
|
||||
void setFrequency(uint32_t freq) {}
|
||||
|
||||
// Real Zephyr SPI implementation — defined in nrf54l15_arduino.cpp
|
||||
uint8_t transfer(uint8_t data);
|
||||
uint16_t transfer16(uint16_t data);
|
||||
void transfer(void *buf, size_t count);
|
||||
void transferBytes(const uint8_t *tx, uint8_t *rx, uint32_t count);
|
||||
uint8_t transfer(uint8_t tx, uint8_t *rx, uint32_t count)
|
||||
{
|
||||
transferBytes(&tx, rx, count);
|
||||
return rx ? rx[0] : 0;
|
||||
}
|
||||
};
|
||||
|
||||
extern SPIClass SPI;
|
||||
extern SPIClass SPI1;
|
||||
5
src/platform/nrf54l15/Stream.h
Normal file
5
src/platform/nrf54l15/Stream.h
Normal file
@@ -0,0 +1,5 @@
|
||||
// Stream.h — shim for nRF54L15/Zephyr
|
||||
// StreamAPI.h and other Meshtastic headers include <Stream.h>.
|
||||
// Redirect to our Arduino.h shim which defines the Stream base class.
|
||||
#pragma once
|
||||
#include "Arduino.h"
|
||||
4
src/platform/nrf54l15/Tone.h
Normal file
4
src/platform/nrf54l15/Tone.h
Normal file
@@ -0,0 +1,4 @@
|
||||
// Tone.h — shim for nRF54L15/Zephyr
|
||||
// Tone functions are stubbed in Arduino.h; this header satisfies direct includes.
|
||||
#pragma once
|
||||
#include "Arduino.h"
|
||||
5
src/platform/nrf54l15/WProgram.h
Normal file
5
src/platform/nrf54l15/WProgram.h
Normal file
@@ -0,0 +1,5 @@
|
||||
// WProgram.h — shim for nRF54L15/Zephyr
|
||||
// ArduinoThread (and other legacy Arduino libs) include <WProgram.h>.
|
||||
// Redirect to our Arduino.h shim.
|
||||
#pragma once
|
||||
#include "Arduino.h"
|
||||
219
src/platform/nrf54l15/Wire.cpp
Normal file
219
src/platform/nrf54l15/Wire.cpp
Normal file
@@ -0,0 +1,219 @@
|
||||
// Wire.cpp — Arduino TwoWire backed by Zephyr i2c30 (TWIM30 hardware).
|
||||
//
|
||||
// The pinctrl + clock-frequency are configured in
|
||||
// zephyr/boards/nrf54l15dk_nrf54l15_cpuapp.overlay. Runtime begin()/setClock()
|
||||
// are best-effort: setClock() goes through i2c_configure() to actually change
|
||||
// the bus speed; begin() just verifies the device is ready.
|
||||
|
||||
#include "Wire.h"
|
||||
#include "configuration.h"
|
||||
|
||||
#include <errno.h>
|
||||
#include <zephyr/device.h>
|
||||
#include <zephyr/drivers/i2c.h>
|
||||
#include <zephyr/kernel.h>
|
||||
|
||||
// Resolve the i2c30 node at compile time. If the overlay has not enabled
|
||||
// i2c30, this evaluates to a NULL device pointer and every call short-circuits
|
||||
// to a NACK return code — matching the prior compile-only stub behavior.
|
||||
#define I2C_NODE DT_NODELABEL(i2c30)
|
||||
|
||||
static const struct device *getI2CDevice()
|
||||
{
|
||||
#if DT_NODE_HAS_STATUS(I2C_NODE, okay)
|
||||
static const struct device *const dev = DEVICE_DT_GET(I2C_NODE);
|
||||
return dev;
|
||||
#else
|
||||
return nullptr;
|
||||
#endif
|
||||
}
|
||||
|
||||
// Wire/Wire1 instances are defined in nrf54l15_arduino.cpp alongside the
|
||||
// other Arduino singletons (Serial, SPI, …).
|
||||
|
||||
TwoWire::TwoWire() : txAddr(0), txLen(0), txBuf{}, rxLen(0), rxPos(0), rxBuf{} {}
|
||||
|
||||
void TwoWire::begin()
|
||||
{
|
||||
const struct device *dev = getI2CDevice();
|
||||
if (dev == nullptr) {
|
||||
LOG_WARN("Wire.begin(): i2c30 not enabled in DT overlay");
|
||||
return;
|
||||
}
|
||||
if (!device_is_ready(dev)) {
|
||||
LOG_WARN("Wire.begin(): i2c30 device not ready");
|
||||
return;
|
||||
}
|
||||
LOG_INFO("Wire.begin(): i2c30 ready");
|
||||
}
|
||||
|
||||
void TwoWire::begin(uint8_t /*sda*/, uint8_t /*scl*/)
|
||||
{
|
||||
// SDA/SCL fixed by overlay pinctrl — pin args ignored.
|
||||
begin();
|
||||
}
|
||||
|
||||
void TwoWire::begin(int /*sda*/, int /*scl*/, uint32_t freq)
|
||||
{
|
||||
begin();
|
||||
if (freq) {
|
||||
setClock(freq);
|
||||
}
|
||||
}
|
||||
|
||||
void TwoWire::end()
|
||||
{
|
||||
// No-op: Zephyr i2c devices stay initialized for the lifetime of the
|
||||
// application. Runtime PM (zephyr,pm-device-runtime-auto in the DT)
|
||||
// handles low-power transitions when idle.
|
||||
}
|
||||
|
||||
void TwoWire::setClock(uint32_t freq)
|
||||
{
|
||||
const struct device *dev = getI2CDevice();
|
||||
if (dev == nullptr) {
|
||||
return;
|
||||
}
|
||||
uint32_t speed;
|
||||
if (freq >= 1000000U) {
|
||||
speed = I2C_SPEED_FAST_PLUS; // 1 MHz
|
||||
} else if (freq >= 400000U) {
|
||||
speed = I2C_SPEED_FAST; // 400 kHz
|
||||
} else {
|
||||
speed = I2C_SPEED_STANDARD; // 100 kHz
|
||||
}
|
||||
uint32_t cfg = I2C_MODE_CONTROLLER | I2C_SPEED_SET(speed);
|
||||
int rc = i2c_configure(dev, cfg);
|
||||
if (rc) {
|
||||
LOG_WARN("Wire.setClock(%u) failed: %d", (unsigned)freq, rc);
|
||||
}
|
||||
}
|
||||
|
||||
void TwoWire::beginTransmission(uint8_t addr)
|
||||
{
|
||||
txAddr = addr;
|
||||
txLen = 0;
|
||||
}
|
||||
|
||||
size_t TwoWire::write(uint8_t data)
|
||||
{
|
||||
if (txLen >= WIRE_BUFFER_LENGTH) {
|
||||
return 0; // overflow — endTransmission() will return 1
|
||||
}
|
||||
txBuf[txLen++] = data;
|
||||
return 1;
|
||||
}
|
||||
|
||||
size_t TwoWire::write(const uint8_t *data, size_t n)
|
||||
{
|
||||
size_t written = 0;
|
||||
for (size_t i = 0; i < n; i++) {
|
||||
if (write(data[i]) == 0) {
|
||||
break;
|
||||
}
|
||||
written++;
|
||||
}
|
||||
return written;
|
||||
}
|
||||
|
||||
uint8_t TwoWire::endTransmission(bool /*stop*/)
|
||||
{
|
||||
// Arduino return codes:
|
||||
// 0 = success
|
||||
// 1 = data-too-long (overflow caught in write())
|
||||
// 2 = NACK on address
|
||||
// 3 = NACK on data
|
||||
// 4 = other error
|
||||
// 5 = timeout
|
||||
if (txLen > WIRE_BUFFER_LENGTH) {
|
||||
return 1;
|
||||
}
|
||||
const struct device *dev = getI2CDevice();
|
||||
if (dev == nullptr || !device_is_ready(dev)) {
|
||||
return 4;
|
||||
}
|
||||
int rc = i2c_write(dev, txBuf, txLen, txAddr);
|
||||
txLen = 0;
|
||||
if (rc == 0) {
|
||||
return 0;
|
||||
}
|
||||
if (rc == -EIO) {
|
||||
return 2; // address NACK is the most common -EIO source on nrf-twim
|
||||
}
|
||||
if (rc == -ETIMEDOUT) {
|
||||
return 5;
|
||||
}
|
||||
return 4;
|
||||
}
|
||||
|
||||
uint8_t TwoWire::requestFrom(uint8_t addr, uint8_t quantity, bool /*stop*/)
|
||||
{
|
||||
rxLen = 0;
|
||||
rxPos = 0;
|
||||
if (quantity == 0) {
|
||||
return 0;
|
||||
}
|
||||
if (quantity > WIRE_BUFFER_LENGTH) {
|
||||
quantity = WIRE_BUFFER_LENGTH;
|
||||
}
|
||||
const struct device *dev = getI2CDevice();
|
||||
if (dev == nullptr || !device_is_ready(dev)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// If there is a pending TX (driver wrote register address via write()
|
||||
// without an explicit endTransmission()), use i2c_write_read so the
|
||||
// repeated-start path matches the typical "set register pointer then
|
||||
// read N bytes" sensor protocol.
|
||||
int rc;
|
||||
if (txLen > 0) {
|
||||
rc = i2c_write_read(dev, addr, txBuf, txLen, rxBuf, quantity);
|
||||
txLen = 0;
|
||||
} else {
|
||||
rc = i2c_read(dev, rxBuf, quantity, addr);
|
||||
}
|
||||
if (rc) {
|
||||
return 0;
|
||||
}
|
||||
rxLen = quantity;
|
||||
return quantity;
|
||||
}
|
||||
|
||||
int TwoWire::available()
|
||||
{
|
||||
return rxLen - rxPos;
|
||||
}
|
||||
|
||||
int TwoWire::read()
|
||||
{
|
||||
if (rxPos >= rxLen) {
|
||||
return -1;
|
||||
}
|
||||
return rxBuf[rxPos++];
|
||||
}
|
||||
|
||||
int TwoWire::peek()
|
||||
{
|
||||
if (rxPos >= rxLen) {
|
||||
return -1;
|
||||
}
|
||||
return rxBuf[rxPos];
|
||||
}
|
||||
|
||||
size_t TwoWire::readBytes(uint8_t *buf, size_t len)
|
||||
{
|
||||
size_t n = 0;
|
||||
while (n < len) {
|
||||
int b = read();
|
||||
if (b < 0) {
|
||||
break;
|
||||
}
|
||||
buf[n++] = (uint8_t)b;
|
||||
}
|
||||
return n;
|
||||
}
|
||||
|
||||
TwoWire::operator bool() const
|
||||
{
|
||||
return getI2CDevice() != nullptr;
|
||||
}
|
||||
83
src/platform/nrf54l15/Wire.h
Normal file
83
src/platform/nrf54l15/Wire.h
Normal file
@@ -0,0 +1,83 @@
|
||||
/**
|
||||
* Wire.h — Arduino TwoWire (I2C) shim for Zephyr / nRF54L15.
|
||||
*
|
||||
* Bus binding: the Zephyr device tree alias `i2c30` (TWIM30 hardware
|
||||
* peripheral, HP domain, 3.0 V) is resolved at compile time via
|
||||
* DEVICE_DT_GET in Wire.cpp. SDA/SCL pins are configured in the board
|
||||
* overlay via pinctrl — `begin(sda, scl)` overloads are accepted for
|
||||
* Arduino API compatibility but the pin arguments are ignored.
|
||||
*
|
||||
* Buffer sizes are sized for the worst-case I2C consumer we plan to use
|
||||
* (NXP SE050 secure element, ~256-byte T=1 frames). BMP280 / INA228 /
|
||||
* SHT40 / INA3221 read in single-digit bytes and fit trivially.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "Arduino.h"
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#ifndef WIRE_BUFFER_LENGTH
|
||||
#define WIRE_BUFFER_LENGTH 256
|
||||
#endif
|
||||
|
||||
class TwoWire
|
||||
{
|
||||
public:
|
||||
TwoWire();
|
||||
|
||||
// ── Bus lifecycle ─────────────────────────────────────────────────
|
||||
// begin() variants — pin arguments are accepted for API compatibility
|
||||
// but ignored: SDA/SCL are fixed by the Zephyr overlay pinctrl. freq
|
||||
// is also fixed by overlay clock-frequency (use setClock() at runtime).
|
||||
void begin();
|
||||
void begin(uint8_t sda, uint8_t scl);
|
||||
void begin(int sda, int scl, uint32_t freq);
|
||||
void end();
|
||||
|
||||
void setClock(uint32_t freq);
|
||||
void setClockStretchLimit(uint32_t) {} // no-op on TWIM hardware
|
||||
|
||||
// ── Master write ─────────────────────────────────────────────────
|
||||
void beginTransmission(uint8_t addr);
|
||||
void beginTransmission(int addr) { beginTransmission((uint8_t)addr); }
|
||||
// Return codes (Arduino convention):
|
||||
// 0 = success, 1 = data-too-long, 2 = NACK on addr, 3 = NACK on data,
|
||||
// 4 = other error, 5 = timeout.
|
||||
uint8_t endTransmission(bool stop = true);
|
||||
uint8_t endTransmission(uint8_t stop) { return endTransmission(stop != 0); }
|
||||
|
||||
size_t write(uint8_t data);
|
||||
size_t write(const uint8_t *data, size_t n);
|
||||
|
||||
// ── Master read ──────────────────────────────────────────────────
|
||||
uint8_t requestFrom(uint8_t addr, uint8_t quantity, bool stop = true);
|
||||
uint8_t requestFrom(uint8_t addr, uint8_t quantity, uint8_t stop) { return requestFrom(addr, quantity, stop != 0); }
|
||||
uint8_t requestFrom(int addr, int quantity, int stop = 1) { return requestFrom((uint8_t)addr, (uint8_t)quantity, stop != 0); }
|
||||
|
||||
int available();
|
||||
int read();
|
||||
int peek();
|
||||
size_t readBytes(uint8_t *buf, size_t len);
|
||||
size_t readBytes(char *buf, size_t len) { return readBytes((uint8_t *)buf, len); }
|
||||
void flush() {}
|
||||
|
||||
// Slave callbacks unsupported — peripheral-only stub.
|
||||
void onReceive(void (*)(int)) {}
|
||||
void onRequest(void (*)(void)) {}
|
||||
|
||||
operator bool() const;
|
||||
|
||||
private:
|
||||
uint8_t txAddr;
|
||||
uint16_t txLen;
|
||||
uint8_t txBuf[WIRE_BUFFER_LENGTH];
|
||||
|
||||
uint16_t rxLen;
|
||||
uint16_t rxPos;
|
||||
uint8_t rxBuf[WIRE_BUFFER_LENGTH];
|
||||
};
|
||||
|
||||
extern TwoWire Wire;
|
||||
extern TwoWire Wire1; // alias to Wire — only one I2C bus on this board
|
||||
79
src/platform/nrf54l15/architecture.h
Normal file
79
src/platform/nrf54l15/architecture.h
Normal file
@@ -0,0 +1,79 @@
|
||||
#pragma once
|
||||
|
||||
#define ARCH_NRF54L15
|
||||
|
||||
//
|
||||
// Feature flags for nRF54L15.
|
||||
//
|
||||
// The HAS_* macros below are Meshtastic's compile-time feature gate: every
|
||||
// optional subsystem (BLE, screen, I2C, GPS, buttons, telemetry, sensors,
|
||||
// radio, CPU shutdown, ...) is wrapped in `#if HAS_FOO` so a given board
|
||||
// only pays for the features it actually ships. On memory-tight MCUs this
|
||||
// is not cosmetic — it's the difference between a binary that fits in
|
||||
// flash and one that doesn't, and between a build that links and one that
|
||||
// drags in drivers for hardware the board doesn't have. Defaulting to 0
|
||||
// here (rather than inheriting nRF52 defaults) is deliberate: the
|
||||
// nRF54L15-DK is a bare dev kit with no screen, no I2C sensors, no GPS,
|
||||
// no user buttons — so every HAS_* flag starts off and gets flipped on
|
||||
// explicitly by variants that add that hardware.
|
||||
//
|
||||
// Feature flags are also the cleanest way to absorb platform divergence
|
||||
// without sprinkling `#ifdef ARCH_NRF54L15` across shared code. Anywhere
|
||||
// a subsystem can be conditionally compiled via HAS_*, prefer that over
|
||||
// per-arch guards: it keeps the core code arch-agnostic, makes it trivial
|
||||
// to bring up the next board (flip the flags, don't patch call sites),
|
||||
// and keeps the "does this platform support X?" question answerable by
|
||||
// reading one file instead of grepping the tree. BLE in particular is
|
||||
// deferred to Phase 2 on this port — the nRF54L15 uses MPSL/Zephyr BLE
|
||||
// APIs rather than the Adafruit SoftDevice stack used by nRF52840 — so
|
||||
// while HAS_BLUETOOTH defaults to 1, the actual implementation lives in
|
||||
// NRF54L15Bluetooth.cpp behind its own Zephyr Kconfig gates.
|
||||
//
|
||||
|
||||
#ifndef HAS_BLUETOOTH
|
||||
#define HAS_BLUETOOTH 1
|
||||
#endif
|
||||
#ifndef HAS_SCREEN
|
||||
#define HAS_SCREEN 0
|
||||
#endif
|
||||
#ifndef HAS_WIRE
|
||||
#define HAS_WIRE 0
|
||||
#endif
|
||||
#ifndef HAS_GPS
|
||||
#define HAS_GPS 0
|
||||
#endif
|
||||
#ifndef HAS_BUTTON
|
||||
#define HAS_BUTTON 0
|
||||
#endif
|
||||
#ifndef HAS_TELEMETRY
|
||||
#define HAS_TELEMETRY 0
|
||||
#endif
|
||||
#ifndef HAS_SENSOR
|
||||
#define HAS_SENSOR 0
|
||||
#endif
|
||||
#ifndef HAS_RADIO
|
||||
#define HAS_RADIO 1
|
||||
#endif
|
||||
#ifndef HAS_CPU_SHUTDOWN
|
||||
#define HAS_CPU_SHUTDOWN 0
|
||||
#endif
|
||||
|
||||
// ADC reference — nRF54L15 SAADC uses VDD/4 internal ref by default
|
||||
#ifndef AREF_VOLTAGE
|
||||
#define AREF_VOLTAGE 3.6
|
||||
#endif
|
||||
#ifndef BATTERY_SENSE_RESOLUTION_BITS
|
||||
#define BATTERY_SENSE_RESOLUTION_BITS 12
|
||||
#endif
|
||||
|
||||
//
|
||||
// HW_VENDOR — maps build-time define to HardwareModel enum.
|
||||
// PRIVATE_HW (255): the protobuf HardwareModel enum reserves DK / DIY boards
|
||||
// without an SKU under this value; the nRF54L15-DK doesn't get a dedicated
|
||||
// enum number. Variant manifest matches via custom_meshtastic_hw_model = 255.
|
||||
//
|
||||
#ifdef NRF54L15_DK
|
||||
#define HW_VENDOR meshtastic_HardwareModel_PRIVATE_HW
|
||||
#else
|
||||
#define HW_VENDOR meshtastic_HardwareModel_UNSET
|
||||
#endif
|
||||
19
src/platform/nrf54l15/bluefruit.h
Normal file
19
src/platform/nrf54l15/bluefruit.h
Normal file
@@ -0,0 +1,19 @@
|
||||
// bluefruit.h — stub for nRF54L15/Zephyr
|
||||
// NodeDB.cpp includes this when ARCH_NRF52 is defined.
|
||||
// Bluetooth is excluded (MESHTASTIC_EXCLUDE_BLUETOOTH=1); this satisfies
|
||||
// the include chain without pulling in the Adafruit Bluefruit SDK.
|
||||
#pragma once
|
||||
|
||||
struct BLEPeripheral {
|
||||
void clearBonds() {}
|
||||
};
|
||||
struct BLECentral {
|
||||
void clearBonds() {}
|
||||
};
|
||||
|
||||
struct BlueFruitClass {
|
||||
BLEPeripheral Periph;
|
||||
BLECentral Central;
|
||||
};
|
||||
|
||||
extern BlueFruitClass Bluefruit;
|
||||
210
src/platform/nrf54l15/main-nrf54l15.cpp
Normal file
210
src/platform/nrf54l15/main-nrf54l15.cpp
Normal file
@@ -0,0 +1,210 @@
|
||||
/*
|
||||
* main-nrf54l15.cpp — Platform entry points for Nordic nRF54L15
|
||||
*
|
||||
* Adapted from src/platform/nrf52/main-nrf52.cpp.
|
||||
* SoftDevice, Adafruit BLE, and nRFCrypto are NOT available on nRF54L15.
|
||||
* Phase 2 will add proper BLE via Zephyr MPSL APIs.
|
||||
*
|
||||
* TODO items are marked with "TODO(nrf54l15):"
|
||||
*/
|
||||
|
||||
#include "configuration.h"
|
||||
#include <SPI.h>
|
||||
#include <Wire.h>
|
||||
#include <assert.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "NodeDB.h"
|
||||
#include "PowerMon.h"
|
||||
#include "Router.h"
|
||||
#include "error.h"
|
||||
#include "main.h"
|
||||
#include "mesh/MeshService.h"
|
||||
#include "meshUtils.h"
|
||||
#include "power.h"
|
||||
#include <power/PowerHAL.h>
|
||||
|
||||
// ── Watchdog ──────────────────────────────────────────────────────────────
|
||||
// TODO(nrf54l15): nRF54L15 has a WDT peripheral but nrfx_wdt driver support
|
||||
// may differ depending on the Zephyr SDK version. Enable once confirmed.
|
||||
#define APP_WATCHDOG_SECS 90
|
||||
static bool watchdog_running = false;
|
||||
|
||||
static inline void watchdog_feed() {} // TODO(nrf54l15): replace with real WDT feed
|
||||
|
||||
// ── Weak variant hooks ────────────────────────────────────────────────────
|
||||
void variant_shutdown() __attribute__((weak));
|
||||
void variant_shutdown() {}
|
||||
|
||||
void variant_nrf54l15LoopHook(void) __attribute__((weak));
|
||||
void variant_nrf54l15LoopHook(void) {}
|
||||
|
||||
// ── PowerHAL ─────────────────────────────────────────────────────────────
|
||||
bool powerHAL_isVBUSConnected()
|
||||
{
|
||||
// TODO(nrf54l15): nRF54L15 has a USB POWER peripheral — read USBREGSTATUS
|
||||
return false;
|
||||
}
|
||||
|
||||
bool powerHAL_isPowerLevelSafe()
|
||||
{
|
||||
// TODO(nrf54l15): implement SAADC VDD measurement similar to nRF52
|
||||
return true;
|
||||
}
|
||||
|
||||
void powerHAL_platformInit()
|
||||
{
|
||||
// TODO(nrf54l15): configure POF comparator and analog reference if needed
|
||||
}
|
||||
|
||||
// ── Utilities ─────────────────────────────────────────────────────────────
|
||||
bool loopCanSleep()
|
||||
{
|
||||
return !Serial;
|
||||
}
|
||||
|
||||
void updateBatteryLevel(uint8_t level)
|
||||
{
|
||||
(void)level;
|
||||
}
|
||||
|
||||
void __attribute__((noreturn)) __assert_func(const char *file, int line, const char *func, const char *failedexpr)
|
||||
{
|
||||
LOG_ERROR("assert failed %s: %d, %s, test=%s", file, line, func, failedexpr);
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void getMacAddr(uint8_t *dmac)
|
||||
{
|
||||
// TODO(nrf54l15): verify FICR register layout for nRF54L15.
|
||||
// nRF52840 uses NRF_FICR->DEVICEADDR[0/1]; nRF54L15 Zephyr HAL may differ.
|
||||
#if defined(NRF_FICR)
|
||||
const uint8_t *src = (const uint8_t *)NRF_FICR->DEVICEADDR;
|
||||
dmac[5] = src[0];
|
||||
dmac[4] = src[1];
|
||||
dmac[3] = src[2];
|
||||
dmac[2] = src[3];
|
||||
dmac[1] = src[4];
|
||||
dmac[0] = src[5] | 0xc0;
|
||||
#else
|
||||
// Fallback: fixed placeholder until Zephyr FICR path is confirmed
|
||||
dmac[0] = 0xC2;
|
||||
dmac[1] = 0xA7;
|
||||
dmac[2] = 0x54;
|
||||
dmac[3] = 0x15;
|
||||
dmac[4] = 0x00;
|
||||
dmac[5] = 0x01;
|
||||
#endif
|
||||
}
|
||||
|
||||
// ── Bluetooth ─────────────────────────────────────────────────────────────────
|
||||
|
||||
void setBluetoothEnable(bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
static bool initialized = false;
|
||||
if (!initialized) {
|
||||
nrf54l15Bluetooth = new NRF54L15Bluetooth();
|
||||
nrf54l15Bluetooth->startDisabled();
|
||||
initialized = true;
|
||||
}
|
||||
if (nrf54l15Bluetooth) {
|
||||
nrf54l15Bluetooth->resumeAdvertising();
|
||||
}
|
||||
} else {
|
||||
if (nrf54l15Bluetooth) {
|
||||
nrf54l15Bluetooth->shutdown();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void clearBonds()
|
||||
{
|
||||
if (!nrf54l15Bluetooth) {
|
||||
nrf54l15Bluetooth = new NRF54L15Bluetooth();
|
||||
nrf54l15Bluetooth->setup();
|
||||
}
|
||||
nrf54l15Bluetooth->clearBonds();
|
||||
}
|
||||
|
||||
void enterDfuMode()
|
||||
{
|
||||
// TODO(nrf54l15): nRF54L15 uses nRF Connect DFU (MCUboot/SUIT).
|
||||
// Trigger via Zephyr boot_request_upgrade() or similar.
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
// ── printf via RTT ────────────────────────────────────────────────────────
|
||||
// TODO(nrf54l15): SEGGER_RTT may not be available with Zephyr; use printk()
|
||||
// or a USB CDC console instead. Remove this override if it conflicts.
|
||||
#ifdef SEGGER_RTT_PRINTF
|
||||
int printf(const char *fmt, ...)
|
||||
{
|
||||
va_list args;
|
||||
va_start(args, fmt);
|
||||
auto res = SEGGER_RTT_vprintf(0, fmt, &args);
|
||||
va_end(args);
|
||||
return res;
|
||||
}
|
||||
#endif
|
||||
|
||||
// ── Deep sleep ────────────────────────────────────────────────────────────
|
||||
void cpuDeepSleep(uint32_t msecToWake)
|
||||
{
|
||||
#if HAS_WIRE
|
||||
Wire.end();
|
||||
#endif
|
||||
SPI.end();
|
||||
if (Serial)
|
||||
Serial.end();
|
||||
|
||||
variant_shutdown();
|
||||
|
||||
// TODO(nrf54l15): use Zephyr pm_system_suspend() or WFI for proper low-power
|
||||
if (msecToWake != portMAX_DELAY) {
|
||||
delay(msecToWake);
|
||||
NVIC_SystemReset();
|
||||
} else {
|
||||
// System off equivalent — halt
|
||||
while (1) {
|
||||
__WFI();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// ── Setup / Loop ──────────────────────────────────────────────────────────
|
||||
// Forward declaration — defined in NRF54L15Bluetooth.cpp
|
||||
void nrf54l15_bt_preinit();
|
||||
|
||||
void nrf54l15Setup()
|
||||
{
|
||||
// nRF54L15 power peripheral layout differs from nRF52; RESETREAS not present here.
|
||||
// TODO(Phase 3): use zephyr/drivers/hwinfo.h hwinfo_get_reset_cause()
|
||||
LOG_DEBUG("Reset reason: (nRF54L15 power peripheral differs from nRF52, skipped)");
|
||||
|
||||
// TODO(nrf54l15): init SAADC, watchdog, and random seed via nrfx or Zephyr
|
||||
// For now seed with a fixed value; replace with hardware entropy source.
|
||||
#if defined(NRF_FICR)
|
||||
randomSeed(analogRead(0) ^ (uint32_t)NRF_FICR->DEVICEADDR[0]);
|
||||
#else
|
||||
randomSeed(analogRead(0));
|
||||
#endif
|
||||
|
||||
// Pre-initialize BT stack here on the main thread (CONFIG_MAIN_STACK_SIZE=8192).
|
||||
// bt_enable() overflows the smaller PowerFSMThread stack when called later.
|
||||
// NRF54L15Bluetooth::setup() checks bt_initialized and skips bt_enable() if true.
|
||||
nrf54l15_bt_preinit();
|
||||
}
|
||||
|
||||
void nrf54l15Loop()
|
||||
{
|
||||
// First-call gate for the future WDT init — body will hold real init code, not just the bookkeeping flag.
|
||||
// cppcheck-suppress duplicateConditionalAssign
|
||||
if (!watchdog_running) {
|
||||
// TODO(nrf54l15): enable WDT here
|
||||
watchdog_running = true;
|
||||
}
|
||||
watchdog_feed();
|
||||
|
||||
variant_nrf54l15LoopHook();
|
||||
}
|
||||
557
src/platform/nrf54l15/nrf54l15_arduino.cpp
Normal file
557
src/platform/nrf54l15/nrf54l15_arduino.cpp
Normal file
@@ -0,0 +1,557 @@
|
||||
/**
|
||||
* nrf54l15_arduino.cpp — Arduino shim implementations for Zephyr/nRF54L15
|
||||
*
|
||||
* Provides concrete implementations for Print, HardwareSerial, GPIO, SPI,
|
||||
* and String methods declared in Arduino.h / SPI.h.
|
||||
*
|
||||
* Phase 3: real GPIO via Zephyr GPIO API and real SPI via Zephyr SPI API.
|
||||
* Pin numbering convention: P0.n = n, P1.n = 16+n, P2.n = 32+n.
|
||||
*/
|
||||
|
||||
#include "Arduino.h"
|
||||
#include "SPI.h"
|
||||
#include "Wire.h"
|
||||
#include <ctype.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <zephyr/drivers/gpio.h>
|
||||
#include <zephyr/drivers/spi.h>
|
||||
#include <zephyr/kernel.h>
|
||||
// ── Bluefruit singleton stub (satisfies NodeDB.cpp ARCH_NRF52 path) ──────────
|
||||
#include "bluefruit.h"
|
||||
BlueFruitClass Bluefruit;
|
||||
|
||||
// ── _fini stub — ARM newlib's __libc_fini_array references _fini, but ────────
|
||||
// Zephyr startup doesn't provide it. Provide a weak no-op so the linker
|
||||
// is satisfied when C++ global dtors or atexit() pull in __libc_fini_array.
|
||||
extern "C" void __attribute__((weak)) _fini(void) {}
|
||||
|
||||
// ── SPI / Wire singletons ─────────────────────────────────────────────────────
|
||||
SPIClass SPI;
|
||||
SPIClass SPI1;
|
||||
TwoWire Wire;
|
||||
TwoWire Wire1;
|
||||
|
||||
// ── HardwareSerial singletons ────────────────────────────────────────────────
|
||||
HardwareSerial Serial;
|
||||
HardwareSerial Serial1;
|
||||
HardwareSerial Serial2;
|
||||
|
||||
// ── Timing functions — C linkage to match extern "C" declarations ────────────
|
||||
extern "C" uint32_t millis(void)
|
||||
{
|
||||
return (uint32_t)k_uptime_get_32();
|
||||
}
|
||||
extern "C" uint32_t micros(void)
|
||||
{
|
||||
return (uint32_t)(k_uptime_get() * 1000ULL);
|
||||
}
|
||||
extern "C" void delay(uint32_t ms)
|
||||
{
|
||||
k_sleep(K_MSEC(ms));
|
||||
}
|
||||
extern "C" void delayMicroseconds(uint32_t us)
|
||||
{
|
||||
k_sleep(K_USEC(us));
|
||||
}
|
||||
extern "C" void yield(void)
|
||||
{
|
||||
k_yield();
|
||||
}
|
||||
|
||||
// ── NVIC_SystemReset — wraps __NVIC_SystemReset from CMSIS core_cm33.h ───────
|
||||
// core_cm33.h has #define NVIC_SystemReset __NVIC_SystemReset, so undef it
|
||||
// before defining our own implementation to prevent macro expansion collision.
|
||||
#pragma push_macro("NVIC_SystemReset")
|
||||
#undef NVIC_SystemReset
|
||||
extern "C" void NVIC_SystemReset(void)
|
||||
{
|
||||
sys_reboot(SYS_REBOOT_COLD);
|
||||
}
|
||||
#pragma pop_macro("NVIC_SystemReset")
|
||||
|
||||
// ── HardwareSerial::write ─────────────────────────────────────────────────────
|
||||
size_t HardwareSerial::write(uint8_t c)
|
||||
{
|
||||
// TODO(nrf54l15 Phase 3): route through Zephyr UART / USB-CDC console
|
||||
// For now use printk so we at least get something over RTT/UART0
|
||||
printk("%c", (char)c);
|
||||
return 1;
|
||||
}
|
||||
|
||||
size_t HardwareSerial::write(const uint8_t *buf, size_t n)
|
||||
{
|
||||
for (size_t i = 0; i < n; i++)
|
||||
printk("%c", (char)buf[i]);
|
||||
return n;
|
||||
}
|
||||
|
||||
// ── Print::printf ─────────────────────────────────────────────────────────────
|
||||
int Print::printf(const char *fmt, ...)
|
||||
{
|
||||
char buf[256];
|
||||
va_list args;
|
||||
va_start(args, fmt);
|
||||
int n = vsnprintf(buf, sizeof(buf), fmt, args);
|
||||
va_end(args);
|
||||
if (n > 0)
|
||||
write((const uint8_t *)buf, (size_t)(n < (int)sizeof(buf) ? n : (int)sizeof(buf) - 1));
|
||||
return n;
|
||||
}
|
||||
|
||||
// ── strlcpy — BSD extension not in Zephyr newlib ────────────────────────────
|
||||
extern "C" size_t strlcpy(char *dst, const char *src, size_t size)
|
||||
{
|
||||
size_t len = strlen(src);
|
||||
if (size > 0) {
|
||||
size_t copy = len < size - 1 ? len : size - 1;
|
||||
memcpy(dst, src, copy);
|
||||
dst[copy] = '\0';
|
||||
}
|
||||
return len;
|
||||
}
|
||||
|
||||
// ── Print numeric helpers ─────────────────────────────────────────────────────
|
||||
static size_t printNumber(Print &p, unsigned long n, uint8_t base)
|
||||
{
|
||||
if (base == 0)
|
||||
return p.write((uint8_t)n);
|
||||
|
||||
char buf[8 * sizeof(long) + 1];
|
||||
char *end = buf + sizeof(buf) - 1;
|
||||
*end = '\0';
|
||||
if (n == 0) {
|
||||
*--end = '0';
|
||||
} else {
|
||||
while (n > 0) {
|
||||
unsigned long remainder = n % base;
|
||||
*--end = (char)(remainder < 10 ? '0' + remainder : 'A' + remainder - 10);
|
||||
n /= base;
|
||||
}
|
||||
}
|
||||
return p.write((const uint8_t *)end, strlen(end));
|
||||
}
|
||||
|
||||
static size_t printFloat(Print &p, double number, uint8_t digits)
|
||||
{
|
||||
if (isnan(number))
|
||||
return p.print("nan");
|
||||
if (isinf(number))
|
||||
return p.print("inf");
|
||||
if (number > 4294967040.0 || number < -4294967040.0)
|
||||
return p.print("ovf");
|
||||
|
||||
size_t n = 0;
|
||||
if (number < 0.0) {
|
||||
n += p.write('-');
|
||||
number = -number;
|
||||
}
|
||||
|
||||
// Round
|
||||
double rounding = 0.5;
|
||||
for (uint8_t i = 0; i < digits; i++)
|
||||
rounding /= 10.0;
|
||||
number += rounding;
|
||||
|
||||
unsigned long int_part = (unsigned long)number;
|
||||
double remainder = number - (double)int_part;
|
||||
n += printNumber(p, int_part, 10);
|
||||
if (digits > 0) {
|
||||
n += p.write('.');
|
||||
for (uint8_t i = 0; i < digits; i++) {
|
||||
remainder *= 10.0;
|
||||
unsigned int d = (unsigned int)remainder;
|
||||
n += p.write('0' + d);
|
||||
remainder -= d;
|
||||
}
|
||||
}
|
||||
return n;
|
||||
}
|
||||
|
||||
size_t Print::print(unsigned char n, int base)
|
||||
{
|
||||
return printNumber(*this, n, base);
|
||||
}
|
||||
size_t Print::print(int n, int base)
|
||||
{
|
||||
if (base == 10 && n < 0) {
|
||||
size_t r = write('-');
|
||||
return r + printNumber(*this, (unsigned long)(-n), base);
|
||||
}
|
||||
return printNumber(*this, (unsigned long)n, base);
|
||||
}
|
||||
size_t Print::print(long n, int base)
|
||||
{
|
||||
if (base == 10 && n < 0) {
|
||||
size_t r = write('-');
|
||||
return r + printNumber(*this, (unsigned long)(-n), base);
|
||||
}
|
||||
return printNumber(*this, (unsigned long)n, base);
|
||||
}
|
||||
size_t Print::print(unsigned int n, int base)
|
||||
{
|
||||
return printNumber(*this, n, base);
|
||||
}
|
||||
size_t Print::print(unsigned long n, int base)
|
||||
{
|
||||
return printNumber(*this, n, base);
|
||||
}
|
||||
size_t Print::print(float n, int d)
|
||||
{
|
||||
return printFloat(*this, n, d);
|
||||
}
|
||||
size_t Print::print(double n, int d)
|
||||
{
|
||||
return printFloat(*this, n, d);
|
||||
}
|
||||
|
||||
// ── String::replace(String, String) ─────────────────────────────────────────
|
||||
void String::replace(const String &from, const String &to)
|
||||
{
|
||||
if (from.isEmpty() || !_buf)
|
||||
return;
|
||||
// Simple O(n²) replace — fine for typical Meshtastic string lengths
|
||||
String result;
|
||||
const char *p = _buf;
|
||||
while (*p) {
|
||||
if (strncmp(p, from.c_str(), from.length()) == 0) {
|
||||
result += to;
|
||||
p += from.length();
|
||||
} else {
|
||||
result += *p++;
|
||||
}
|
||||
}
|
||||
*this = result;
|
||||
}
|
||||
|
||||
// ═════════════════════════════════════════════════════════════════════════════
|
||||
// GPIO — Real Zephyr implementation (Phase 3)
|
||||
// Pin mapping: P0.n = n (0-15), P1.n = 16+n (16-31), P2.n = 32+n (32-47)
|
||||
// ═════════════════════════════════════════════════════════════════════════════
|
||||
|
||||
static const struct device *_gpio_dev_for_pin(uint32_t pin, gpio_pin_t *zpin)
|
||||
{
|
||||
if (pin < 16) {
|
||||
*zpin = (gpio_pin_t)pin;
|
||||
return DEVICE_DT_GET(DT_NODELABEL(gpio0));
|
||||
} else if (pin < 32) {
|
||||
*zpin = (gpio_pin_t)(pin - 16);
|
||||
return DEVICE_DT_GET(DT_NODELABEL(gpio1));
|
||||
} else {
|
||||
*zpin = (gpio_pin_t)(pin - 32);
|
||||
return DEVICE_DT_GET(DT_NODELABEL(gpio2));
|
||||
}
|
||||
}
|
||||
|
||||
void pinMode(uint32_t pin, uint32_t mode)
|
||||
{
|
||||
gpio_pin_t zpin;
|
||||
const struct device *dev = _gpio_dev_for_pin(pin, &zpin);
|
||||
if (!device_is_ready(dev))
|
||||
return;
|
||||
|
||||
gpio_flags_t flags;
|
||||
switch (mode) {
|
||||
case OUTPUT:
|
||||
flags = GPIO_OUTPUT_INACTIVE;
|
||||
break;
|
||||
case INPUT_PULLUP:
|
||||
flags = GPIO_INPUT | GPIO_PULL_UP;
|
||||
break;
|
||||
case INPUT_PULLDOWN:
|
||||
flags = GPIO_INPUT | GPIO_PULL_DOWN;
|
||||
break;
|
||||
default:
|
||||
flags = GPIO_INPUT;
|
||||
break;
|
||||
}
|
||||
gpio_pin_configure(dev, zpin, flags);
|
||||
}
|
||||
|
||||
// Bring-up diagnostics for the SX1262 wiring path. Off by default — enable by
|
||||
// adding `-DNRF54L15_GPIO_DEBUG` to platformio.ini build_flags. Useful when
|
||||
// validating CS/NRESET toggles after a wiring change, diagnosing a "stuck HIGH"
|
||||
// BUSY before the first NRESET pulse, or tracing BUSY transitions during early
|
||||
// boot. In normal operation these traces are noise (they bypass LOG level
|
||||
// controls and print on every GPIO touch), so they are gated at compile time.
|
||||
#ifdef NRF54L15_GPIO_DEBUG
|
||||
#define GPIO_LOG_MAX 20
|
||||
static uint32_t _gpio_log_count = 0;
|
||||
#endif
|
||||
|
||||
void digitalWrite(uint32_t pin, uint32_t value)
|
||||
{
|
||||
#ifdef NRF54L15_GPIO_DEBUG
|
||||
// Before the very first NRESET pulse, snapshot BUSY state.
|
||||
// If BUSY is already HIGH here, the chip never completed power-on calibration.
|
||||
if (pin == 32 && value == 0) {
|
||||
static bool _first_nreset = true;
|
||||
if (_first_nreset) {
|
||||
_first_nreset = false;
|
||||
const struct device *bdev = DEVICE_DT_GET(DT_NODELABEL(gpio2));
|
||||
if (device_is_ready(bdev)) {
|
||||
gpio_pin_configure(bdev, 3, GPIO_INPUT); // P2.03 = BUSY
|
||||
int busy_before = gpio_pin_get(bdev, 3);
|
||||
printk("[nrf54l15] BUSY before first NRESET = %d%s\n", busy_before,
|
||||
busy_before ? " ← STUCK HIGH (chip damaged?)" : " ← LOW (chip OK)");
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
gpio_pin_t zpin;
|
||||
const struct device *dev = _gpio_dev_for_pin(pin, &zpin);
|
||||
if (!device_is_ready(dev)) {
|
||||
// Genuine hardware/DTS misconfiguration — keep this regardless of the
|
||||
// GPIO_DEBUG gate so it surfaces in production builds too.
|
||||
printk("[GPIO] pin%u dev NOT READY\n", (unsigned)pin);
|
||||
return;
|
||||
}
|
||||
gpio_pin_set(dev, zpin, (int)value);
|
||||
#ifdef NRF54L15_GPIO_DEBUG
|
||||
if ((pin == 37 || pin == 32) && _gpio_log_count < GPIO_LOG_MAX) {
|
||||
// Read back the pin state to confirm it actually changed
|
||||
int actual = gpio_pin_get(dev, zpin);
|
||||
printk("[GPIO] pin%u → %u (read-back=%d)\n", (unsigned)pin, (unsigned)value, actual);
|
||||
_gpio_log_count++;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
int digitalRead(uint32_t pin)
|
||||
{
|
||||
gpio_pin_t zpin;
|
||||
const struct device *dev = _gpio_dev_for_pin(pin, &zpin);
|
||||
if (!device_is_ready(dev))
|
||||
return 0;
|
||||
int v = gpio_pin_get(dev, zpin);
|
||||
#ifdef NRF54L15_GPIO_DEBUG
|
||||
// Log BUSY pin (35=P2.03) state changes + periodic updates for 10 seconds
|
||||
if (pin == 35) {
|
||||
static uint32_t busy_log_count = 0;
|
||||
static int last_busy = -1;
|
||||
static uint32_t first_read_ms = 0;
|
||||
if (first_read_ms == 0)
|
||||
first_read_ms = k_uptime_get_32();
|
||||
uint32_t elapsed_ms = k_uptime_get_32() - first_read_ms;
|
||||
|
||||
// Always log state changes
|
||||
if (v != last_busy) {
|
||||
printk("[BUSY] %ums: state changed %d → %d\n", (unsigned)elapsed_ms, last_busy, v);
|
||||
last_busy = v;
|
||||
}
|
||||
// Also log every 500ms for first 10 seconds so we can see timeline
|
||||
if (elapsed_ms < 10000 && busy_log_count < 20 && (elapsed_ms / 500) > (busy_log_count)) {
|
||||
printk("[BUSY] %ums: pin=%d (periodic)\n", (unsigned)elapsed_ms, v);
|
||||
busy_log_count = (elapsed_ms / 500) + 1;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
return v;
|
||||
}
|
||||
|
||||
// ─── attachInterrupt — supports up to NRF54L15_MAX_IRQS pins ────────────────
|
||||
#define NRF54L15_MAX_IRQS 8
|
||||
|
||||
struct _PinIrq {
|
||||
struct gpio_callback cb;
|
||||
voidFuncPtr user_cb;
|
||||
const struct device *dev;
|
||||
gpio_pin_t zpin;
|
||||
bool used;
|
||||
};
|
||||
|
||||
static _PinIrq _irq_table[NRF54L15_MAX_IRQS];
|
||||
|
||||
static void _gpio_irq_dispatch(const struct device *dev, struct gpio_callback *cb, uint32_t pins)
|
||||
{
|
||||
_PinIrq *irq = CONTAINER_OF(cb, _PinIrq, cb);
|
||||
if (irq->user_cb)
|
||||
irq->user_cb();
|
||||
}
|
||||
|
||||
void attachInterrupt(uint32_t pin, voidFuncPtr cb, int mode)
|
||||
{
|
||||
gpio_pin_t zpin;
|
||||
const struct device *dev = _gpio_dev_for_pin(pin, &zpin);
|
||||
if (!device_is_ready(dev))
|
||||
return;
|
||||
|
||||
// Find a free slot (or reuse existing registration for same pin)
|
||||
_PinIrq *slot = nullptr;
|
||||
for (int i = 0; i < NRF54L15_MAX_IRQS; i++) {
|
||||
if (_irq_table[i].used && _irq_table[i].dev == dev && _irq_table[i].zpin == zpin) {
|
||||
// Re-register: remove old callback first
|
||||
gpio_remove_callback(dev, &_irq_table[i].cb);
|
||||
slot = &_irq_table[i];
|
||||
break;
|
||||
}
|
||||
if (!slot && !_irq_table[i].used)
|
||||
slot = &_irq_table[i];
|
||||
}
|
||||
if (!slot)
|
||||
return; // table full
|
||||
|
||||
gpio_flags_t irq_flags;
|
||||
switch (mode) {
|
||||
case RISING:
|
||||
irq_flags = GPIO_INT_EDGE_RISING;
|
||||
break;
|
||||
case FALLING:
|
||||
irq_flags = GPIO_INT_EDGE_FALLING;
|
||||
break;
|
||||
default:
|
||||
irq_flags = GPIO_INT_EDGE_BOTH;
|
||||
break;
|
||||
}
|
||||
|
||||
slot->user_cb = cb;
|
||||
slot->dev = dev;
|
||||
slot->zpin = zpin;
|
||||
slot->used = true;
|
||||
|
||||
gpio_pin_configure(dev, zpin, GPIO_INPUT);
|
||||
gpio_init_callback(&slot->cb, _gpio_irq_dispatch, BIT(zpin));
|
||||
gpio_add_callback(dev, &slot->cb);
|
||||
gpio_pin_interrupt_configure(dev, zpin, irq_flags);
|
||||
}
|
||||
|
||||
void detachInterrupt(uint32_t pin)
|
||||
{
|
||||
gpio_pin_t zpin;
|
||||
const struct device *dev = _gpio_dev_for_pin(pin, &zpin);
|
||||
for (int i = 0; i < NRF54L15_MAX_IRQS; i++) {
|
||||
if (_irq_table[i].used && _irq_table[i].dev == dev && _irq_table[i].zpin == zpin) {
|
||||
gpio_pin_interrupt_configure(dev, zpin, GPIO_INT_DISABLE);
|
||||
gpio_remove_callback(dev, &_irq_table[i].cb);
|
||||
_irq_table[i].used = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// ═════════════════════════════════════════════════════════════════════════════
|
||||
// SPI — Real Zephyr implementation using SPIM00 (HP domain, 3.0V)
|
||||
// CS is handled by RadioLib via digitalWrite() — hardware CS not used.
|
||||
// Mode 0 (CPOL=0, CPHA=0), MSB first.
|
||||
// ═════════════════════════════════════════════════════════════════════════════
|
||||
|
||||
// Use SPIM00 (HP domain, 3.0V) — SPIM20 is 1.8V LP domain, incompatible with SX1262.
|
||||
// Lazy-init: DEVICE_DT_GET in global scope fails when the extern symbol is
|
||||
// not visible in this translation unit. Use a function-local static instead.
|
||||
static const struct device *_spi00(void)
|
||||
{
|
||||
static const struct device *dev = nullptr;
|
||||
if (!dev) {
|
||||
dev = DEVICE_DT_GET(DT_NODELABEL(spi00));
|
||||
if (!device_is_ready(dev)) {
|
||||
printk("[nrf54l15] spi00 NOT READY\n");
|
||||
dev = nullptr;
|
||||
} else {
|
||||
printk("[nrf54l15] spi00 ready\n");
|
||||
}
|
||||
}
|
||||
return dev;
|
||||
}
|
||||
|
||||
// SPI config: Mode 0, MSB first, no hardware CS (RadioLib does it manually)
|
||||
//
|
||||
// SPIM00 base clock = 128 MHz (nRF54L15 default when NRF_CONFIG_CPU_FREQ_MHZ
|
||||
// is not set; SystemInit() applies 128 MHz). Hardware prescaler must be EVEN
|
||||
// and in [4, 126] (SPIM00_PRESCALER_DIVISOR_RANGE_MIN/MAX from MDK).
|
||||
// 1 MHz → prescaler = 128 > 126 → NRFX_ERROR_INVALID_PARAM → -EIO on every
|
||||
// transfer. Minimum valid frequency is 2 MHz (prescaler = 64).
|
||||
static const struct spi_config _spi00_cfg = {
|
||||
.frequency = 2000000U, // 2 MHz — minimum valid for SPIM00 at 128 MHz base
|
||||
.operation = SPI_OP_MODE_MASTER | SPI_WORD_SET(8) | SPI_TRANSFER_MSB,
|
||||
.slave = 0,
|
||||
.cs = {}, // CS = NULL → RadioLib handles CS via GPIO
|
||||
};
|
||||
|
||||
// Static DMA buffers — stack-allocated bufs on nRF54L15 may not be reachable
|
||||
// by SPIM20 EasyDMA. Static placement in .bss/.data is always in Global SRAM.
|
||||
// rx_byte is pre-filled with 0xAA before every transfer so we can distinguish:
|
||||
// 0xAA → DMA never wrote (EasyDMA can't reach the buffer)
|
||||
// 0x00 → MISO actively driven LOW (chip in reset / bus fight)
|
||||
// 0xFF → MISO floating HIGH
|
||||
// other → real chip response
|
||||
static uint8_t _spi_tx_byte __attribute__((aligned(4)));
|
||||
static uint8_t _spi_rx_byte __attribute__((aligned(4)));
|
||||
|
||||
// Dump the first SPI_DUMP_N byte exchanges so we can see what MISO returns.
|
||||
#define SPI_DUMP_N 30
|
||||
static uint32_t _spi_dump_count = 0;
|
||||
|
||||
uint8_t SPIClass::transfer(uint8_t data)
|
||||
{
|
||||
const struct device *dev = _spi00();
|
||||
if (!dev)
|
||||
return 0xFF;
|
||||
|
||||
_spi_tx_byte = data;
|
||||
_spi_rx_byte = 0xAA; // sentinel: if DMA doesn't write, we return 0xAA
|
||||
|
||||
struct spi_buf tx_buf = {.buf = &_spi_tx_byte, .len = 1};
|
||||
struct spi_buf rx_buf = {.buf = &_spi_rx_byte, .len = 1};
|
||||
struct spi_buf_set tx_set = {.buffers = &tx_buf, .count = 1};
|
||||
struct spi_buf_set rx_set = {.buffers = &rx_buf, .count = 1};
|
||||
|
||||
static uint32_t spi_err_count = 0;
|
||||
int ret = spi_transceive(dev, &_spi00_cfg, &tx_set, &rx_set);
|
||||
if (ret != 0 && spi_err_count++ < 3)
|
||||
printk("[SPI] err=%d tx=0x%02x\n", ret, data);
|
||||
|
||||
if (_spi_dump_count < SPI_DUMP_N) {
|
||||
printk("[SPI] #%u tx=0x%02x rx=0x%02x\n", (unsigned)_spi_dump_count, data, _spi_rx_byte);
|
||||
_spi_dump_count++;
|
||||
}
|
||||
|
||||
return _spi_rx_byte;
|
||||
}
|
||||
|
||||
// Static DMA-safe buffers for transfer16 — same EasyDMA reachability concern
|
||||
// applies as for the byte path: stack buffers from a caller thread may sit in
|
||||
// per-thread RAM regions that EasyDMA cannot reach.
|
||||
static uint8_t _spi_tx16[2] __attribute__((aligned(4)));
|
||||
static uint8_t _spi_rx16[2] __attribute__((aligned(4)));
|
||||
|
||||
uint16_t SPIClass::transfer16(uint16_t data)
|
||||
{
|
||||
const struct device *dev = _spi00();
|
||||
if (!dev)
|
||||
return 0xFFFF;
|
||||
|
||||
_spi_tx16[0] = (uint8_t)(data >> 8);
|
||||
_spi_tx16[1] = (uint8_t)(data & 0xFF);
|
||||
_spi_rx16[0] = 0xAA;
|
||||
_spi_rx16[1] = 0xAA;
|
||||
struct spi_buf tx_buf = {.buf = _spi_tx16, .len = 2};
|
||||
struct spi_buf rx_buf = {.buf = _spi_rx16, .len = 2};
|
||||
struct spi_buf_set tx_set = {.buffers = &tx_buf, .count = 1};
|
||||
struct spi_buf_set rx_set = {.buffers = &rx_buf, .count = 1};
|
||||
spi_transceive(dev, &_spi00_cfg, &tx_set, &rx_set);
|
||||
return ((uint16_t)_spi_rx16[0] << 8) | _spi_rx16[1];
|
||||
}
|
||||
|
||||
void SPIClass::transferBytes(const uint8_t *tx, uint8_t *rx, uint32_t count)
|
||||
{
|
||||
if (!count)
|
||||
return;
|
||||
const struct device *dev = _spi00();
|
||||
if (!dev)
|
||||
return;
|
||||
// Zephyr requires non-const buf pointer; cast is safe for tx-only direction
|
||||
struct spi_buf tx_buf = {.buf = const_cast<uint8_t *>(tx), .len = count};
|
||||
struct spi_buf rx_buf = {.buf = rx, .len = count};
|
||||
struct spi_buf_set tx_set = {.buffers = &tx_buf, .count = 1};
|
||||
struct spi_buf_set rx_set = {.buffers = rx_buf.buf ? &rx_buf : nullptr, .count = rx_buf.buf ? 1U : 0U};
|
||||
spi_transceive(dev, &_spi00_cfg, &tx_set, rx ? &rx_set : nullptr);
|
||||
}
|
||||
|
||||
void SPIClass::transfer(void *buf, size_t count)
|
||||
{
|
||||
if (!count || !buf)
|
||||
return;
|
||||
transferBytes(reinterpret_cast<const uint8_t *>(buf), reinterpret_cast<uint8_t *>(buf), (uint32_t)count);
|
||||
}
|
||||
121
src/platform/nrf54l15/nrf54l15_main.cpp
Normal file
121
src/platform/nrf54l15/nrf54l15_main.cpp
Normal file
@@ -0,0 +1,121 @@
|
||||
/*
|
||||
* nrf54l15_main.cpp — Zephyr entry point for Meshtastic nRF54L15 port
|
||||
*
|
||||
* Zephyr calls main() instead of Arduino's setup()/loop().
|
||||
* This file provides the main() that bootstraps the Arduino-style
|
||||
* Meshtastic application loop.
|
||||
*/
|
||||
|
||||
#include <zephyr/drivers/hwinfo.h>
|
||||
#include <zephyr/fatal.h>
|
||||
#include <zephyr/kernel.h>
|
||||
#include <zephyr/sys/reboot.h>
|
||||
|
||||
// Forward declarations from src/main.cpp
|
||||
void setup();
|
||||
void loop();
|
||||
|
||||
// ── Crash info saved to noinit RAM (survives soft reset) ─────────────────────
|
||||
// Zephyr's arch_esf does not expose the faulting SP directly; we capture PSP
|
||||
// at entry to the fatal handler (the exception-basic frame lives there) and
|
||||
// store xPSR alongside PC/LR for context.
|
||||
struct crash_info {
|
||||
uint32_t magic;
|
||||
uint32_t reason;
|
||||
uint32_t pc;
|
||||
uint32_t psp; // stack pointer captured at fault entry
|
||||
uint32_t xpsr; // saved program status (flags + exception number)
|
||||
uint32_t lr;
|
||||
uint32_t cfsr; // Configurable Fault Status Register
|
||||
};
|
||||
static struct crash_info saved_crash __attribute__((section(".noinit")));
|
||||
#define CRASH_MAGIC 0xDEADBEEF
|
||||
|
||||
// Override Zephyr's weak fatal handler to save crash info, then cold-reboot so
|
||||
// main() can report the saved record on the next boot. We don't rely on
|
||||
// CONFIG_RESET_ON_FATAL_ERROR (default off → k_fatal_halt would spin forever)
|
||||
// — we issue sys_reboot() ourselves after flushing logs.
|
||||
extern "C" void k_sys_fatal_error_handler(unsigned int reason, const struct arch_esf *esf)
|
||||
{
|
||||
saved_crash.magic = CRASH_MAGIC;
|
||||
saved_crash.reason = reason;
|
||||
// Capture the faulting thread's stack pointer before we start using the
|
||||
// handler's own stack for logging.
|
||||
uint32_t psp_at_entry;
|
||||
__asm__ volatile("mrs %0, psp" : "=r"(psp_at_entry));
|
||||
saved_crash.psp = psp_at_entry;
|
||||
if (esf) {
|
||||
saved_crash.pc = esf->basic.pc;
|
||||
saved_crash.xpsr = esf->basic.xpsr;
|
||||
saved_crash.lr = esf->basic.lr;
|
||||
}
|
||||
// Read Cortex-M33 SCB CFSR
|
||||
saved_crash.cfsr = *((volatile uint32_t *)0xE000ED28U);
|
||||
printk("[nrf54l15] FATAL reason=%u pc=0x%08x lr=0x%08x cfsr=0x%08x\n", reason, saved_crash.pc, saved_crash.lr,
|
||||
saved_crash.cfsr);
|
||||
|
||||
// Walk the failing thread's stack and print any word that looks like a
|
||||
// Thumb code address (0x1000 — flash end, with the Thumb-mode low bit set).
|
||||
// The Cortex-M exception frame at PSP holds r0,r1,r2,r3,r12,lr,pc,xpsr
|
||||
// (8 words); deeper words are the caller's saved frame, which gives a
|
||||
// crude but useful poor-man's backtrace when CONFIG_DEBUG_COREDUMP is off.
|
||||
// Found the BLE-init bad_alloc → abort() chain (heap exhaustion under
|
||||
// CONFIG_BT_BUF_ACL_RX_SIZE=251) when the fault dump alone showed only
|
||||
// abort itself. Cheap (~150 B of code) and silent until a fault.
|
||||
uint32_t psp;
|
||||
__asm__ volatile("mrs %0, psp" : "=r"(psp));
|
||||
printk("[nrf54l15] PSP=0x%08x — stack walk:\n", psp);
|
||||
// Validate PSP before dereferencing. Real faults frequently leave PSP
|
||||
// pointing at corrupted/unmapped memory, and walking it blindly triggers a
|
||||
// second fault inside this handler. Restrict to nRF54L15 SRAM (256 KB at
|
||||
// 0x20000000) with 4-byte alignment, and clamp the walk so we never read
|
||||
// past the end of RAM.
|
||||
const uintptr_t SRAM_START = 0x20000000UL;
|
||||
const uintptr_t SRAM_END = 0x20040000UL;
|
||||
if (psp < SRAM_START || psp >= SRAM_END || (psp & 0x3U) != 0) {
|
||||
printk("[nrf54l15] PSP out of SRAM range or unaligned, skipping walk\n");
|
||||
} else {
|
||||
const uint32_t *sp = (const uint32_t *)psp;
|
||||
int max_words = (int)((SRAM_END - psp) / sizeof(uint32_t));
|
||||
if (max_words > 96)
|
||||
max_words = 96;
|
||||
for (int i = 0; i < max_words; i++) {
|
||||
uint32_t v = sp[i];
|
||||
if (v >= 0x00001000 && v < 0x00080000 && (v & 1)) {
|
||||
printk("[nrf54l15] sp[%d]=0x%08x (code)\n", i, v);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Give the RTT/printk backend a chance to drain before we reset, otherwise
|
||||
// the crash log line above is lost and the next boot's "Prev crash" line is
|
||||
// the only forensic evidence we get.
|
||||
k_busy_wait(50000); // 50 ms
|
||||
sys_reboot(SYS_REBOOT_COLD);
|
||||
// Unreachable; k_fatal_halt as a defensive backstop in case sys_reboot
|
||||
// returns (it shouldn't).
|
||||
k_fatal_halt(reason);
|
||||
}
|
||||
|
||||
int main(void)
|
||||
{
|
||||
uint32_t reset_cause = 0;
|
||||
hwinfo_get_reset_cause(&reset_cause);
|
||||
hwinfo_clear_reset_cause();
|
||||
printk("[nrf54l15] Reset cause: 0x%08x\n", reset_cause);
|
||||
|
||||
if (saved_crash.magic == CRASH_MAGIC) {
|
||||
printk("[nrf54l15] Prev crash: reason=%u pc=0x%08x lr=0x%08x psp=0x%08x xpsr=0x%08x cfsr=0x%08x\n", saved_crash.reason,
|
||||
saved_crash.pc, saved_crash.lr, saved_crash.psp, saved_crash.xpsr, saved_crash.cfsr);
|
||||
saved_crash.magic = 0;
|
||||
}
|
||||
|
||||
printk("[nrf54l15] A: main() entry\n");
|
||||
printk("[nrf54l15] B: calling setup()\n");
|
||||
setup();
|
||||
printk("[nrf54l15] C: setup() returned\n");
|
||||
while (true) {
|
||||
loop();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
11
src/platform/nrf54l15/utility/bonding.h
Normal file
11
src/platform/nrf54l15/utility/bonding.h
Normal file
@@ -0,0 +1,11 @@
|
||||
// utility/bonding.h — stub for nRF54L15/Zephyr
|
||||
// NodeDB.cpp includes this when ARCH_NRF52 is defined.
|
||||
// Bluetooth is excluded; this stub satisfies the include chain.
|
||||
#pragma once
|
||||
|
||||
// BLE role constants (from Bluefruit SDK)
|
||||
#define BLE_GAP_ROLE_PERIPH 0x01
|
||||
#define BLE_GAP_ROLE_CENTRAL 0x02
|
||||
|
||||
// Stub for bond_print_list()
|
||||
static inline void bond_print_list(uint8_t) {}
|
||||
@@ -34,6 +34,8 @@
|
||||
// "USERPREFS_CONFIG_GPS_UPDATE_INTERVAL": "600",
|
||||
// "USERPREFS_CONFIG_POSITION_BROADCAST_INTERVAL": "1800",
|
||||
// "USERPREFS_CONFIG_DEVICE_TELEM_UPDATE_INTERVAL": "900", // Device telemetry update interval in seconds
|
||||
// "USERPREFS_CONFIG_ENV_TELEM_UPDATE_INTERVAL": "900", // Environment telemetry update interval in seconds
|
||||
// "USERPREFS_CONFIG_ENVIRONMENT_MEASUREMENT_ENABLED": "1", // Force BMP280/sensor reads + LoRa broadcast on first boot
|
||||
// "USERPREFS_LORACONFIG_CHANNEL_NUM": "31",
|
||||
// "USERPREFS_LORACONFIG_MODEM_PRESET": "meshtastic_Config_LoRaConfig_ModemPreset_SHORT_FAST",
|
||||
// "USERPREFS_USE_ADMIN_KEY_0": "{ 0xcd, 0xc0, 0xb4, 0x3c, 0x53, 0x24, 0xdf, 0x13, 0xca, 0x5a, 0xa6, 0x0c, 0x0d, 0xec, 0x85, 0x5a, 0x4c, 0xf6, 0x1a, 0x96, 0x04, 0x1a, 0x3e, 0xfc, 0xbb, 0x8e, 0x33, 0x71, 0xe5, 0xfc, 0xff, 0x3c }",
|
||||
|
||||
@@ -16,7 +16,7 @@ extra_scripts =
|
||||
extra_scripts/esp32_extra.py
|
||||
|
||||
build_src_filter =
|
||||
${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/stm32wl> -<platform/rp2xx0> -<mesh/eth/> -<mesh/raspihttp>
|
||||
${arduino_base.build_src_filter} -<platform/nrf52/> -<platform/nrf54l15/> -<platform/stm32wl> -<platform/rp2xx0> -<mesh/eth/> -<mesh/raspihttp>
|
||||
|
||||
upload_speed = 921600
|
||||
debug_init_break = tbreak setup
|
||||
|
||||
@@ -9,8 +9,9 @@ build_src_filter =
|
||||
${env.build_src_filter}
|
||||
-<platform/esp32/>
|
||||
-<nimble/>
|
||||
-<platform/nrf52/>
|
||||
-<platform/stm32wl/>
|
||||
-<platform/nrf52/>
|
||||
-<platform/nrf54l15/>
|
||||
-<platform/stm32wl/>
|
||||
-<platform/rp2xx0>
|
||||
-<mesh/wifi/>
|
||||
-<mesh/http/>
|
||||
|
||||
@@ -40,7 +40,7 @@ build_unflags =
|
||||
-std=gnu++11
|
||||
|
||||
build_src_filter =
|
||||
${arduino_base.build_src_filter} -<platform/esp32/> -<platform/stm32wl> -<nimble/> -<mesh/wifi/> -<mesh/api/> -<mesh/http/> -<modules/esp32> -<platform/rp2xx0> -<mesh/eth/> -<mesh/raspihttp> -<serialization/>
|
||||
${arduino_base.build_src_filter} -<platform/esp32/> -<platform/nrf54l15/> -<platform/stm32wl> -<nimble/> -<mesh/wifi/> -<mesh/api/> -<mesh/http/> -<modules/esp32> -<platform/rp2xx0> -<mesh/eth/> -<mesh/raspihttp> -<serialization/>
|
||||
|
||||
lib_deps=
|
||||
${arduino_base.lib_deps}
|
||||
|
||||
74
variants/nrf54l15/nrf54l15.ini
Normal file
74
variants/nrf54l15/nrf54l15.ini
Normal file
@@ -0,0 +1,74 @@
|
||||
[nrf54l15_base]
|
||||
platform = https://github.com/Seeed-Studio/platform-seeedboards.git
|
||||
framework = zephyr
|
||||
extends = arduino_base
|
||||
|
||||
build_type = release
|
||||
build_flags =
|
||||
${arduino_base.build_flags}
|
||||
-Isrc/platform/nrf54l15
|
||||
-DMESHTASTIC_EXCLUDE_AUDIO=1
|
||||
-DMESHTASTIC_EXCLUDE_GPS=1
|
||||
-DMESHTASTIC_EXCLUDE_MQTT=1
|
||||
-DHAS_WIRE=1
|
||||
-DHAS_SENSOR=1
|
||||
-DHAS_BUTTON=0
|
||||
-DHAS_TELEMETRY=1
|
||||
-DMESHTASTIC_EXCLUDE_PAXCOUNTER=1
|
||||
-DARDUINO=100
|
||||
-DMESHTASTIC_EXCLUDE_ACCELEROMETER=1
|
||||
-DMAX_NUM_NODES=40
|
||||
-fpermissive
|
||||
# Libraries that Zephyr LDF misses; add include paths explicitly
|
||||
-I.pio/libdeps/${PIOENV}/Crypto
|
||||
-I.pio/libdeps/${PIOENV}/ArduinoThread
|
||||
-I".pio/libdeps/${PIOENV}/ESP8266 and ESP32 OLED driver for SSD1306 displays/src"
|
||||
-I.pio/libdeps/${PIOENV}/OneButton/src
|
||||
-I.pio/libdeps/${PIOENV}/arduino-fsm
|
||||
-I.pio/libdeps/${PIOENV}/TinyGPSPlus/src
|
||||
-I.pio/libdeps/${PIOENV}/ErriezCRC32/src
|
||||
-I.pio/libdeps/${PIOENV}/NonBlockingRTTTL/src
|
||||
-I.pio/libdeps/${PIOENV}/RadioLib/src
|
||||
|
||||
build_src_filter =
|
||||
${arduino_base.build_src_filter}
|
||||
-<platform/esp32/>
|
||||
-<platform/stm32wl>
|
||||
-<platform/nrf52/>
|
||||
-<platform/rp2xx0>
|
||||
-<nimble/>
|
||||
-<mesh/wifi/>
|
||||
-<mesh/api/>
|
||||
-<mesh/http/>
|
||||
-<modules/esp32>
|
||||
-<mesh/eth/>
|
||||
-<mesh/raspihttp>
|
||||
-<serialization/>
|
||||
-<mqtt/>
|
||||
-<motion/>
|
||||
+<platform/nrf54l15/>
|
||||
|
||||
lib_compat_mode = off
|
||||
|
||||
lib_deps =
|
||||
${arduino_base.lib_deps}
|
||||
${radiolib_base.lib_deps}
|
||||
rweather/Crypto@0.4.0
|
||||
; Cherry-picked sensor libs from environmental_base. The full
|
||||
; environmental_base pulls Adafruit_SSD1306 / GFX which need Arduino
|
||||
; pin macros (digitalPinToPort / portOutputRegister) that the Zephyr
|
||||
; Arduino shim does not implement.
|
||||
https://github.com/adafruit/Adafruit_BusIO/archive/refs/tags/1.17.4.zip
|
||||
https://github.com/adafruit/Adafruit_Sensor/archive/refs/tags/1.1.15.zip
|
||||
https://github.com/adafruit/Adafruit_BMP280_Library/archive/refs/tags/3.0.0.zip
|
||||
https://github.com/adafruit/Adafruit_BME280_Library/archive/refs/tags/2.3.0.zip
|
||||
https://github.com/adafruit/Adafruit_INA260/archive/refs/tags/1.5.3.zip
|
||||
https://github.com/adafruit/Adafruit_INA219/archive/refs/tags/1.2.3.zip
|
||||
https://github.com/RobTillaart/INA3221_RT/archive/refs/tags/0.4.2.zip
|
||||
https://github.com/RobTillaart/INA226/archive/refs/tags/0.6.6.zip
|
||||
https://github.com/adafruit/Adafruit_SHT4X/archive/refs/tags/1.0.5.zip
|
||||
|
||||
lib_ignore =
|
||||
BluetoothOTA
|
||||
lvgl
|
||||
Adafruit_nRFCrypto
|
||||
108
variants/nrf54l15/nrf54l15dk/README.md
Normal file
108
variants/nrf54l15/nrf54l15dk/README.md
Normal file
@@ -0,0 +1,108 @@
|
||||
# nRF54L15-DK — EBYTE E22-900M30S Wiring Guide
|
||||
|
||||
Board: **Nordic nRF54L15-DK (PCA10156)**
|
||||
Radio: **EBYTE E22-900M30S** (SX1262, 30 dBm, 868/915 MHz)
|
||||
|
||||
---
|
||||
|
||||
## Why P2 (HP domain) and not P1
|
||||
|
||||
The nRF54L15 splits its GPIOs across three supply domains:
|
||||
|
||||
- **P0** — Main domain, **3.0 V** — usable
|
||||
- **P1** — LP domain, **1.8 V** — **not compatible** with the SX1262
|
||||
- **P2** — HP domain, **3.0 V** — usable
|
||||
|
||||
The SX1262 requires VIH ≥ 0.7 × VDD (≈ 2.31 V at VDD = 3.3 V). P1's 1.8 V output
|
||||
leaves the chip stuck in reset with `BUSY` never going LOW. All E22 signals
|
||||
therefore live on **P2** and are driven by **SPIM00**.
|
||||
|
||||
> `P2.09` is normally wired to LED0 on the DK; we ignore the LED and use
|
||||
> SPIM00's default MISO pin. The on-board MX25R64 NOR flash also sat on SPIM00
|
||||
> — it is deleted in the device-tree overlay to free the bus.
|
||||
|
||||
---
|
||||
|
||||
## Connections — J2 header, P2 bank
|
||||
|
||||
| E22-900M30S | GPIO | DK pin | Function |
|
||||
| ----------- | ----- | ------ | ---------------------------------------------- |
|
||||
| MISO | P2.04 | 36 | SPIM00 data in |
|
||||
| NSS / CS | P2.05 | 37 | SPI chip-select (driven by RadioLib as a GPIO) |
|
||||
| DIO1 | P2.06 | 38 | IRQ — modem interrupt (routed via gpiote30) |
|
||||
| BUSY | P2.03 | 35 | Module busy (GPIO input) |
|
||||
| NRESET | P2.00 | 32 | Module reset (GPIO output, active LOW) |
|
||||
| RXEN | P2.07 | 39 | LNA enable — held HIGH via `SX126X_ANT_SW` |
|
||||
| MOSI | P2.02 | 34 | SPIM00 data out |
|
||||
| SCK | P2.01 | 33 | SPIM00 clock |
|
||||
| GND | — | GND | Common ground |
|
||||
| VCC | — | VDD | 3.3 V |
|
||||
|
||||
> **Numbering convention**: `P0.n = n`, `P1.n = 16+n`, `P2.n = 32+n`.
|
||||
> Example: `P2.04` → 32 + 4 = **36**.
|
||||
|
||||
---
|
||||
|
||||
## DIO2 → TXEN bridge (required)
|
||||
|
||||
The E22-900M30S does **not** connect DIO2 to TXEN internally. A physical bridge on the module is required:
|
||||
|
||||
1. Locate the `DIO2` and `TXEN` pads on the underside of the E22 module.
|
||||
2. Solder a wire bridge or a 0 Ω resistor between the two pads.
|
||||
3. With this bridge, the SX1262 drives the PA automatically via `SX126X_DIO2_AS_RF_SWITCH`.
|
||||
|
||||
Without this bridge the module **will not transmit** (PA is never enabled).
|
||||
|
||||
---
|
||||
|
||||
## RXEN — LNA always on
|
||||
|
||||
`RXEN` (P2.07) is held HIGH permanently via `SX126X_ANT_SW 39` in `variant.h`.
|
||||
**Do not use** `SX126X_RXEN` — RadioLib would drive it LOW in IDLE state and
|
||||
the LNA would stay disabled (radio deaf in RX).
|
||||
|
||||
---
|
||||
|
||||
## Reserved DK pins — do not reuse
|
||||
|
||||
| Pins | Reserved function |
|
||||
| ----------- | -------------------------------------------------------- |
|
||||
| P0.00–P0.03 | IMCU debug UART (uart30, J-Link VCOM — used by RTT host) |
|
||||
| P0.04 | BTN3 |
|
||||
| P1.00–P1.01 | 32 kHz crystal |
|
||||
| P1.02–P1.03 | NFC antenna |
|
||||
| P1.10 | LED1 (status LED — kept) |
|
||||
| P1.13 | BTN0 (only remaining user button) |
|
||||
| P1.14 | LED3 |
|
||||
| P2.01–P2.05 | SPIM00 / E22 (see connection table above) |
|
||||
| P2.08–P2.10 | Trace ETM / LED2 (avoid) |
|
||||
|
||||
---
|
||||
|
||||
## Build and flash
|
||||
|
||||
```bash
|
||||
# Build
|
||||
pio run -e nrf54l15dk
|
||||
|
||||
# Flash (requires a J-Link connected via the DK's on-board IMCU)
|
||||
pio run -e nrf54l15dk -t upload
|
||||
|
||||
# Monitor RTT (channel 1 = Meshtastic logs)
|
||||
JLinkRTTLogger -device nRF54L15_xxAA -if SWD -speed 4000 -RTTChannel 1 boot.log
|
||||
```
|
||||
|
||||
Expected boot log:
|
||||
|
||||
```text
|
||||
*** Booting Zephyr OS build zephyr-v40201 ***
|
||||
[nrf54l15] Reset cause: ...
|
||||
[nrf54l15] B: calling setup()
|
||||
INFO | ... SX1262
|
||||
INFO | ... lora.begin() = 0 ← RADIOLIB_ERR_NONE
|
||||
[nrf54l15] C: setup() returned
|
||||
```
|
||||
|
||||
If you see `Record critical error 3` (`NO_RADIO`), check: DIO2→TXEN bridge,
|
||||
supply voltages (the E22 must see 3.0–3.3 V on P2, not 1.8 V), and SPI wiring
|
||||
continuity.
|
||||
24
variants/nrf54l15/nrf54l15dk/platformio.ini
Normal file
24
variants/nrf54l15/nrf54l15dk/platformio.ini
Normal file
@@ -0,0 +1,24 @@
|
||||
[env:nrf54l15dk]
|
||||
# PRIVATE_HW (255) — the protobuf HardwareModel enum reserves DK / DIY boards
|
||||
# without an SKU under PRIVATE_HW; no dedicated enum value will be assigned.
|
||||
custom_meshtastic_hw_model = 255
|
||||
custom_meshtastic_hw_model_slug = NRF54L15_DK
|
||||
custom_meshtastic_architecture = nrf54l15
|
||||
custom_meshtastic_actively_supported = false
|
||||
custom_meshtastic_support_level = 3
|
||||
custom_meshtastic_display_name = Nordic nRF54L15-DK
|
||||
|
||||
extends = nrf54l15_base
|
||||
board = nrf54l15dk
|
||||
board_level = extra
|
||||
debug_tool = jlink
|
||||
upload_protocol = jlink
|
||||
board_runner_args_jlink = --device nRF54L15_xxAA --speed 4000
|
||||
|
||||
build_flags = ${nrf54l15_base.build_flags}
|
||||
-Ivariants/nrf54l15/nrf54l15dk
|
||||
-DNRF54L15_DK
|
||||
-DMESHTASTIC_EXCLUDE_FILES_MANIFEST=1
|
||||
|
||||
build_src_filter = ${nrf54l15_base.build_src_filter}
|
||||
+<../variants/nrf54l15/nrf54l15dk>
|
||||
9
variants/nrf54l15/nrf54l15dk/variant.cpp
Normal file
9
variants/nrf54l15/nrf54l15dk/variant.cpp
Normal file
@@ -0,0 +1,9 @@
|
||||
#include "variant.h"
|
||||
|
||||
void initVariant()
|
||||
{
|
||||
// Minimal board init for nRF54L15-DK.
|
||||
// GPIO/SPI peripheral setup is handled by the Zephyr device tree overlay
|
||||
// (zephyr/boards/nrf54l15dk_nrf54l15_cpuapp.overlay).
|
||||
// Add any board-level power sequencing here if needed.
|
||||
}
|
||||
86
variants/nrf54l15/nrf54l15dk/variant.h
Normal file
86
variants/nrf54l15/nrf54l15dk/variant.h
Normal file
@@ -0,0 +1,86 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
* Nordic nRF54L15-DK (PCA10156) — Meshtastic variant
|
||||
*
|
||||
* ── GPIO voltage domains ─────────────────────────────────────────────────────
|
||||
* P0 (gpio0 @ 0x10A000) Main domain 3.0 V ← usable
|
||||
* P1 (gpio1 @ 0xd8200 ) LP domain 1.8 V ← NOT compatible with E22
|
||||
* P2 (gpio2 @ 0x50400 ) HP domain 3.0 V ← usable
|
||||
*
|
||||
* The SX1262 needs VIH ≥ 0.7 × VDD = 2.31 V (VDD = 3.3 V).
|
||||
* P1 outputs only 1.8 V → chip stays in reset, BUSY never goes LOW.
|
||||
* All E22 signals are therefore on P2 (3.0 V), driven by SPIM00.
|
||||
*
|
||||
* EBYTE E22-900M30S (SX1262) wiring — J2 header, all P2:
|
||||
*
|
||||
* E22 pin GPIO pin# Notes
|
||||
* ─────────────────────────────────────────────────────────────────────
|
||||
* MISO → P2.04 36 SPIM00 data in
|
||||
* NSS/CS → P2.05 37 SPI chip-select (RadioLib GPIO)
|
||||
* DIO1 → P2.06 38 IRQ — interrupt via gpiote30
|
||||
* BUSY → P2.03 35 GPIO input
|
||||
* NRESET → P2.00 32 GPIO output
|
||||
* RXEN → P2.07 39 Held HIGH via ANT_SW (LNA always active)
|
||||
* MOSI → P2.02 34 SPIM00 data out
|
||||
* SCK → P2.01 33 SPIM00 clock
|
||||
*
|
||||
* DIO2 → TXEN bridge required on E22 module (solder bridge / wire).
|
||||
* DIO3 drives TCXO reference (1.8 V).
|
||||
*
|
||||
* Pin numbering convention: P0.n = n, P1.n = 16+n, P2.n = 32+n.
|
||||
*
|
||||
* Reserved / do-not-use DK pins:
|
||||
* P0.00-P0.02 IMCU VCOM TX/RX/RTS pads (uart30 disabled; pads idle)
|
||||
* P0.03 I2C SDA (TWIM30) — sensor bus
|
||||
* P0.04 I2C SCL (TWIM30) — sensor bus; SW3 button on this pad,
|
||||
* DO NOT press SW3 while I2C is active
|
||||
* P1.00-P1.01 32 kHz crystal
|
||||
* P1.02-P1.03 NFC antenna
|
||||
* P1.10 LED1 (status LED — keep)
|
||||
* P1.13 BTN0 — main user button
|
||||
* P1.14 LED3
|
||||
* P2.01-P2.05 SPIM00 / E22 (see above)
|
||||
* P2.08-P2.10 Trace pins (avoid)
|
||||
*/
|
||||
|
||||
#ifndef NRF54L15_DK
|
||||
#define NRF54L15_DK
|
||||
#endif
|
||||
|
||||
// ── SX1262 / E22-900M30S — all P2, HP domain (3.0 V) ────────────────────────
|
||||
#define USE_SX1262
|
||||
#define SX126X_CS 37 // P2.05 — chip-select
|
||||
#define SX126X_DIO1 38 // P2.06 — IRQ (gpiote30 capable)
|
||||
#define SX126X_BUSY 35 // P2.03 — BUSY
|
||||
#define SX126X_RESET 32 // P2.00 — NRESET
|
||||
|
||||
// RXEN (P2.07) held HIGH permanently — LNA always active.
|
||||
// RadioLib must NOT toggle it; ANT_SW drives it HIGH before lora.begin().
|
||||
#define SX126X_ANT_SW 39 // P2.07 — RXEN driven HIGH at init
|
||||
|
||||
// DIO2 controls TXEN via bridge on E22 module.
|
||||
// DIO3 provides 1.8 V TCXO reference.
|
||||
#define SX126X_DIO2_AS_RF_SWITCH
|
||||
#define SX126X_DIO3_TCXO_VOLTAGE 1.8f
|
||||
|
||||
// ── LEDs (active HIGH) ───────────────────────────────────────────────────────
|
||||
#define PIN_LED1 26 // P1.10 — LED1 (status LED, LP domain — output only, OK)
|
||||
#define PIN_LED2 41 // P2.09 — LED0 on DK (remapped; P2.07 now used for RXEN)
|
||||
#define LED_STATE_ON 1
|
||||
|
||||
// ── Buttons (active LOW, internal pull-up) ───────────────────────────────────
|
||||
// BTN1 (P1.09), BTN2 (P1.08) and BTN3 (P0.04) deleted from DTS — only BTN0
|
||||
// remains. BTN3's pad (P0.04) is now I2C SCL.
|
||||
#define PIN_BUTTON1 29 // P1.13 — BTN0
|
||||
#define BUTTON_NEED_PULLUP
|
||||
|
||||
// ── I2C bus (TWIM30, HP domain, 3.0 V) ──────────────────────────────────────
|
||||
// SDA=P0.03, SCL=P0.04. Pinctrl + clock-frequency live in the board overlay.
|
||||
// External 4.7 kΩ pull-ups required on both lines. Meshtastic's Arduino
|
||||
// TwoWire layer (src/platform/nrf54l15/Wire.cpp) resolves the device at
|
||||
// compile time via DT_NODELABEL(i2c30); these PIN_WIRE_* defines are kept
|
||||
// for parity with the Arduino convention used by other variants.
|
||||
#define PIN_WIRE_SDA 3 // P0.03
|
||||
#define PIN_WIRE_SCL 4 // P0.04
|
||||
#define WIRE_INTERFACES_COUNT 1
|
||||
@@ -20,7 +20,7 @@ build_flags =
|
||||
-D__FREERTOS=1
|
||||
# -D _POSIX_THREADS
|
||||
build_src_filter =
|
||||
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<modules/esp32> -<platform/nrf52/> -<platform/stm32wl> -<mesh/eth/> -<mesh/wifi/> -<mesh/http/> -<mesh/raspihttp>
|
||||
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<modules/esp32> -<platform/nrf52/> -<platform/nrf54l15/> -<platform/stm32wl> -<mesh/eth/> -<mesh/wifi/> -<mesh/http/> -<mesh/raspihttp>
|
||||
|
||||
lib_ignore =
|
||||
BluetoothOTA
|
||||
|
||||
@@ -16,8 +16,8 @@ build_flags =
|
||||
-Isrc/platform/rp2xx0
|
||||
-D__PLAT_RP2350__
|
||||
-D__FREERTOS=1
|
||||
build_src_filter =
|
||||
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<modules/esp32> -<platform/nrf52/> -<platform/stm32wl> -<mesh/eth/> -<mesh/wifi/> -<mesh/http/> -<mesh/raspihttp> -<platform/rp2xx0/pico_sleep> -<platform/rp2xx0/hardware_rosc>
|
||||
build_src_filter =
|
||||
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<modules/esp32> -<platform/nrf52/> -<platform/nrf54l15/> -<platform/stm32wl> -<mesh/eth/> -<mesh/wifi/> -<mesh/http/> -<mesh/raspihttp> -<platform/rp2xx0/pico_sleep> -<platform/rp2xx0/hardware_rosc>
|
||||
|
||||
lib_ignore =
|
||||
BluetoothOTA
|
||||
|
||||
@@ -44,7 +44,7 @@ build_flags =
|
||||
-Wl,--wrap=_tzset_unlocked_r
|
||||
|
||||
build_src_filter =
|
||||
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<mesh/api/> -<mesh/wifi/> -<mesh/http/> -<modules/esp32> -<mesh/eth/> -<input> -<buzz> -<modules/RemoteHardwareModule.cpp> -<platform/nrf52> -<platform/portduino> -<platform/rp2xx0> -<mesh/raspihttp>
|
||||
${arduino_base.build_src_filter} -<platform/esp32/> -<nimble/> -<mesh/api/> -<mesh/wifi/> -<mesh/http/> -<modules/esp32> -<mesh/eth/> -<input> -<buzz> -<modules/RemoteHardwareModule.cpp> -<platform/nrf52> -<platform/nrf54l15/> -<platform/portduino> -<platform/rp2xx0> -<mesh/raspihttp>
|
||||
|
||||
board_upload.offset_address = 0x08000000
|
||||
upload_protocol = stlink
|
||||
|
||||
117
zephyr/boards/nrf54l15dk_nrf54l15_cpuapp.overlay
Normal file
117
zephyr/boards/nrf54l15dk_nrf54l15_cpuapp.overlay
Normal file
@@ -0,0 +1,117 @@
|
||||
#include <zephyr/dt-bindings/i2c/i2c.h>
|
||||
|
||||
/*
|
||||
* Zephyr device tree overlay — Nordic nRF54L15-DK + EBYTE E22-900M30S (SX1262)
|
||||
*
|
||||
* P1 GPIO bank runs at 1.8V VDDIO (LP domain) — NOT compatible with SX1262
|
||||
* which needs VIH ≥ 2.31V (0.7 × 3.3V). All E22 signals therefore use P2,
|
||||
* which is in the HP domain (3.0V VDDIO), via SPIM00.
|
||||
*
|
||||
* SPIM00 (HP domain, 3.0V) replaces SPIM20 (LP domain, 1.8V).
|
||||
* Default pinctrl from cpuapp_common.dtsi already maps SPIM00 to P2 pins:
|
||||
* MISO = P2.04, MOSI = P2.02, SCK = P2.01
|
||||
*
|
||||
* The on-board MX25R64 NOR flash was attached to SPIM00; it is not used by
|
||||
* Meshtastic (LittleFS lives in internal RRAM), so we delete its DTS node to
|
||||
* free the bus and P2.05 (its CS pin) for our use.
|
||||
*
|
||||
* Physical wiring (all P2, HP domain):
|
||||
* E22 MISO → P2.04 (SPIM00 MISO)
|
||||
* E22 NSS → P2.05 (freed from MX25R64 CS, RadioLib GPIO)
|
||||
* E22 DIO1 → P2.06 (IRQ — interrupt capable via gpiote30)
|
||||
* E22 BUSY → P2.03 (GPIO input)
|
||||
* E22 RST → P2.00 (GPIO output)
|
||||
* E22 RXEN → P2.07 (held HIGH via ANT_SW; replaces LED2 on DK)
|
||||
* E22 MOSI → P2.02 (SPIM00 MOSI)
|
||||
* E22 SCK → P2.01 (SPIM00 SCK)
|
||||
*
|
||||
* Pin numbering convention: P0.n = n, P1.n = 16+n, P2.n = 32+n.
|
||||
*/
|
||||
|
||||
/* Disable uart20 — no longer needed for LoRa (P1 domain abandoned). */
|
||||
&uart20 {
|
||||
status = "disabled";
|
||||
};
|
||||
|
||||
/* Disable uart30 to free P0.00–P0.03 from the uart30_default pinctrl (which
|
||||
* also reserves P0.03 as UART30 CTS). The peripheral instance 30 is shared
|
||||
* with i2c30/spi30 — only one of {UARTE30, TWIM30, SPIM30} can be enabled at
|
||||
* a time. We pick TWIM30 (i2c30) for sensors (SHT40 / INA3221 / SE050 on the
|
||||
* custom PCB; BMP280 / INA228 on the DK for bring-up). Console stays on RTT
|
||||
* via CONFIG_RTT_CONSOLE=y. */
|
||||
&uart30 {
|
||||
status = "disabled";
|
||||
};
|
||||
|
||||
/* I2C bus via TWIM30 (HP domain, 3.0 V), SDA=P0.03 / SCL=P0.04.
|
||||
* P0.03 was the UART30 CTS; freed by disabling uart30 above.
|
||||
* P0.04 was button SW3 on the DK; deleted below. The pad still routes to
|
||||
* the SW3 button on the board — DO NOT press SW3 during I2C use, it will
|
||||
* short SCL to GND mid-transaction.
|
||||
* 400 kHz is the highest standard rate supported by all three target sensors
|
||||
* (BMP280, INA228, SE050). External 4.7 kΩ pull-ups required on both lines. */
|
||||
&pinctrl {
|
||||
i2c30_default: i2c30_default {
|
||||
group1 {
|
||||
psels = <NRF_PSEL(TWIM_SDA, 0, 3)>,
|
||||
<NRF_PSEL(TWIM_SCL, 0, 4)>;
|
||||
bias-pull-up;
|
||||
};
|
||||
};
|
||||
|
||||
i2c30_sleep: i2c30_sleep {
|
||||
group1 {
|
||||
psels = <NRF_PSEL(TWIM_SDA, 0, 3)>,
|
||||
<NRF_PSEL(TWIM_SCL, 0, 4)>;
|
||||
low-power-enable;
|
||||
};
|
||||
};
|
||||
};
|
||||
|
||||
&i2c30 {
|
||||
status = "okay";
|
||||
clock-frequency = <I2C_BITRATE_FAST>; /* 400 kHz */
|
||||
pinctrl-0 = <&i2c30_default>;
|
||||
pinctrl-1 = <&i2c30_sleep>;
|
||||
pinctrl-names = "default", "sleep";
|
||||
};
|
||||
|
||||
/ {
|
||||
buttons {
|
||||
/* button1 (P1.09) and button2 (P1.08) no longer repurposed —
|
||||
* E22 now uses P2. button3 (P0.04) is now I2C SCL — its node
|
||||
* must be removed before the i2c30 pinctrl can claim the pad. */
|
||||
/delete-node/ button_1;
|
||||
/delete-node/ button_2;
|
||||
/delete-node/ button_3;
|
||||
};
|
||||
|
||||
aliases {
|
||||
/delete-property/ sw1;
|
||||
/delete-property/ sw2;
|
||||
/delete-property/ sw3;
|
||||
};
|
||||
};
|
||||
|
||||
/*
|
||||
* Override SPIM00 to remove the MX25R64 NOR flash child.
|
||||
* The SPIM00 peripheral itself stays enabled (status = "okay" from
|
||||
* cpuapp_common.dtsi) with its existing pinctrl (P2.01/P2.02/P2.04).
|
||||
* RadioLib drives CS (P2.05) as a plain GPIO — no hardware CS needed.
|
||||
*/
|
||||
&spi00 {
|
||||
/delete-node/ mx25r6435f@0;
|
||||
};
|
||||
|
||||
/*
|
||||
* Grow storage_partition from 36 KB to 700 KB by reclaiming slot1_partition.
|
||||
* slot1 (image-1) is the MCUboot secondary slot for dual-bank OTA, which we
|
||||
* don't use (flashing is direct via J-Link). With only 9 blocks (36 KB / 4 KB)
|
||||
* LittleFS ran out of space during COW writes of config.proto.
|
||||
* New layout: storage_partition spans 0xb6000..0x165000 (700 KB, ~175 blocks).
|
||||
*/
|
||||
/delete-node/ &slot1_partition;
|
||||
|
||||
&storage_partition {
|
||||
reg = <0xb6000 0xaf000>;
|
||||
};
|
||||
299
zephyr/prj.conf
Normal file
299
zephyr/prj.conf
Normal file
@@ -0,0 +1,299 @@
|
||||
# Zephyr project configuration for nRF54L15 Meshtastic port
|
||||
#
|
||||
# NOTE: this prj.conf is shared by ALL Zephyr PlatformIO environments
|
||||
# in this project. Keep it compatible with any future Zephyr targets.
|
||||
|
||||
# ── C++ support (required by Meshtastic) ──────────────────────────────────────
|
||||
CONFIG_CPP=y
|
||||
CONFIG_STD_CPP17=y
|
||||
# Full libstdc++ — provides <functional>, <list>, <string>, <vector>, etc.
|
||||
# Works with either newlib or picolibc (Zephyr auto-selects based on board).
|
||||
CONFIG_REQUIRES_FULL_LIBCPP=y
|
||||
# Disable C++ exceptions — not needed by Meshtastic and saves RAM/ROM
|
||||
CONFIG_CPP_EXCEPTIONS=n
|
||||
|
||||
# ── Peripheral subsystems ─────────────────────────────────────────────────────
|
||||
CONFIG_SPI=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_GPIO=y
|
||||
|
||||
# sys_reboot() used by BLE zombie-connection watchdog (BleDeferredThread).
|
||||
# nRF54L15 SW-LL occasionally drops the BLE link without forwarding
|
||||
# LE Disconnection Complete to the host; cold reboot is the only reliable
|
||||
# recovery path.
|
||||
CONFIG_REBOOT=y
|
||||
|
||||
# ── ATT Prepare/Execute Write (LONG WRITE) ───────────────────────────────────
|
||||
# iOS CoreBluetooth automatically fragments writes >MTU-3 via ATT Prepare Write
|
||||
# (opcode 0x16). Default CONFIG_BT_ATT_PREPARE_COUNT=0 makes Zephyr reject with
|
||||
# "Request Not Supported" (0x06), which iOS surfaces as a write error →
|
||||
# disconnect. With MTU=65 any ToRadio write >62 bytes triggers this path.
|
||||
# Enabling this allocates N prep_pool buffers (each BT_ATT_BUF_SIZE = 65 bytes)
|
||||
# and reassembles fragments into a single write_toradio() call on execute.
|
||||
# 4 × 65 = 260 B max assembled value — enough for typical iOS NodeInfo/admin
|
||||
# writes after config stream completes.
|
||||
CONFIG_BT_ATT_PREPARE_COUNT=4
|
||||
|
||||
# ── Filesystem — LittleFS on storage_partition (RRAM) ───────────────────────
|
||||
# Size is set by the board overlay (the nRF54L15-DK overlay reclaims slot1 to
|
||||
# expand storage_partition to ~700 KB). Capacity is reported at runtime via
|
||||
# FIXED_PARTITION_SIZE(storage_partition) in InternalFileSystem::totalBytes().
|
||||
CONFIG_FLASH=y
|
||||
CONFIG_FLASH_MAP=y
|
||||
CONFIG_FLASH_PAGE_LAYOUT=y
|
||||
CONFIG_FILE_SYSTEM=y
|
||||
CONFIG_FILE_SYSTEM_LITTLEFS=y
|
||||
CONFIG_FILE_SYSTEM_MKFS=y
|
||||
# Disable SPI NOR flash driver — MX25R64 node deleted from DTS, SPIM00 used
|
||||
# exclusively by RadioLib (SX1262). Without this, the spi_nor driver claims
|
||||
# SPIM00 at boot and tries to read MX25R64 ID (gets garbage since the chip is
|
||||
# not wired), producing "Device id a8 a8 a8 does not match config c2 28 17".
|
||||
CONFIG_SPI_NOR=n
|
||||
# Disable runtime PM — keeps SPI initialization path simple; avoids any
|
||||
# interaction between PM auto-suspend/resume cycles and the SPIM00 clock
|
||||
# request mechanism (CONFIG_CLOCK_CONTROL_NRF_HSFLL_GLOBAL).
|
||||
CONFIG_PM_DEVICE_RUNTIME=n
|
||||
# Suppress Zephyr FS subsystem's internal error/warning logs (ENOENT on
|
||||
# missing files and EEXIST on duplicate mkdir are expected and handled).
|
||||
CONFIG_FS_LOG_LEVEL_OFF=y
|
||||
|
||||
# ── Console / logging ─────────────────────────────────────────────────────────
|
||||
# Use SEGGER RTT for console — does not require COM3 (CDC UART), reads via SWD
|
||||
CONFIG_UART_CONSOLE=n
|
||||
CONFIG_USE_SEGGER_RTT=y
|
||||
CONFIG_RTT_CONSOLE=y
|
||||
CONFIG_LOG=y
|
||||
CONFIG_LOG_BACKEND_RTT=y
|
||||
CONFIG_LOG_DEFAULT_LEVEL=2
|
||||
# Immediate mode: log writes go directly to RTT backend without a separate thread.
|
||||
# Deferred mode requires the log thread to run (lowest priority — never gets CPU
|
||||
# in heavy setup()/loop() workloads), leaving the RTT buffer empty indefinitely.
|
||||
CONFIG_LOG_MODE_IMMEDIATE=y
|
||||
# Force RTT control block re-init on every boot — prevents stale/corrupted CB after crash
|
||||
CONFIG_SEGGER_RTT_INIT_MODE_ALWAYS=y
|
||||
# Use RTT channel 1 for the LOG backend, channel 0 (Terminal) for direct printk.
|
||||
# Sharing channel 0 forces LOG_PRINTK=y (deferred) to avoid corruption.
|
||||
CONFIG_LOG_BACKEND_RTT_BUFFER=1
|
||||
# Buffer sizes shrunk from 24576 → 4096 to free ~40 KB of BSS for newlib heap.
|
||||
# At 24576 the BSS pushed _end up so far that newlib heap was only ~25 KB,
|
||||
# and BUF_ACL_RX_SIZE=152 + BLE/PhoneAPI lazy init ran out of malloc space.
|
||||
# 4 KB still gives several seconds of log retention before host attaches.
|
||||
CONFIG_LOG_BACKEND_RTT_BUFFER_SIZE=4096
|
||||
# Overwrite oldest data if buffer fills — never stalls
|
||||
CONFIG_LOG_BACKEND_RTT_MODE_BLOCK=n
|
||||
CONFIG_LOG_BACKEND_RTT_MODE_OVERWRITE=y
|
||||
CONFIG_LOG_BACKEND_RTT_OUTPUT_BUFFER_SIZE=256
|
||||
|
||||
# ── LFXO clock source — use RC oscillator to avoid ~2s crystal stabilization
|
||||
# disrupting the GRTC timer and hanging k_sleep
|
||||
CONFIG_CLOCK_CONTROL_NRF_K32SRC_RC=y
|
||||
|
||||
# ── Stack sizes — Meshtastic setup() is heavy (RadioLib, NodeDB, printf) ──────
|
||||
# bt_enable() called from nrf54l15Setup() needs >8KB.
|
||||
# Phase 7: CONFIG_BT_SETTINGS=y causes bt_set_name() → settings_save_one() →
|
||||
# settings_file_save() → LittleFS I/O. The I/O chain needs ~3 KB of stack
|
||||
# headroom beyond what the BT init alone requires. Increase main stack to 24KB
|
||||
# and system workqueue to 8KB to cover both the cooperative-OSThread call path
|
||||
# (which runs on the main thread) and any async flash work items.
|
||||
CONFIG_MAIN_STACK_SIZE=24576
|
||||
CONFIG_SYSTEM_WORKQUEUE_STACK_SIZE=8192
|
||||
# Log processing thread stack — default 768 overflows when processing RTT fault dump
|
||||
CONFIG_LOG_PROCESS_THREAD_STACK_SIZE=2048
|
||||
|
||||
# ── Fault/exception diagnostics — identify ~2000ms crash ─────────────────────
|
||||
CONFIG_FAULT_DUMP=2
|
||||
CONFIG_EXCEPTION_DEBUG=y
|
||||
CONFIG_STACK_SENTINEL=y
|
||||
# Thread names + extra exception info — fault dumps then identify the failing
|
||||
# thread (otherwise "Current thread: 0x... (unknown)") and include r4-r11 + psp
|
||||
# so the custom k_sys_fatal_error_handler can walk the stack to show the caller
|
||||
# chain. Cheap (~32 B/thread for names, no perf hit) and very useful when a
|
||||
# crash recurs in the field.
|
||||
CONFIG_THREAD_NAME=y
|
||||
CONFIG_EXTRA_EXCEPTION_INFO=y
|
||||
# SEGGER RTT buffer — keep modest (4 KB) to leave RAM for newlib heap.
|
||||
CONFIG_SEGGER_RTT_BUFFER_SIZE_UP=4096
|
||||
# Report reset reason from previous crash
|
||||
CONFIG_HWINFO=y
|
||||
|
||||
# ── Bluetooth ─────────────────────────────────────────────────────────────────
|
||||
# Zephyr BT host + LL SW controller (MPSL) — peripheral role only
|
||||
CONFIG_BT=y
|
||||
CONFIG_BT_PERIPHERAL=y
|
||||
# SMP / LE Encryption enabled so the Meshtastic app pairs with a PIN before
|
||||
# accessing the GATT service.
|
||||
CONFIG_BT_SMP=y
|
||||
# Enforce MITM so clients must complete passkey exchange — without this Just
|
||||
# Works pairings complete silently without prompting the user for a PIN.
|
||||
CONFIG_BT_SMP_ENFORCE_MITM=y
|
||||
# Fixed-passkey path so the device (no display) can advertise a known PIN via
|
||||
# bt_passkey_set() when config.bluetooth.mode == FIXED_PIN.
|
||||
CONFIG_BT_FIXED_PASSKEY=y
|
||||
# Allow legacy pairing as fallback. SC_PAIR_ONLY=y has been observed to cause
|
||||
# some clients to abort pairing with reason 0x01 within 150 ms of the pairing
|
||||
# request, before any PIN dialog appears. Accepting legacy lets the same
|
||||
# clients fall through to Passkey Entry successfully.
|
||||
CONFIG_BT_SMP_SC_PAIR_ONLY=n
|
||||
# BT_LL_SW_SPLIT is auto-selected from DT (zephyr,bt-hci-ll-sw-split node in nRF54L15 DTS)
|
||||
# Do NOT set CONFIG_BT_CTLR=y (deprecated — radio silently non-functional)
|
||||
# Dynamic device name so bt_set_name() can embed the node short ID at runtime
|
||||
CONFIG_BT_DEVICE_NAME_DYNAMIC=y
|
||||
CONFIG_BT_DEVICE_NAME_MAX=32
|
||||
# Only need one simultaneous central connection
|
||||
CONFIG_BT_MAX_CONN=1
|
||||
# BT subsystem logging — INF for connection/service diagnostics
|
||||
CONFIG_BT_LOG_LEVEL_INF=y
|
||||
# BT thread stacks — defaults are too small for nRF54L15 SW-LL init.
|
||||
# prio_recv_thread overflows at 2048; bump all BT stacks to safe sizes.
|
||||
# BT RX thread runs ALL our GATT write callbacks (rx_work_handler → hci_acl →
|
||||
# bt_conn_recv → bt_l2cap_recv → bt_att_recv → write_toradio_cb →
|
||||
# PhoneAPI::handleStartConfig → getFiles("/", 10) recursion + nanopb encode).
|
||||
# 4096 overflows on "Client wants config" → abort() / kernel panic (reason 4).
|
||||
CONFIG_BT_RX_STACK_SIZE=4096
|
||||
CONFIG_BT_HCI_TX_STACK_SIZE=1024
|
||||
# bt_long_wq runs bt_pub_key_gen (ECC P256 keygen) on this thread.
|
||||
# Defaults (prio=10, stack=1400) leave it starved by Meshtastic app threads
|
||||
# at boot: pub_key gen never completes, so smp_public_key() defers
|
||||
# indefinitely waiting for sc_public_key, and every SC pairing attempt
|
||||
# stalls right after exchanging public keys (no PIN prompt on iOS, every
|
||||
# AUTHEN-gated char rejects with ATT error 0x05).
|
||||
# Prio 0 = highest preemptible, ties with main; stack 4096 clears P256M
|
||||
# driver frames with margin.
|
||||
CONFIG_BT_LONG_WQ_PRIO=0
|
||||
CONFIG_BT_LONG_WQ_STACK_SIZE=4096
|
||||
# Use legacy advertising (bt_le_adv_start / HCI 0x2006 path).
|
||||
# With CONFIG_BT_EXT_ADV=y, bt_le_adv_start() is internally translated to the
|
||||
# extended HCI path with LEGACY-bit (0x2036), which produces non-connectable PDUs
|
||||
# on the nRF54L15 SW-LL. With CONFIG_BT_EXT_ADV=n the host uses pure legacy HCI
|
||||
# commands (0x2006/0x2008/0x200a) — the same path Nordic uses in all nRF54L15
|
||||
# NCS examples (peripheral_uart, peripheral_lbs), which is iOS-compatible and
|
||||
# avoids the LE Remove Advertising Set (0x203c) controller timeout crash.
|
||||
CONFIG_BT_EXT_ADV=n
|
||||
|
||||
# ── Phase 7: BT bond persistence ──────────────────────────────────────────────
|
||||
# CONFIG_BT_SETTINGS enables the BT host settings integration: the stack
|
||||
# automatically calls settings_save_subtree("bt/keys") after pairing, and
|
||||
# settings_load() on boot restores previously bonded peers.
|
||||
#
|
||||
# Backend: SETTINGS_FILE stores all key-value pairs in a single flat file in
|
||||
# LittleFS. No new partition needed — the existing storage_partition (mounted
|
||||
# at /lfs, size set by the board overlay) is used. File path: /lfs/bt_settings.
|
||||
#
|
||||
# Ordering guarantee: LittleFS is mounted by fsInit() BEFORE nrf54l15Setup()
|
||||
# calls nrf54l15_bt_preinit(), so the file backend is always available when
|
||||
# settings_load() is called after bt_enable().
|
||||
CONFIG_BT_SETTINGS=y
|
||||
CONFIG_SETTINGS=y
|
||||
CONFIG_SETTINGS_FILE=y
|
||||
CONFIG_SETTINGS_FILE_PATH="/lfs/bt_settings"
|
||||
# BT_MAX_PAIRED default is 1 — first bond (e.g. iOS) blocks every subsequent
|
||||
# peer's SMP pairing request with "Unable to get keys" because there is no free
|
||||
# bt_keys slot to allocate. Raise to 4 so the device can simultaneously hold
|
||||
# iOS, Windows, Linux, and one spare bond. Add OVERWRITE_OLDEST so that when
|
||||
# the table fills, the LRU peer is evicted instead of rejecting the new pair.
|
||||
CONFIG_BT_MAX_PAIRED=4
|
||||
CONFIG_BT_KEYS_OVERWRITE_OLDEST=y
|
||||
# Disable GATT database caching and Service Changed characteristic.
|
||||
# CONFIG_BT_GATT_CACHING (default y with BT_SETTINGS) marks every new client as
|
||||
# "not change-aware" and returns ATT_ERR_DB_OUT_OF_SYNC (0x12) on every GATT
|
||||
# request until the client reads the DB-hash characteristic. The Meshtastic app
|
||||
# does not implement GATT caching and silently aborts service discovery on 0x12,
|
||||
# causing the connection to stall with zero GATT activity.
|
||||
# CONFIG_BT_GATT_SERVICE_CHANGED (default y) adds the Generic Attribute Profile
|
||||
# service; disabling it is required before BT_GATT_CACHING can be disabled.
|
||||
CONFIG_BT_GATT_SERVICE_CHANGED=n
|
||||
CONFIG_BT_GATT_CACHING=n
|
||||
# Disable automatic PHY update (1M→2M) after connection.
|
||||
# The nRF54L15 SW-LL fails the LL_PHY_REQ/RSP exchange and disconnects
|
||||
# exactly 1.786s after connection — before any ATT/GATT operations.
|
||||
CONFIG_BT_AUTO_PHY_UPDATE=n
|
||||
# ATT/GATT/L2CAP debug logging — see exactly what happens after connection
|
||||
CONFIG_BT_ATT_LOG_LEVEL_DBG=y
|
||||
CONFIG_BT_GATT_LOG_LEVEL_DBG=y
|
||||
CONFIG_BT_SMP_LOG_LEVEL_DBG=y
|
||||
# L2CAP DBG: shows recv on fixed ATT channel — confirms whether iOS sends any data
|
||||
CONFIG_BT_L2CAP_LOG_LEVEL_DBG=y
|
||||
# Keep bt_conn at INF — DBG floods RTT buffer every ~150µs (tx_processor loop),
|
||||
# overwriting all ATT/GATT messages before they can be read.
|
||||
# Connection events (connected/disconnected) are logged at INF level.
|
||||
CONFIG_BT_CONN_LOG_LEVEL_INF=y
|
||||
# Keep HCI logs at INF to save RAM (log thread processing buffers, etc.).
|
||||
# (Earlier DBG was used to diagnose the hci_acl → L2CAP stall — fix applied.)
|
||||
CONFIG_BT_HCI_CORE_LOG_LEVEL_INF=y
|
||||
CONFIG_BT_HCI_DRIVER_LOG_LEVEL_INF=y
|
||||
# Fix: ACL packets reach hci_acl() but never reach bt_l2cap_recv().
|
||||
# Root cause: bt_conn_recv() calls bt_conn_tx_notify(conn, true) which submits
|
||||
# tx_complete_work to k_sys_work_q and blocks on k_work_flush(). The BT rx
|
||||
# workqueue (bt_workq) is stuck in k_work_flush waiting for the system
|
||||
# workqueue, which is busy with LittleFS I/O / other work → dead stall until
|
||||
# iOS supervision timeout fires (5s) and disconnects with reason 0x13.
|
||||
# Solution: dedicate a separate workqueue for TX notify processing so it is
|
||||
# independent from the system workqueue.
|
||||
CONFIG_BT_CONN_TX_NOTIFY_WQ=y
|
||||
# Dedicated workqueue only runs tx_notify_process() (iterates tx_complete list,
|
||||
# calls short callbacks). Default 8192 is overkill and eats malloc heap needed
|
||||
# by PowerFSM init → realloc() returns NULL → bus fault during FSM::add_transition.
|
||||
CONFIG_BT_CONN_TX_NOTIFY_WQ_STACK_SIZE=2048
|
||||
|
||||
# ── ATT/L2CAP MTU — larger payloads for Meshtastic packets ───────────────────
|
||||
# TX side: controller sends up to L2CAP_TX_MTU bytes per ATT operation.
|
||||
# RX side: server ATT MTU is min(BT_L2CAP_TX_MTU, BT_BUF_ACL_RX_SIZE - 4).
|
||||
# Both set to 247 / 251 → ATT MTU = 247 in each direction, matching Zephyr's
|
||||
# samples/bluetooth/mtu_update reference. This means typical iOS ToRadio
|
||||
# writes (NodeInfo, channel settings, common admin packets) fit in a single
|
||||
# ATT_WRITE_REQ and avoid the ATT Prepare/Execute Write path entirely.
|
||||
# CONFIG_BT_ATT_PREPARE_COUNT=4 (above) still backstops oversized writes.
|
||||
#
|
||||
# Heap dependency: bumping BUF_ACL_RX_SIZE > default (~69) grows the BT host
|
||||
# net_buf pools in BSS, which proportionally shrinks the newlib heap arena
|
||||
# (MAX_HEAP_SIZE = SRAM_SIZE - (_end - SRAM_BASE), so any BSS growth steals
|
||||
# from the heap directly). Empirically the lazy BLE init path
|
||||
# (setBluetoothEnable → startDisabled → bt_set_name → settings_save →
|
||||
# LittleFS) needs ~12 KB of newlib heap to run without bad_alloc. At
|
||||
# BUF_ACL_RX_SIZE=251 with the previous 24 KB RTT buffers (LOG_BACKEND_RTT +
|
||||
# SEGGER_RTT_BUFFER_SIZE_UP), the heap collapsed to ~4 KB free at
|
||||
# transition time → `new char[]` in RedirectablePrint::log returned NULL →
|
||||
# libstdc++ called abort() from main thread. Shrinking both RTT buffers to
|
||||
# 4 KB (above) frees ~40 KB of BSS for the heap and resolves it.
|
||||
#
|
||||
# DLE stays off (BT_DATA_LEN_UPDATE=n below): the LLCP remote table at
|
||||
# ull_llcp_remote.c:878 is guarded by #ifdef CONFIG_BT_CTLR_DATA_LENGTH, so
|
||||
# the controller answers iOS's LL_LENGTH_REQ with LL_UNKNOWN_RSP and falls
|
||||
# back to 27-byte LL PDUs. The host reassembles LL PDUs into L2CAP frames
|
||||
# up to BT_BUF_ACL_RX_SIZE before dispatching to ATT.
|
||||
CONFIG_BT_L2CAP_TX_MTU=247
|
||||
# Server ATT MTU = BUF_ACL_RX_SIZE - 4 = 247 (matches L2CAP_TX_MTU)
|
||||
CONFIG_BT_BUF_ACL_RX_SIZE=251
|
||||
|
||||
# ── Fix: LL Feature Exchange collision (ROOT CAUSE of iOS GATT hang) ─────────
|
||||
# On connection, Zephyr host calls bt_hci_le_read_remote_features() because
|
||||
# BT_CTLR_PER_INIT_FEAT_XCHG=y makes can_initiate_feature_exchange() return
|
||||
# true for peripheral role. This makes the controller send LL_PER_INIT_FEAT_XCHG
|
||||
# to iOS right after connecting.
|
||||
# iOS (as central) simultaneously sends LL_FEATURE_REQ to the peripheral.
|
||||
# The nRF54L15 SW-LL mishandles this COLLISION: iOS waits for LL_FEATURE_RSP
|
||||
# to its LL_FEATURE_REQ, never gets it, and stalls — sending zero L2CAP bytes.
|
||||
# BT_CTLR_PER_INIT_FEAT_XCHG=n: host does NOT send HCI_LE_Read_Remote_Features
|
||||
# as peripheral → no LL_PER_INIT_FEAT_XCHG sent → no collision → iOS feature
|
||||
# exchange completes → iOS proceeds to L2CAP/ATT.
|
||||
CONFIG_BT_CTLR_PER_INIT_FEAT_XCHG=n
|
||||
# Fix: LL Connection Parameter Request handling.
|
||||
# BT_CTLR_CONN_PARAM_REQ=n was ineffective: the LLCP remote decode table in
|
||||
# ull_llcp_remote.c hardcodes PDU_DATA_LLCTRL_TYPE_CONN_PARAM_REQ → PROC_CONN_PARAM_REQ
|
||||
# regardless of Kconfig. With =n the handler is compiled out → controller asserts /
|
||||
# enters broken state when iOS sends LL_CONN_PARAM_REQ (which is optional from Central).
|
||||
# Fix: =y so the procedure is actually handled. To avoid host/peripheral vs Central
|
||||
# collision at 5 s (deferred_work → send_conn_le_param_update), disable auto-update
|
||||
# below so the host never initiates HCI_LE_Connection_Update.
|
||||
CONFIG_BT_CTLR_CONN_PARAM_REQ=y
|
||||
# Prevent Zephyr host from initiating connection parameter update 5 s after connect.
|
||||
# With CONN_PARAM_REQ=y, if iOS (Central) already issued LL_CONN_PARAM_REQ and the
|
||||
# SW-LL is mid-procedure, a simultaneous host-initiated HCI_LE_Connection_Update
|
||||
# creates an LL collision. Disabling the auto-update avoids the collision entirely.
|
||||
CONFIG_BT_GAP_AUTO_UPDATE_CONN_PARAMS=n
|
||||
# Disable optional LL procedures (belt-and-suspenders while debugging):
|
||||
# BT_PHY_UPDATE=n + BT_CTLR_PHY_2M=n: no PHY update procedure → iOS doesn't attempt LL_PHY_REQ
|
||||
# BT_DATA_LEN_UPDATE=n: no DLE → controller sends LL_UNKNOWN_RSP to LL_LENGTH_REQ
|
||||
CONFIG_BT_CTLR_PHY_2M=n
|
||||
CONFIG_BT_PHY_UPDATE=n
|
||||
CONFIG_BT_DATA_LEN_UPDATE=n
|
||||
Reference in New Issue
Block a user