feat(tank): SaltyTank tracked-vehicle ESC driver (Issue #122) #127

Merged
sl-jetson merged 1 commits from sl-controls/issue-122-tank-driver into main 2026-03-02 09:26:19 -05:00
Collaborator

Summary

  • kinematics.pytank_speeds with slip compensation (angular_cmd = angular_z / (1-slip_factor)), skid_steer_speeds, speed_to_pwm, compute_track_speeds (2wd|4wd|tracked + ±max clip), expand_to_4ch, odometry_from_track_speeds (angular × (1-slip_factor))
  • tank_driver_node.py — 50 Hz ROS2 node; serial P<ch1>,<ch2>,<ch3>,<ch4>\n; H\n heartbeat; dual stop paths: watchdog 0.3 s + /saltybot/e_stop Bool topic (latching, cleared by new cmd_vel); runtime drive_mode + slip_factor live param switch; slip-compensated dead-reckoning; /saltybot/tank_pwm JSON + /saltybot/tank_odom
  • config/tank_params.yaml, launch/tank_driver.launch.py, package.xml, setup.py/cfg
  • test/test_tank_kinematics.py — 71/71 unit tests passing (parametric round-trip over slip {0.0, 0.1, 0.3, 0.5})

Slip compensation model

Command path: angular_cmd = angular_z / (1 - slip_factor)
Odometry path: angular_odom = (v_right - v_left) / B x (1 - slip_factor)

The corrections are complementary — consistent dead-reckoning at any slip value. Tune live: ros2 param set /tank_driver slip_factor 0.1

Test plan

  • 71 unit tests pass
  • Deploy: ros2 launch saltybot_tank_driver tank_driver.launch.py
  • Verify neutral PWM at rest
  • Zero-radius pivot via /cmd_vel (linear=0, angular!=0)
  • E-stop: ros2 topic pub /saltybot/e_stop std_msgs/Bool '{data: true}' --once
  • Live mode switch: ros2 param set /tank_driver drive_mode 4wd
  • Confirm /saltybot/tank_odom tracks motion

Closes #122

🤖 Generated with Claude Code

## Summary - **kinematics.py** — `tank_speeds` with slip compensation (`angular_cmd = angular_z / (1-slip_factor)`), `skid_steer_speeds`, `speed_to_pwm`, `compute_track_speeds` (2wd|4wd|tracked + ±max clip), `expand_to_4ch`, `odometry_from_track_speeds` (angular × (1-slip_factor)) - **tank_driver_node.py** — 50 Hz ROS2 node; serial `P<ch1>,<ch2>,<ch3>,<ch4>\n`; `H\n` heartbeat; dual stop paths: watchdog 0.3 s + `/saltybot/e_stop` Bool topic (latching, cleared by new cmd_vel); runtime `drive_mode` + `slip_factor` live param switch; slip-compensated dead-reckoning; `/saltybot/tank_pwm` JSON + `/saltybot/tank_odom` - **config/tank_params.yaml**, **launch/tank_driver.launch.py**, **package.xml**, **setup.py/cfg** - **test/test_tank_kinematics.py** — 71/71 unit tests passing (parametric round-trip over slip {0.0, 0.1, 0.3, 0.5}) ## Slip compensation model Command path: `angular_cmd = angular_z / (1 - slip_factor)` Odometry path: `angular_odom = (v_right - v_left) / B x (1 - slip_factor)` The corrections are complementary — consistent dead-reckoning at any slip value. Tune live: `ros2 param set /tank_driver slip_factor 0.1` ## Test plan - [x] 71 unit tests pass - [ ] Deploy: `ros2 launch saltybot_tank_driver tank_driver.launch.py` - [ ] Verify neutral PWM at rest - [ ] Zero-radius pivot via /cmd_vel (linear=0, angular!=0) - [ ] E-stop: `ros2 topic pub /saltybot/e_stop std_msgs/Bool '{data: true}' --once` - [ ] Live mode switch: `ros2 param set /tank_driver drive_mode 4wd` - [ ] Confirm /saltybot/tank_odom tracks motion Closes #122 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-controls added 1 commit 2026-03-02 09:16:03 -05:00
- kinematics.py: tank_speeds with slip compensation (angular_cmd scaled
  by 1/(1-slip_factor)), skid_steer_speeds (no slip), speed_to_pwm,
  compute_track_speeds (2wd|4wd|tracked modes, ±max clip), expand_to_4ch,
  odometry_from_track_speeds (angular scaled by (1-slip_factor) — inverse
  of command path, consistent dead-reckoning across all slip values)
- tank_driver_node.py: 50 Hz ROS2 node; serial P<ch1>,<ch2>,<ch3>,<ch4>\n;
  H\n heartbeat; dual stop paths (watchdog 0.3s + /saltybot/e_stop topic,
  latching); runtime drive_mode + slip_factor param switch; dead-reckoning
  odometry with slip compensation; publishes /saltybot/tank_pwm (JSON) +
  /saltybot/tank_odom
- config/tank_params.yaml, launch/tank_driver.launch.py, package.xml,
  setup.py, setup.cfg
- test/test_tank_kinematics.py: 71 unit tests, all passing (includes
  parametric round-trip over slip ∈ {0.0, 0.1, 0.3, 0.5})

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-jetson merged commit 89c7c5fa3e into main 2026-03-02 09:26:19 -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#127
No description provided.