saltylab-firmware/include/can_driver.h
sl-firmware 8bc2f9eeac 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 19:10:11 -04:00

102 lines
3.6 KiB
C
Raw Blame History

This file contains ambiguous Unicode characters

This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

#ifndef CAN_DRIVER_H
#define CAN_DRIVER_H
#include <stdint.h>
#include <stdbool.h>
/* CAN bus driver for BLDC motor controllers (Issue #597)
* CAN2 on PB12 (RX, AF9) / PB13 (TX, AF9) at 500 kbps
* APB1 = 54 MHz: PSC=6, BS1=13tq, BS2=4tq, SJW=1tq → 18 tq/bit = 500 kbps
*/
/* Node IDs */
#define CAN_NUM_MOTORS 2u
#define CAN_NODE_LEFT 0u
#define CAN_NODE_RIGHT 1u
/* CAN frame IDs */
#define CAN_ID_VEL_CMD_BASE 0x100u /* TX: 0x100 + node_id — velocity/torque command */
#define CAN_ID_ENABLE_CMD_BASE 0x110u /* TX: 0x110 + node_id — enable/disable */
#define CAN_ID_FEEDBACK_BASE 0x200u /* RX: 0x200 + node_id — position/velocity/current */
/* Filter: accept standard IDs 0x2000x21F */
#define CAN_FILTER_STDID 0x200u
#define CAN_FILTER_MASK 0x7E0u
/* Bit timing (500 kbps @ 54 MHz APB1) */
#define CAN_PRESCALER 6u
/* TX rate */
#define CAN_TX_RATE_HZ 100u
/* Node alive timeout */
#define CAN_NODE_TIMEOUT_MS 100u
/* TX command frame (8 bytes payload, DLC=4 for vel cmd) */
typedef struct {
int16_t velocity_rpm; /* target RPM (+/- = fwd/rev) */
int16_t torque_x100; /* torque limit × 100 (0 = unlimited) */
} can_cmd_t;
/* RX feedback frame (DLC=8) */
typedef struct {
int16_t velocity_rpm; /* actual RPM */
int16_t current_ma; /* phase current in mA */
int16_t position_x100; /* position × 100 (degrees or encoder counts) */
int8_t temperature_c; /* controller temperature °C */
uint8_t fault; /* fault flags (0 = healthy) */
uint32_t last_rx_ms; /* HAL_GetTick() at last valid frame */
} can_feedback_t;
/* Bus statistics */
typedef struct {
uint32_t tx_count; /* frames transmitted */
uint32_t rx_count; /* frames received */
uint16_t err_count; /* HAL-level errors */
uint8_t bus_off; /* 1 = bus-off state */
uint8_t _pad;
} can_stats_t;
/* Initialise CAN2 peripheral, GPIO, and filter bank 14 */
void can_driver_init(void);
/* Send velocity+torque command to one node */
void can_driver_send_cmd(uint8_t node_id, const can_cmd_t *cmd);
/* Send enable/disable command to one node */
void can_driver_send_enable(uint8_t node_id, bool enable);
/* Copy latest feedback snapshot (returns false if node never heard from) */
bool can_driver_get_feedback(uint8_t node_id, can_feedback_t *out);
/* Returns true if node has been heard within CAN_NODE_TIMEOUT_MS */
bool can_driver_is_alive(uint8_t node_id, uint32_t now_ms);
/* Copy bus statistics snapshot */
void can_driver_get_stats(can_stats_t *out);
/* Drain RX FIFO0; call every main-loop tick */
void can_driver_process(void);
/* ---- Extended / standard frame support (Issue #674) ---- */
/* Callback for extended-ID (29-bit) frames arriving in FIFO1 (VESC STATUS) */
typedef void (*can_ext_frame_cb_t)(uint32_t ext_id, const uint8_t *data, uint8_t len);
/* Callback for standard-ID (11-bit) frames arriving in FIFO0 (Orin commands) */
typedef void (*can_std_frame_cb_t)(uint16_t std_id, const uint8_t *data, uint8_t len);
/* Register callback for 29-bit extended frames (register before can_driver_init) */
void can_driver_set_ext_cb(can_ext_frame_cb_t cb);
/* Register callback for 11-bit standard frames (register before can_driver_init) */
void can_driver_set_std_cb(can_std_frame_cb_t cb);
/* Transmit a 29-bit extended-ID data frame (VESC RPM/current commands) */
void can_driver_send_ext(uint32_t ext_id, const uint8_t *data, uint8_t len);
/* Transmit an 11-bit standard-ID data frame (Orin telemetry broadcast) */
void can_driver_send_std(uint16_t std_id, const uint8_t *data, uint8_t len);
#endif /* CAN_DRIVER_H */