feat(perception): wheel encoder differential drive odometry (Issue #184) #318

Merged
sl-jetson merged 1 commits from sl-perception/issue-184-wheel-odom into main 2026-03-03 00:42:28 -05:00
Collaborator

Summary

Closes #184

  • New saltybot_bridge_msgs ament_cmake package with WheelTicks.msg (int32 left/right encoder counts from STM32 bridge)
  • WheelOdomNode subscribes to /saltybot/wheel_ticks (RELIABLE QoS), integrates midpoint-Euler differential drive kinematics, publishes nav_msgs/Odometry on /odom_wheel at 50 Hz
  • Optional odom → base_link TF broadcast (configurable via publish_tf param)
  • Pure-Python kinematics helper _wheel_odom.py (no ROS2 deps): unwrap_delta, ticks_to_meters, integrate_odom, normalize_angle, quat_from_yaw
  • Correctly handles STM32 int32 counter rollover (detect > 2^31, adjust ±2^32)

Parameters

Param Default Description
wheel_radius 0.034 m Effective wheel radius
wheel_base 0.160 m Centre-to-centre separation
ticks_per_rev 1000 Encoder ticks per revolution
publish_hz 50.0 Odometry publish rate
odom_frame_id odom Header frame id
base_frame_id base_link Child frame id
publish_tf true Broadcast TF transform

Test plan

  • test/test_wheel_odom.py — 42 tests, 0 failures (pure Python, no ROS2 required)
  • unwrap_delta: normal deltas, zero, positive + negative int32 rollover, symmetry
  • ticks_to_meters: zero ticks, full/half rev, negative, zero guard, proportionality
  • normalize_angle: 0, 2π→0, 3π/2→-π/2, large multiples
  • integrate_odom: straight fwd/bwd/y-axis/accumulation, rotation (left/right/spin), 4×90° closure, 360° spin closure
  • quat_from_yaw: 0, π, π/2, -π/2, unit norm for parametric yaw values

🤖 Generated with Claude Code

## Summary Closes #184 - New `saltybot_bridge_msgs` ament_cmake package with `WheelTicks.msg` (int32 left/right encoder counts from STM32 bridge) - `WheelOdomNode` subscribes to `/saltybot/wheel_ticks` (RELIABLE QoS), integrates midpoint-Euler differential drive kinematics, publishes `nav_msgs/Odometry` on `/odom_wheel` at 50 Hz - Optional `odom → base_link` TF broadcast (configurable via `publish_tf` param) - Pure-Python kinematics helper `_wheel_odom.py` (no ROS2 deps): `unwrap_delta`, `ticks_to_meters`, `integrate_odom`, `normalize_angle`, `quat_from_yaw` - Correctly handles STM32 int32 counter rollover (detect > 2^31, adjust ±2^32) ## Parameters | Param | Default | Description | |---|---|---| | `wheel_radius` | 0.034 m | Effective wheel radius | | `wheel_base` | 0.160 m | Centre-to-centre separation | | `ticks_per_rev` | 1000 | Encoder ticks per revolution | | `publish_hz` | 50.0 | Odometry publish rate | | `odom_frame_id` | `odom` | Header frame id | | `base_frame_id` | `base_link` | Child frame id | | `publish_tf` | `true` | Broadcast TF transform | ## Test plan - [x] `test/test_wheel_odom.py` — 42 tests, 0 failures (pure Python, no ROS2 required) - [x] `unwrap_delta`: normal deltas, zero, positive + negative int32 rollover, symmetry - [x] `ticks_to_meters`: zero ticks, full/half rev, negative, zero guard, proportionality - [x] `normalize_angle`: 0, 2π→0, 3π/2→-π/2, large multiples - [x] `integrate_odom`: straight fwd/bwd/y-axis/accumulation, rotation (left/right/spin), 4×90° closure, 360° spin closure - [x] `quat_from_yaw`: 0, π, π/2, -π/2, unit norm for parametric yaw values 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-perception added 1 commit 2026-03-03 00:31:21 -05:00
Adds saltybot_bridge_msgs package with WheelTicks.msg (int32 left/right
encoder counts) and a WheelOdomNode that subscribes to
/saltybot/wheel_ticks, integrates midpoint-Euler differential drive
kinematics (handling int32 counter rollover), and publishes
nav_msgs/Odometry on /odom_wheel at 50 Hz with optional TF broadcast.

New files:
  jetson/ros2_ws/src/saltybot_bridge_msgs/
    msg/WheelTicks.msg
    CMakeLists.txt, package.xml

  jetson/ros2_ws/src/saltybot_bringup/
    saltybot_bringup/_wheel_odom.py     — pure kinematics (no ROS2 deps)
    saltybot_bringup/wheel_odom_node.py — 50 Hz timer node + TF broadcast
    test/test_wheel_odom.py             — 42 tests, all passing

Modified:
  saltybot_bringup/package.xml  — add saltybot_bridge_msgs, nav_msgs deps
  saltybot_bringup/setup.py     — add wheel_odom console_script entry

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-perception force-pushed sl-perception/issue-184-wheel-odom from b4181183e7 to 067a871103 2026-03-03 00:42:03 -05:00 Compare
sl-jetson merged commit ffc69a05c0 into main 2026-03-03 00:42:28 -05: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#318
No description provided.