feat: UWB accuracy analyzer (Issue #634) #641

Merged
sl-jetson merged 1 commits from sl-uwb/issue-634-uwb-logger into main 2026-03-15 16:30:17 -04:00
Collaborator

Summary

Jetson-side ROS2 package for continuous UWB position logging and on-demand accuracy testing at known ground-truth positions.

saltybot_uwb_logger_msgs (new package)

AccuracyReport.msg: n_samples, mean_x/y, bias_x/y, std_x/y/2d, cep50_m, cep95_m, rmse_m, max_error_m, per-anchor anchor_range_mean/std_m[], test_id, duration_s

StartAccuracyTest.srv: truth_x/y_m, n_samples, timeout_s, test_idsuccess, message, test_id

saltybot_uwb_logger (new package)

accuracy_stats.py — pure numpy, no ROS2:

  • compute_stats(xs, ys, truth_x, truth_y)AccuracyStats
    • CEP50 / CEP95 = 50th / 95th percentile of 2-D error (not Gaussian assumption)
    • RMSE, max_error, bias (systematic offset), std_2d = √(std_x²+std_y²)
  • RangeAccum — streaming mean/std for per-anchor range data

logger_node.py/uwb_logger ROS2 node:

Topic Direction CSV file
/saltybot/pose/fused subscribe fused_pose_<DATE>.csv (ts, x, y, heading)
/saltybot/uwb/pose subscribe uwb_pose_<DATE>.csv (ts, x, y)
/uwb/ranges subscribe uwb_ranges_<DATE>.csv (ts, anchor_id, range_m, raw_mm, rssi, tag_id)
/saltybot/uwb/accuracy_report publish

Service /saltybot/uwb/start_accuracy_test:

  • Accepts concurrent-test guard (returns error if already running)
  • Collects N fused-pose + per-anchor range samples in a background thread
  • On completion or timeout: publishes AccuracyReport + writes accuracy_<test_id>.json
  • CSV flushed to disk every 5 s; all file I/O disabled when enable_csv=false

Tests

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

  • Zero errors, known bias, CEP50=median error identity, RMSE formula, max_error, circle symmetry, std_2d Pythagorean, realistic 10 cm CEP50 scenario, biased UWB, RangeAccum empty/single/multi

Test plan

  • ros2 launch saltybot_uwb_logger uwb_logger.launch.py
  • Verify CSV files created in ~/uwb_logs/
  • Place robot at measured (3.0, 2.0) position, call:
    ros2 service call /saltybot/uwb/start_accuracy_test \
      saltybot_uwb_logger_msgs/srv/StartAccuracyTest \
      "{truth_x_m: 3.0, truth_y_m: 2.0, n_samples: 200, timeout_s: 30.0}"
    
  • ros2 topic echo /saltybot/uwb/accuracy_report — verify CEP50 < 0.15 m
  • Check ~/uwb_logs/accuracy_<test_id>.json written correctly
  • Repeat at 3-4 positions to characterize spatial accuracy variation

🤖 Generated with Claude Code

## Summary Jetson-side ROS2 package for continuous UWB position logging and on-demand accuracy testing at known ground-truth positions. ### `saltybot_uwb_logger_msgs` (new package) **`AccuracyReport.msg`**: `n_samples`, `mean_x/y`, `bias_x/y`, `std_x/y/2d`, `cep50_m`, `cep95_m`, `rmse_m`, `max_error_m`, per-anchor `anchor_range_mean/std_m[]`, `test_id`, `duration_s` **`StartAccuracyTest.srv`**: `truth_x/y_m`, `n_samples`, `timeout_s`, `test_id` → `success`, `message`, `test_id` ### `saltybot_uwb_logger` (new package) **`accuracy_stats.py`** — pure numpy, no ROS2: - `compute_stats(xs, ys, truth_x, truth_y)` → `AccuracyStats` - CEP50 / CEP95 = 50th / 95th percentile of 2-D error (not Gaussian assumption) - RMSE, max_error, bias (systematic offset), std_2d = √(std_x²+std_y²) - `RangeAccum` — streaming mean/std for per-anchor range data **`logger_node.py`** — `/uwb_logger` ROS2 node: | Topic | Direction | CSV file | |---|---|---| | `/saltybot/pose/fused` | subscribe | `fused_pose_<DATE>.csv` (ts, x, y, heading) | | `/saltybot/uwb/pose` | subscribe | `uwb_pose_<DATE>.csv` (ts, x, y) | | `/uwb/ranges` | subscribe | `uwb_ranges_<DATE>.csv` (ts, anchor_id, range_m, raw_mm, rssi, tag_id) | | `/saltybot/uwb/accuracy_report` | publish | — | **Service `/saltybot/uwb/start_accuracy_test`**: - Accepts concurrent-test guard (returns error if already running) - Collects N fused-pose + per-anchor range samples in a background thread - On completion or timeout: publishes `AccuracyReport` + writes `accuracy_<test_id>.json` - CSV flushed to disk every 5 s; all file I/O disabled when `enable_csv=false` ### Tests 16/16 unit tests passing (`test/test_accuracy_stats.py`) — no ROS2 or hardware: - Zero errors, known bias, CEP50=median error identity, RMSE formula, max_error, circle symmetry, std_2d Pythagorean, realistic 10 cm CEP50 scenario, biased UWB, `RangeAccum` empty/single/multi ## Test plan - [ ] `ros2 launch saltybot_uwb_logger uwb_logger.launch.py` - [ ] Verify CSV files created in `~/uwb_logs/` - [ ] Place robot at measured (3.0, 2.0) position, call: ``` ros2 service call /saltybot/uwb/start_accuracy_test \ saltybot_uwb_logger_msgs/srv/StartAccuracyTest \ "{truth_x_m: 3.0, truth_y_m: 2.0, n_samples: 200, timeout_s: 30.0}" ``` - [ ] `ros2 topic echo /saltybot/uwb/accuracy_report` — verify CEP50 < 0.15 m - [ ] Check `~/uwb_logs/accuracy_<test_id>.json` written correctly - [ ] Repeat at 3-4 positions to characterize spatial accuracy variation 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-jetson added 1 commit 2026-03-15 14:44:58 -04:00
saltybot_uwb_logger_msgs (new package):
- AccuracyReport.msg: n_samples, mean/bias/std (x,y,2D), CEP50, CEP95,
  RMSE, max_error, per-anchor range stats, test_id, duration_s
- StartAccuracyTest.srv: request (truth_x/y_m, n_samples, timeout_s,
  test_id) → response (success, message, test_id)

saltybot_uwb_logger (new package):
- accuracy_stats.py: compute_stats() + RangeAccum — pure numpy, no ROS2
  CEP50/CEP95 = 50th/95th percentile of 2-D error; bias, std, RMSE, max
- logger_node.py: /uwb_logger ROS2 node
  Subscribes:
    /saltybot/pose/fused  → fused_pose_<DATE>.csv (ts, x, y, heading)
    /saltybot/uwb/pose    → uwb_pose_<DATE>.csv   (ts, x, y)
    /uwb/ranges           → uwb_ranges_<DATE>.csv (ts, anchor_id, range_m,
                                                   raw_mm, rssi, tag_id)
  Service /saltybot/uwb/start_accuracy_test:
    Collects N fused-pose samples at known (truth_x, truth_y) in background
    thread. On completion or timeout: publishes AccuracyReport on
    /saltybot/uwb/accuracy_report + writes accuracy_<test_id>.json.
    Per-anchor range stats included. CSV flushed every 5 s.

Tests: 16/16 passing (test/test_accuracy_stats.py, no ROS2/hardware)

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-jetson merged commit 4c7fa938a5 into main 2026-03-15 16:30:17 -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#641
No description provided.