sl-perception 0ecf341c57 feat: Add Issue #365 — UWB DW3000 anchor/tag tracking (bearing + distance)
Software-complete implementation of the two-anchor UWB ranging stack.
All ROS2 / serial code written against an abstract interface so tests run
without physical hardware (anchors on order).

New message
- UwbTarget.msg: valid, bearing_deg, distance_m, confidence,
  anchor0/1_dist_m, baseline_m, fix_quality (0=none 1=single 2=dual)

Core library — _uwb_tracker.py (pure Python, no ROS2/runtime deps)
- parse_frame(): ASCII RANGE,<id>,<tag>,<mm> protocol decoder
- bearing_from_ranges(): law-of-cosines 2-anchor bearing with confidence
  (penalises extreme angles + close-range geometry)
- bearing_single_anchor(): fallback bearing=0, conf≤0.3
- BearingKalman: 1-D constant-velocity Kalman filter [bearing, rate]
- UwbRangingState: thread-safe per-anchor state + stale timeout + Kalman
- AnchorSerialReader: background thread, readline() interface (real or mock)

ROS2 node — uwb_node.py
- Opens /dev/ttyUSB0 + /dev/ttyUSB1 (configurable)
- Non-fatal serial open failure (will publish FIX_NONE until plugged in)
- Publishes /saltybot/uwb_target at 10 Hz (configurable)
- Graceful shutdown: stops reader threads

Tests — test/test_uwb_tracker.py: 64/64 passing
- Frame parsing: valid, malformed, STATUS, CR/LF, mm→m conversion
- Bearing geometry: straight-ahead, ±45°, ±30°, symmetry, confidence
- Kalman: seeding, smoothing, convergence, rate tracking
- UwbRangingState: single/dual fix, stale timeout, thread safety
- AnchorSerialReader: mock serial, bytes decode, stop()

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-03 15:25:23 -05:00

14 lines
670 B
Plaintext
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

std_msgs/Header header
bool valid # false when no recent UWB fix
float32 bearing_deg # horizontal bearing to tag (°, right=+, left=)
float32 distance_m # range to tag (m); arithmetic mean of both anchors
float32 confidence # 0.01.0; degrades when anchors disagree or stale
# Raw per-anchor two-way-ranging distances
float32 anchor0_dist_m # left anchor (anchor index 0)
float32 anchor1_dist_m # right anchor (anchor index 1)
# Derived geometry
float32 baseline_m # measured anchor separation (m) — used for sanity check
uint8 fix_quality # 0=no fix 1=single-anchor 2=dual-anchor