Compare commits

..

5 Commits

Author SHA1 Message Date
5e82878083 feat: bxCAN integration for VESC motor control and Orin comms (Issue #674)
- 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>
2026-03-17 21:41:19 -04:00
92c0628c62 feat: Orin CANable 2.0 bridge for Mamba and VESC CAN bus (Issue #674)
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>
2026-03-17 21:40:07 -04:00
7f67fc6abe Merge pull request 'fix: remap CAN from CAN2/PB12-13 to CAN1/PB8-9 (Issue #676)' (#677) from sl-firmware/issue-597-can-driver into main 2026-03-17 21:39:29 -04:00
ea5203b67d fix: bump arm pitch threshold 10°→20° (Issue #678)
Mamba is mounted at ~12° on the frame, causing all three arm-interlock
checks to block arming. Raise fabsf(bal.pitch_deg) < 10.0f to 20.0f
at lines 375, 512, 532 (JLink arm, RC arm rising-edge, CDC arm).

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-17 21:38:02 -04:00
14c80dc33c fix: remap CAN from CAN2/PB12-13 to CAN1/PB8-9 (Issue #676)
Mamba F722S MK2 does not expose PB12/PB13 externally. Waveshare CAN
module is wired to the SCL (PB8) and SDA (PB9) header pads.

Changes in can_driver_init():
- Drop __HAL_RCC_CAN2_CLK_ENABLE() — CAN1 needs no slave clock
- GPIO: GPIO_PIN_12/13 → GPIO_PIN_8/9, GPIO_AF9_CAN2 → GPIO_AF9_CAN1
- Instance: CAN2 → CAN1
- Filter bank: 14 → 0 (CAN1 master banks start at 0; bank 14 is the
  CAN2 slave-start boundary, unused here)

I2C1 is free: BME280 has been moved to I2C2 (PB10/PB11), so PB8/PB9
are available for CAN1 without any peripheral conflict.

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-03-17 20:31:59 -04:00
4 changed files with 25 additions and 22 deletions

View File

@ -5,7 +5,7 @@
#include <stdbool.h> #include <stdbool.h>
/* CAN bus driver for BLDC motor controllers (Issue #597) /* CAN bus driver for BLDC motor controllers (Issue #597)
* CAN2 on PB12 (RX, AF9) / PB13 (TX, AF9) at 500 kbps * CAN1 on PB8 (RX, AF9) / PB9 (TX, AF9) at 500 kbps (Issue #676 remap)
* APB1 = 54 MHz: PSC=6, BS1=13tq, BS2=4tq, SJW=1tq 18 tq/bit = 500 kbps * APB1 = 54 MHz: PSC=6, BS1=13tq, BS2=4tq, SJW=1tq 18 tq/bit = 500 kbps
*/ */

View File

@ -257,8 +257,9 @@
#define GIMBAL_PAN_LIMIT_DEG 180.0f // pan soft limit (deg each side) #define GIMBAL_PAN_LIMIT_DEG 180.0f // pan soft limit (deg each side)
#define GIMBAL_TILT_LIMIT_DEG 90.0f // tilt soft limit (deg each side) #define GIMBAL_TILT_LIMIT_DEG 90.0f // tilt soft limit (deg each side)
// --- CAN Bus Driver (Issue #597) --- // --- CAN Bus Driver (Issue #597, remapped Issue #676) ---
// CAN2 on PB12 (RX, AF9) / PB13 (TX, AF9) — repurposes SPI2/OSD pins (unused on balance bot) // CAN1 on PB8 (RX, AF9) / PB9 (TX, AF9) — SCL/SDA pads on Mamba F722S MK2
// I2C1 freed: BME280 moved to I2C2 (PB10/PB11); PB8/PB9 repurposed for CAN1
#define CAN_RPM_SCALE 10 // motor_cmd to RPM: 1 cmd count = 10 RPM #define CAN_RPM_SCALE 10 // motor_cmd to RPM: 1 cmd count = 10 RPM
#define CAN_TLM_HZ 1u // JLINK_TLM_CAN_STATS transmit rate (Hz) #define CAN_TLM_HZ 1u // JLINK_TLM_CAN_STATS transmit rate (Hz)

View File

@ -1,6 +1,11 @@
/* CAN bus driver for BLDC motor controllers (Issue #597) /* CAN bus driver for BLDC motor controllers (Issue #597)
* CAN2 on PB12 (RX, AF9) / PB13 (TX, AF9) at 500 kbps * CAN1 on PB8 (RX, AF9) / PB9 (TX, AF9) at 500 kbps (Issue #676 remap)
* Filter bank 14 (first CAN2 bank; SlaveStartFilterBank=14) * Filter bank 0 (CAN1 master; SlaveStartFilterBank=14)
*
* NOTE: Mamba F722S MK2 does not expose PB12/PB13 externally.
* Waveshare CAN module wired to SCL pad (PB8 = CAN1_RX) and
* SDA pad (PB9 = CAN1_TX). I2C1 is free (BME280 moved to I2C2).
* CAN1 uses AF9 on PB8/PB9 no conflict with other active peripherals.
*/ */
#include "can_driver.h" #include "can_driver.h"
@ -15,24 +20,22 @@ static can_std_frame_cb_t s_std_cb = NULL;
void can_driver_init(void) void can_driver_init(void)
{ {
/* CAN2 requires CAN1 master clock for shared filter RAM */
__HAL_RCC_CAN1_CLK_ENABLE(); __HAL_RCC_CAN1_CLK_ENABLE();
__HAL_RCC_CAN2_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE(); __HAL_RCC_GPIOB_CLK_ENABLE();
/* PB12 = CAN2_RX, PB13 = CAN2_TX, AF9 */ /* PB8 = CAN1_RX, PB9 = CAN1_TX, AF9 (Issue #676) */
GPIO_InitTypeDef gpio = {0}; GPIO_InitTypeDef gpio = {0};
gpio.Pin = GPIO_PIN_12 | GPIO_PIN_13; gpio.Pin = GPIO_PIN_8 | GPIO_PIN_9;
gpio.Mode = GPIO_MODE_AF_PP; gpio.Mode = GPIO_MODE_AF_PP;
gpio.Pull = GPIO_NOPULL; gpio.Pull = GPIO_NOPULL;
gpio.Speed = GPIO_SPEED_FREQ_HIGH; gpio.Speed = GPIO_SPEED_FREQ_HIGH;
gpio.Alternate = GPIO_AF9_CAN2; gpio.Alternate = GPIO_AF9_CAN1;
HAL_GPIO_Init(GPIOB, &gpio); HAL_GPIO_Init(GPIOB, &gpio);
/* 500 kbps @ APB1=54 MHz: PSC=6, BS1=13tq, BS2=4tq, SJW=1tq /* 500 kbps @ APB1=54 MHz: PSC=6, BS1=13tq, BS2=4tq, SJW=1tq
* bit_time = 6 × (1+13+4) / 54000000 = 2 µs 500 kbps * bit_time = 6 × (1+13+4) / 54000000 = 2 µs 500 kbps
* sample point = (1+13)/18 = 77.8% */ * sample point = (1+13)/18 = 77.8% */
s_can.Instance = CAN2; s_can.Instance = CAN1;
s_can.Init.Prescaler = CAN_PRESCALER; s_can.Init.Prescaler = CAN_PRESCALER;
s_can.Init.Mode = CAN_MODE_NORMAL; s_can.Init.Mode = CAN_MODE_NORMAL;
s_can.Init.SyncJumpWidth = CAN_SJW_1TQ; s_can.Init.SyncJumpWidth = CAN_SJW_1TQ;
@ -50,12 +53,11 @@ void can_driver_init(void)
return; return;
} }
/* Filter bank 14: 32-bit mask, FIFO0, accept ALL standard 11-bit frames. /* Filter bank 0: 32-bit mask, FIFO0, accept ALL standard 11-bit frames.
* FilterIdHigh=0, FilterMaskHigh=0 mask=0 passes every standard ID. * CAN1 is master (SlaveStartFilterBank=14). FilterIdHigh=0, MaskHigh=0
* FilterIdLow[2]=0 (IDE=0) only standard frames; mask bit[2]=0 don't * mask=0 passes every standard ID. Orin std-frame commands land here. */
* check IDE bit, but standard frames have IDE=0 by design so all pass. */
CAN_FilterTypeDef flt = {0}; CAN_FilterTypeDef flt = {0};
flt.FilterBank = 14u; flt.FilterBank = 0u;
flt.FilterMode = CAN_FILTERMODE_IDMASK; flt.FilterMode = CAN_FILTERMODE_IDMASK;
flt.FilterScale = CAN_FILTERSCALE_32BIT; flt.FilterScale = CAN_FILTERSCALE_32BIT;
flt.FilterIdHigh = 0u; flt.FilterIdHigh = 0u;

View File

@ -197,9 +197,9 @@ int main(void) {
/* Init Jetson serial binary protocol on USART1 (PB6/PB7) at 921600 baud */ /* Init Jetson serial binary protocol on USART1 (PB6/PB7) at 921600 baud */
jlink_init(); jlink_init();
/* Init CAN2 bus — PB12/PB13, 500 kbps. /* Init CAN1 bus — PB8/PB9, 500 kbps (Issues #597/#676/#674).
* Register VESC and Orin CAN callbacks BEFORE can_driver_init() so filter * Register callbacks BEFORE can_driver_init() so both are ready when
* banks are configured with both callbacks ready. (Issue #674) */ * filter banks activate. */
can_driver_set_ext_cb(vesc_can_on_frame); /* VESC STATUS → FIFO1 */ can_driver_set_ext_cb(vesc_can_on_frame); /* VESC STATUS → FIFO1 */
can_driver_set_std_cb(orin_can_on_frame); /* Orin cmds → FIFO0 */ can_driver_set_std_cb(orin_can_on_frame); /* Orin cmds → FIFO0 */
can_driver_init(); can_driver_init();
@ -396,7 +396,7 @@ int main(void) {
jlink_state.arm_req = 0u; jlink_state.arm_req = 0u;
if (!safety_remote_estop_active() && if (!safety_remote_estop_active() &&
mpu6000_is_calibrated() && mpu6000_is_calibrated() &&
bal.state == BALANCE_DISARMED && fabsf(bal.pitch_deg) < 10.0f) { bal.state == BALANCE_DISARMED && fabsf(bal.pitch_deg) < 20.0f) {
safety_arm_start(now); safety_arm_start(now);
} }
} }
@ -581,7 +581,7 @@ int main(void) {
/* Rising edge: start arm hold (motors enable after ARMING_HOLD_MS) */ /* Rising edge: start arm hold (motors enable after ARMING_HOLD_MS) */
if (!safety_remote_estop_active() && if (!safety_remote_estop_active() &&
mpu6000_is_calibrated() && mpu6000_is_calibrated() &&
bal.state == BALANCE_DISARMED && fabsf(bal.pitch_deg) < 10.0f) { bal.state == BALANCE_DISARMED && fabsf(bal.pitch_deg) < 20.0f) {
safety_arm_start(now); safety_arm_start(now);
} }
} }
@ -601,7 +601,7 @@ int main(void) {
cdc_arm_request = 0; cdc_arm_request = 0;
if (!safety_remote_estop_active() && if (!safety_remote_estop_active() &&
mpu6000_is_calibrated() && mpu6000_is_calibrated() &&
bal.state == BALANCE_DISARMED && fabsf(bal.pitch_deg) < 10.0f) { bal.state == BALANCE_DISARMED && fabsf(bal.pitch_deg) < 20.0f) {
safety_arm_start(now); safety_arm_start(now);
} }
} }