feat: Jetson command protocol — /cmd_vel to STM32 (Phase 2) #34

Merged
seb merged 1 commits from sl-jetson/command-protocol into main 2026-02-28 21:43:04 -05:00
Collaborator

Summary

Full bidirectional Jetson↔STM32 command protocol over the existing USB CDC connection.

STM32 firmware

include/jetson_cmd.h + src/jetson_cmd.c — new module, follows existing patterns:

  • C<speed>,<steer>\n — drive command (speed/steer: -1000..+1000). Buffered in ISR, parsed with sscanf in main loop (same as PID cdc_cmd_buf pattern)
  • H\n — heartbeat. Timestamp updated in ISR. STM32 deactivates Jetson commands after 500ms silence → steer reverts to 0, setpoint offset removed
  • Speed → bal.setpoint offset (±4°): jetson_cmd_sp_offset() applied around balance_update(), restored after. Balance PID still has full authority
  • Steer → motor_driver_update(…, jsteer, …) only when heartbeat alive; falls back to 0

lib/USB_CDC/src/usbd_cdc_if.cH and C cases added to CDC_Receive switch

src/main.cjetson_cmd_process() in main loop, setpoint offset, steer injection

ROS2 (Jetson)

saltybot_cmd_node.py — full bidirectional node (recommended for Nav2):

  • Owns /dev/ttyACM0 — do NOT run alongside serial_bridge_node
  • Subscribes /cmd_velC<speed>,<steer>\n (Twist mapping: linear.x * speed_scale, angular.z * steer_scale)
  • 200ms heartbeat timer → H\n
  • Sends C0,0\n on shutdown
  • All telemetry RX publishing (IMU, balance_state, diagnostics) included

serial_bridge_node.py — added write_serial() helper

launch/bridge.launch.pymode:=bidirectional (default) or mode:=rx_only

config/bridge_params.yamlspeed_scale, steer_scale, heartbeat_period docs

test/test_cmd.py — 13 tests covering zero, full fwd/rev, clamping, combined motion

Test plan

  • pytest test/ — 21/21 pass (no ROS2 runtime needed)
  • colcon build --packages-select saltybot_bridge succeeds on Jetson
  • ros2 launch saltybot_bridge bridge.launch.py → saltybot_cmd_node starts
  • Firmware compiled with jetson_cmd.c — no new warnings
  • ros2 topic pub /cmd_vel … linear.x:=0.3 → robot leans forward
  • Stop publishing /cmd_vel for >500ms → robot returns to balance setpoint
  • Angular.z commands → robot steers left/right while balancing
  • TILT_FAULT: steer/speed commands ignored (bal.state check in main loop)

🤖 Generated with Claude Code

## Summary Full bidirectional Jetson↔STM32 command protocol over the existing USB CDC connection. ### STM32 firmware **`include/jetson_cmd.h` + `src/jetson_cmd.c`** — new module, follows existing patterns: - `C<speed>,<steer>\n` — drive command (speed/steer: -1000..+1000). Buffered in ISR, parsed with sscanf in main loop (same as PID `cdc_cmd_buf` pattern) - `H\n` — heartbeat. Timestamp updated in ISR. STM32 deactivates Jetson commands after 500ms silence → steer reverts to 0, setpoint offset removed - Speed → `bal.setpoint` offset (±4°): `jetson_cmd_sp_offset()` applied around `balance_update()`, restored after. Balance PID still has full authority - Steer → `motor_driver_update(…, jsteer, …)` only when heartbeat alive; falls back to 0 **`lib/USB_CDC/src/usbd_cdc_if.c`** — `H` and `C` cases added to `CDC_Receive` switch **`src/main.c`** — `jetson_cmd_process()` in main loop, setpoint offset, steer injection ### ROS2 (Jetson) **`saltybot_cmd_node.py`** — full bidirectional node (recommended for Nav2): - Owns `/dev/ttyACM0` — do NOT run alongside `serial_bridge_node` - Subscribes `/cmd_vel` → `C<speed>,<steer>\n` (Twist mapping: `linear.x * speed_scale`, `angular.z * steer_scale`) - 200ms heartbeat timer → `H\n` - Sends `C0,0\n` on shutdown - All telemetry RX publishing (IMU, balance_state, diagnostics) included **`serial_bridge_node.py`** — added `write_serial()` helper **`launch/bridge.launch.py`** — `mode:=bidirectional` (default) or `mode:=rx_only` **`config/bridge_params.yaml`** — `speed_scale`, `steer_scale`, `heartbeat_period` docs **`test/test_cmd.py`** — 13 tests covering zero, full fwd/rev, clamping, combined motion ## Test plan - [ ] `pytest test/` — 21/21 pass (no ROS2 runtime needed) - [ ] `colcon build --packages-select saltybot_bridge` succeeds on Jetson - [ ] `ros2 launch saltybot_bridge bridge.launch.py` → saltybot_cmd_node starts - [ ] Firmware compiled with jetson_cmd.c — no new warnings - [ ] `ros2 topic pub /cmd_vel … linear.x:=0.3` → robot leans forward - [ ] Stop publishing /cmd_vel for >500ms → robot returns to balance setpoint - [ ] Angular.z commands → robot steers left/right while balancing - [ ] TILT_FAULT: steer/speed commands ignored (bal.state check in main loop) 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-jetson added 1 commit 2026-02-28 21:07:45 -05:00
STM32 firmware (C):
- include/jetson_cmd.h: protocol constants (HB_TIMEOUT_MS=500,
  SPEED_MAX_DEG=4°), API for jetson_cmd_process/is_active/steer/sp_offset
- src/jetson_cmd.c: main-loop parser for buffered C<spd>,<str> frames;
  setpoint offset = speed/1000 * 4°; steer clamped ±1000
- lib/USB_CDC/src/usbd_cdc_if.c: add H (heartbeat) and C (drive cmd) to
  CDC_Receive ISR — follows existing pattern: H updates jetson_hb_tick in
  ISR, C copied to jetson_cmd_buf for main-loop sscanf (avoids sscanf in IRQ)
- src/main.c: integrate jetson_cmd — process buffered frame, apply setpoint
  offset around balance_update(), inject steer into motor_driver_update()
  only when heartbeat alive (fallback: steer=0, setpoint unchanged)

ROS2 (Python):
- saltybot_cmd_node.py: full bidirectional node — owns serial port, handles
  telemetry RX → topics AND /cmd_vel TX → C<spd>,<str>\n + H\n heartbeat
  200ms timer; sends C0,0\n on shutdown; speed/steer_scale configurable
- serial_bridge_node.py: add write_serial() helper for extensibility
- launch/bridge.launch.py: mode arg (bidirectional|rx_only) selects node
- config/bridge_params.yaml: heartbeat_period, speed_scale, steer_scale docs
- test/test_cmd.py: 13 tests — zero, full fwd/rev, turn clamping, combined
- setup.py: saltybot_cmd_node entry point

All 21 tests pass (8 parse + 13 cmd).

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
seb approved these changes 2026-02-28 21:43:02 -05:00
seb left a comment
Owner

Flash-tested, builds and streams clean.

Flash-tested, builds and streams clean.
seb merged commit f867956b43 into main 2026-02-28 21:43:04 -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#34
No description provided.