feat: ESP-NOW to ROS2 serial relay node (Issue #618) #621

Merged
sl-jetson merged 1 commits from sl-uwb/issue-618-espnow-relay into main 2026-03-15 11:02:22 -04:00
Collaborator

Summary

Jetson-side ROS2 node that reads ESP-NOW packets forwarded by an ESP32 receiver over USB serial and publishes them as ROS2 topics.

saltybot_uwb_espnow_relay (new package)

packet.py — Pure-Python parser, no dependencies beyond stdlib:

  • EspNowPacket dataclass: parses the exact 20-byte frame from tag firmware
    (magic[2], tag_id, msg_type, anchor_id, range_mm int32 LE, rssi_dbm float32 LE, timestamp_ms, battery_pct, flags, seq_num)
  • FrameReader — stateful STX-framing decoder with XOR-CRC validation and sync recovery (re-hunts STX after bad length or CRC; works with byte-by-byte streaming)

relay_node.py — ROS2 node (/espnow_relay):

Packet type Topic Message
MSG_RANGE (0x10) /uwb/espnow/ranges saltybot_uwb_msgs/UwbRange
MSG_ESTOP (0x20) /uwb/espnow/estop std_msgs/Bool
MSG_ESTOP (0x20) /saltybot/estop std_msgs/Bool (latched)
MSG_HEARTBEAT (0x30) /uwb/espnow/heartbeat saltybot_uwb_msgs/EspNowHeartbeat
  • Background serial thread with auto-reconnect on disconnect
  • E-stop latch: holds /saltybot/estop True for estop_latch_s (default 2 s) after last ESTOP packet — handles tag packet loss during button hold
  • Range gating: min_range_m / max_range_m params discard implausible measurements

saltybot_uwb_msgs — adds EspNowHeartbeat.msg

Fields: header, tag_id, battery_pct, seq_num, timestamp_ms

Tests

16/16 unit tests passing (test/test_packet.py) — no ROS2 or hardware needed:

  • Packet parsing: RANGE, ESTOP flags, HEARTBEAT, bad magic, wrong length, negative range_mm, battery unknown (0xFF)
  • FrameReader: single frame, consecutive frames, garbage before STX, bad CRC, wrong LEN byte, split feed, byte-by-byte, recovery after truncated frame

Hardware note

The receiver ESP32 (any spare ESP32 UWB-Pro in WiFi-only mode) runs a companion sketch that receives ESP-NOW broadcasts and forwards each 20-byte packet over USB as: STX(0x02) LEN(0x14) DATA[20] XOR-CRC. A udev rule symlinks its serial port to /dev/espnow-relay.

Test plan

  • Flash receiver sketch to spare ESP32, verify /dev/espnow-relay appears
  • ros2 launch saltybot_uwb_espnow_relay espnow_relay.launch.py
  • Walk person-worn tag near receiver, verify ros2 topic echo /uwb/espnow/ranges
  • Press tag e-stop button, verify /saltybot/estop → True, clears after 2 s release
  • Unplug receiver ESP32, verify node logs warning and auto-reconnects on replug

🤖 Generated with Claude Code

## Summary Jetson-side ROS2 node that reads ESP-NOW packets forwarded by an ESP32 receiver over USB serial and publishes them as ROS2 topics. ### `saltybot_uwb_espnow_relay` (new package) **`packet.py`** — Pure-Python parser, no dependencies beyond stdlib: - `EspNowPacket` dataclass: parses the exact 20-byte frame from tag firmware (`magic[2]`, `tag_id`, `msg_type`, `anchor_id`, `range_mm` int32 LE, `rssi_dbm` float32 LE, `timestamp_ms`, `battery_pct`, `flags`, `seq_num`) - `FrameReader` — stateful STX-framing decoder with XOR-CRC validation and sync recovery (re-hunts STX after bad length or CRC; works with byte-by-byte streaming) **`relay_node.py`** — ROS2 node (`/espnow_relay`): | Packet type | Topic | Message | |---|---|---| | `MSG_RANGE` (0x10) | `/uwb/espnow/ranges` | `saltybot_uwb_msgs/UwbRange` | | `MSG_ESTOP` (0x20) | `/uwb/espnow/estop` | `std_msgs/Bool` | | `MSG_ESTOP` (0x20) | `/saltybot/estop` | `std_msgs/Bool` (latched) | | `MSG_HEARTBEAT` (0x30) | `/uwb/espnow/heartbeat` | `saltybot_uwb_msgs/EspNowHeartbeat` | - Background serial thread with auto-reconnect on disconnect - E-stop latch: holds `/saltybot/estop` True for `estop_latch_s` (default 2 s) after last ESTOP packet — handles tag packet loss during button hold - Range gating: `min_range_m` / `max_range_m` params discard implausible measurements ### `saltybot_uwb_msgs` — adds `EspNowHeartbeat.msg` Fields: `header`, `tag_id`, `battery_pct`, `seq_num`, `timestamp_ms` ### Tests 16/16 unit tests passing (`test/test_packet.py`) — no ROS2 or hardware needed: - Packet parsing: RANGE, ESTOP flags, HEARTBEAT, bad magic, wrong length, negative range_mm, battery unknown (0xFF) - FrameReader: single frame, consecutive frames, garbage before STX, bad CRC, wrong LEN byte, split feed, byte-by-byte, recovery after truncated frame ### Hardware note The receiver ESP32 (any spare ESP32 UWB-Pro in WiFi-only mode) runs a companion sketch that receives ESP-NOW broadcasts and forwards each 20-byte packet over USB as: `STX(0x02) LEN(0x14) DATA[20] XOR-CRC`. A udev rule symlinks its serial port to `/dev/espnow-relay`. ## Test plan - [ ] Flash receiver sketch to spare ESP32, verify `/dev/espnow-relay` appears - [ ] `ros2 launch saltybot_uwb_espnow_relay espnow_relay.launch.py` - [ ] Walk person-worn tag near receiver, verify `ros2 topic echo /uwb/espnow/ranges` - [ ] Press tag e-stop button, verify `/saltybot/estop` → True, clears after 2 s release - [ ] Unplug receiver ESP32, verify node logs warning and auto-reconnects on replug 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-jetson added 1 commit 2026-03-15 10:08:53 -04:00
New ROS2 package saltybot_uwb_espnow_relay:
- packet.py: EspNowPacket dataclass + FrameReader stateful decoder
  - Parses 20-byte ESP-NOW packets: MAGIC, tag_id, msg_type, anchor_id,
    range_mm (int32 LE), rssi_dbm (float32), timestamp_ms, battery_pct,
    flags (bit0=estop), seq_num
  - Serial framing: STX(0x02) + LEN(0x14) + DATA[20] + XOR-CRC(1)
  - Sync recovery: re-hunts STX after bad LEN or CRC; byte-by-byte capable
- relay_node.py: /espnow_relay ROS2 node
  - Reads from USB serial in background thread (auto-reconnects on error)
  - MSG_RANGE (0x10): publishes UwbRange on /uwb/espnow/ranges
  - MSG_ESTOP (0x20): publishes std_msgs/Bool on /uwb/espnow/estop
    and /saltybot/estop (latched True for estop_latch_s after last packet)
  - MSG_HEARTBEAT (0x30): publishes EspNowHeartbeat on /uwb/espnow/heartbeat
  - Range validity gating: min_range_m / max_range_m params
- 16/16 unit tests passing (test/test_packet.py, no ROS2/hardware needed)

saltybot_uwb_msgs: add EspNowHeartbeat.msg
  (tag_id, battery_pct, seq_num, timestamp_ms + std_msgs/Header)

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-jetson merged commit a01fa091d4 into main 2026-03-15 11:02:22 -04:00
Sign in to join this conversation.
No Reviewers
No Label
1 Participants
Notifications
Due Date
No due date set.
Dependencies

No dependencies set.

Reference: seb/saltylab-firmware#621
No description provided.