New packages
------------
saltybot_uwb_msgs (ament_cmake)
• UwbRange.msg — per-anchor range reading (anchor_id, range_m, raw_mm, rssi)
• UwbRangeArray.msg — array of UwbRange published on /uwb/ranges
saltybot_uwb (ament_python)
• ranging_math.py — pure triangulate_2anchor() (height-compensated TWR
geometry, 2-anchor intersection) + KalmanFilter2D
(constant-velocity, numpy-free, 16 tests pass)
• uwb_driver_node.py — SerialReader threads poll MaUWB ESP32-S3 DW3000
anchors via AT+RANGE?, triangulate, Kalman-smooth,
publish /uwb/target (PoseStamped/base_link) + /uwb/ranges
• config/uwb_config.yaml, launch/uwb.launch.py
• test/test_ranging_math.py — 16 unit tests (triangulation + Kalman), all pass
Updated saltybot_follower
-------------------------
• person_follower_node.py — adds fuse_targets() pure helper + /uwb/target
subscriber (primary, weight=0.7); /person/target secondary (weight=0.3);
weighted blend when both fresh, graceful fallback to single source; new
params uwb_weight + uwb_timeout
• person_follower_params.yaml — uwb_weight: 0.7, uwb_timeout: 1.0s
• test_person_follower.py — 7 new TestFuseTargets cases; total 60 pass
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
14 lines
436 B
Plaintext
14 lines
436 B
Plaintext
# UwbRange.msg — range measurement from a single UWB anchor
|
|
#
|
|
# anchor_id : 0 = anchor-0 (port side), 1 = anchor-1 (starboard side)
|
|
# range_m : measured horizontal range in metres (after height correction)
|
|
# raw_mm : raw TWR range from AT+RANGE? response, millimetres
|
|
# rssi : received signal strength (dBm), 0 if not reported by module
|
|
|
|
std_msgs/Header header
|
|
|
|
uint8 anchor_id
|
|
float32 range_m
|
|
uint32 raw_mm
|
|
float32 rssi
|