feat(rover): SaltyRover 4-wheel ESC motor driver (Issue #110) #117

Merged
sl-jetson merged 1 commits from sl-controls/issue-110-rover-driver into main 2026-03-02 09:04:02 -05:00
Collaborator

Summary

  • kinematics.py — pure, ROS2-free module: unicycle→differential/skid-steer, speed_to_pwm (1000–2000 µs), compute_wheel_speeds with ±max clip, odometry_from_wheel_speeds inverse helper
  • rover_driver_node.py — 50 Hz ROS2 node; serial P<ch1>,<ch2>,<ch3>,<ch4>\n protocol + H\n heartbeat; deadman on /cmd_vel silence; runtime 2WD/4WD variant switch via four_wheel param (live via ros2 param set); dead-reckoning odometry; publishes /saltybot/rover_pwm (JSON) + /saltybot/rover_odom
  • config/rover_params.yaml, launch/rover_driver.launch.py, package.xml, setup.py/cfg
  • test/test_rover_kinematics.py — 51 unit tests, all passing

Test plan

  • 51 unit tests pass (pytest test/test_rover_kinematics.py)
  • Deploy to Jetson: ros2 launch saltybot_rover_driver rover_driver.launch.py
  • Verify PWM frame on ESC serial port: P1500,1500,1500,1500\n at rest
  • Test 4WD→2WD live switch: ros2 param set /rover_driver four_wheel false
  • Confirm /saltybot/rover_odom updates during motion

Closes #110

🤖 Generated with Claude Code

## Summary - **kinematics.py** — pure, ROS2-free module: unicycle→differential/skid-steer, `speed_to_pwm` (1000–2000 µs), `compute_wheel_speeds` with ±max clip, `odometry_from_wheel_speeds` inverse helper - **rover_driver_node.py** — 50 Hz ROS2 node; serial `P<ch1>,<ch2>,<ch3>,<ch4>\n` protocol + `H\n` heartbeat; deadman on `/cmd_vel` silence; runtime 2WD/4WD variant switch via `four_wheel` param (live via `ros2 param set`); dead-reckoning odometry; publishes `/saltybot/rover_pwm` (JSON) + `/saltybot/rover_odom` - **config/rover_params.yaml**, **launch/rover_driver.launch.py**, **package.xml**, **setup.py/cfg** - **test/test_rover_kinematics.py** — 51 unit tests, all passing ## Test plan - [x] 51 unit tests pass (`pytest test/test_rover_kinematics.py`) - [ ] Deploy to Jetson: `ros2 launch saltybot_rover_driver rover_driver.launch.py` - [ ] Verify PWM frame on ESC serial port: `P1500,1500,1500,1500\n` at rest - [ ] Test 4WD→2WD live switch: `ros2 param set /rover_driver four_wheel false` - [ ] Confirm `/saltybot/rover_odom` updates during motion Closes #110 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-controls added 1 commit 2026-03-02 08:45:38 -05:00
- kinematics.py: pure unicycle→differential/skid-steer kinematics,
  speed_to_pwm (1000–2000µs), compute_wheel_speeds with ±max clip,
  odometry_from_wheel_speeds inverse helper
- rover_driver_node.py: 50 Hz ROS2 node; serial P<ch1>,<ch2>,<ch3>,<ch4>\n
  protocol; heartbeat H\n; deadman on /cmd_vel silence; runtime 2WD/4WD
  variant switch via four_wheel param; dead-reckoning odometry;
  publishes /saltybot/rover_pwm (JSON) + /saltybot/rover_odom
- config/rover_params.yaml, launch/rover_driver.launch.py, package.xml,
  setup.py, setup.cfg
- test/test_rover_kinematics.py: 51 unit tests, all passing

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-webui force-pushed sl-controls/issue-110-rover-driver from e313d92012 to 3c438595e8 2026-03-02 09:03:35 -05:00 Compare
sl-jetson merged commit 7de55accc3 into main 2026-03-02 09:04:02 -05:00
Sign in to join this conversation.
No Reviewers
No Label
2 Participants
Notifications
Due Date
No due date set.
Dependencies

No dependencies set.

Reference: seb/saltylab-firmware#117
No description provided.