feat: ESP-NOW to ROS2 serial relay node (Issue #618) #621
Loading…
x
Reference in New Issue
Block a user
No description provided.
Delete Branch "sl-uwb/issue-618-espnow-relay"
Deleting a branch is permanent. Although the deleted branch may continue to exist for a short time before it actually gets removed, it CANNOT be undone in most cases. Continue?
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:EspNowPacketdataclass: parses the exact 20-byte frame from tag firmware(
magic[2],tag_id,msg_type,anchor_id,range_mmint32 LE,rssi_dbmfloat32 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):MSG_RANGE(0x10)/uwb/espnow/rangessaltybot_uwb_msgs/UwbRangeMSG_ESTOP(0x20)/uwb/espnow/estopstd_msgs/BoolMSG_ESTOP(0x20)/saltybot/estopstd_msgs/Bool(latched)MSG_HEARTBEAT(0x30)/uwb/espnow/heartbeatsaltybot_uwb_msgs/EspNowHeartbeat/saltybot/estopTrue forestop_latch_s(default 2 s) after last ESTOP packet — handles tag packet loss during button holdmin_range_m/max_range_mparams discard implausible measurementssaltybot_uwb_msgs— addsEspNowHeartbeat.msgFields:
header,tag_id,battery_pct,seq_num,timestamp_msTests
16/16 unit tests passing (
test/test_packet.py) — no ROS2 or hardware needed: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
/dev/espnow-relayappearsros2 launch saltybot_uwb_espnow_relay espnow_relay.launch.pyros2 topic echo /uwb/espnow/ranges/saltybot/estop→ True, clears after 2 s release🤖 Generated with Claude Code
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>