feat: Orin CAN bus bridge — CANable 2.0 (Issue #674) #675

Merged
sl-jetson merged 2 commits from sl-jetson/issue-674-can-bus-orin into main 2026-03-17 21:41:30 -04:00
Collaborator

Summary

  • Adds jetson/scripts/setup_can.sh: slcand-based bring-up/tear-down for CANable 2.0 (slcan firmware) → slcan0 at 500 kbps, with graceful error handling
  • Adds saltybot_can_bridge ROS2 package: full CAN bridge between Orin and Mamba motor controller + VESC motor controllers
  • mamba_protocol.py: all CAN message IDs and encode/decode helpers for velocity, mode, estop, IMU, battery, VESC state
  • can_bridge_node.py: subscribes /cmd_vel + /estop; publishes /can/imu, /can/battery, /can/vesc/left/state, /can/vesc/right/state, /can/connection_status; background reader thread, watchdog, auto-reconnect every 5s
  • 30 passing unit tests, no ROS2 or hardware required

Test plan

  • pytest test/test_can_bridge.py — all 30 pass
  • sudo setup_can.sh up → slcan0 comes up on Orin with CANable 2.0 plugged in
  • ros2 run saltybot_can_bridge can_bridge_node starts without error
  • /cmd_vel publishes velocity frames to Mamba on the bus
  • /estop True sends ESTOP frame + mode=2 to Mamba
  • CAN disconnect triggers "disconnected" on /can/connection_status within 5s
  • Reconnect restores "connected" status

Generated with Claude Code

## Summary - Adds jetson/scripts/setup_can.sh: slcand-based bring-up/tear-down for CANable 2.0 (slcan firmware) → slcan0 at 500 kbps, with graceful error handling - Adds saltybot_can_bridge ROS2 package: full CAN bridge between Orin and Mamba motor controller + VESC motor controllers - mamba_protocol.py: all CAN message IDs and encode/decode helpers for velocity, mode, estop, IMU, battery, VESC state - can_bridge_node.py: subscribes /cmd_vel + /estop; publishes /can/imu, /can/battery, /can/vesc/left/state, /can/vesc/right/state, /can/connection_status; background reader thread, watchdog, auto-reconnect every 5s - 30 passing unit tests, no ROS2 or hardware required ## Test plan - [ ] pytest test/test_can_bridge.py — all 30 pass - [ ] sudo setup_can.sh up → slcan0 comes up on Orin with CANable 2.0 plugged in - [ ] ros2 run saltybot_can_bridge can_bridge_node starts without error - [ ] /cmd_vel publishes velocity frames to Mamba on the bus - [ ] /estop True sends ESTOP frame + mode=2 to Mamba - [ ] CAN disconnect triggers "disconnected" on /can/connection_status within 5s - [ ] Reconnect restores "connected" status Generated with Claude Code
sl-jetson added 1 commit 2026-03-17 18:54:45 -04:00
Adds slcan setup script and saltybot_can_bridge ROS2 package implementing
full CAN bus integration between the Orin and the Mamba motor controller /
VESC motor controllers via a CANable 2.0 USB dongle (slcan interface).

- jetson/scripts/setup_can.sh: slcand-based bring-up/tear-down for slcan0
  at 500 kbps with error handling (already up, device missing, retry)
- saltybot_can_bridge/mamba_protocol.py: CAN message ID constants and
  encode/decode helpers for velocity, mode, e-stop, IMU, battery, VESC state
- saltybot_can_bridge/can_bridge_node.py: ROS2 node subscribing to /cmd_vel
  and /estop, publishing /can/imu, /can/battery, /can/vesc/{left,right}/state
  and /can/connection_status; background reader thread, watchdog zero-vel,
  auto-reconnect every 5 s on CAN error
- config/can_bridge_params.yaml: default params (slcan0, VESC IDs 56/68,
  Mamba ID 1, 0.5 s command timeout)
- test/test_can_bridge.py: 30 unit tests covering encode/decode round-trips
  and edge cases — all pass without ROS2 or CAN hardware

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-jetson added 1 commit 2026-03-17 19:10:15 -04:00
- can_driver: add filter bank 15 (all ext IDs → FIFO1) and widen bank 14
  to accept all standard IDs; add can_driver_send_ext/std and ext/std
  frame callbacks (can_driver_set_ext_cb / can_driver_set_std_cb)
- vesc_can: VESC 29-bit extended CAN protocol driver — send RPM to IDs 56
  and 68 (FSESC 6.7 Pro Mini Dual), parse STATUS/STATUS_4/STATUS_5
  big-endian payloads, alive timeout, JLINK_TLM_VESC_STATE at 1 Hz
- orin_can: Orin↔FC standard CAN protocol — HEARTBEAT/DRIVE/MODE/ESTOP
  commands in, FC_STATUS + FC_VESC broadcast at 10 Hz
- jlink: add JLINK_TLM_VESC_STATE (0x8E), jlink_tlm_vesc_state_t (22 bytes),
  jlink_send_vesc_state_tlm()
- main: wire vesc_can_init/orin_can_init; replace can_driver_send_cmd with
  vesc_can_send_rpm; inject Orin CAN speed/steer into balance PID; add
  Orin CAN estop/clear handling; add orin_can_broadcast at 10 Hz
- test: 56-test host-side suite for vesc_can; test/stubs/stm32f7xx_hal.h
  minimal HAL stub for all future host-side tests

Safety: balance PID runs independently on Mamba — if Orin CAN link drops
(orin_can_is_alive() == false) the robot continues balancing in-place.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-jetson force-pushed sl-jetson/issue-674-can-bus-orin from 8bc2f9eeac to 5e82878083 2026-03-17 21:41:23 -04:00 Compare
sl-jetson merged commit 0a2f336eb8 into main 2026-03-17 21:41:30 -04: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#675
No description provided.