CAN Bus¶
CAN(Controller Area Network)由 Bosch 于 1986 年为汽车设计,现在是机器人、无人机、工业控制领域的核心总线。大疆 M3508/M2006 电机、宇树电机、各类商业关节驱动器几乎都使用 CAN 通信。
一、原理¶
为什么选 CAN?¶
| 特性 | CAN Bus | RS485 | UART |
|---|---|---|---|
| 拓扑 | 多主总线(任意节点可发起) | 主从 | 点对点 |
| 抗干扰 | 差分信号,极强 | 差分信号,强 | 单端,弱 |
| 错误检测 | 内置 CRC + 多重错误检测 | 可选 | 可选 |
| 优先级仲裁 | 硬件自动仲裁 | 无 | 无 |
| 最大速率 | 1 Mbps(CAN 2.0)/ 5+ Mbps(CAN FD) | 10 Mbps | ~10 Mbps |
| 典型距离 | 40 m @ 1 Mbps / 1 km @ 50 kbps | 1200 m | ~15 m |
| 节点数量 | 最多 110+ | 最多 32(标准) | 2 |
差分信号¶
CANH ──┐ ┌──┐ ┌──────
│ │ │ │
────────┘ └──┘ └────── CANL
(显性=0) (隐性=1)
差分电压: CANH - CANL
隐性(1): ~0V 差分
显性(0): ~2V 差分
CAN 总线物理层使用双绞线,差分传输对共模噪声有极强免疫力。
帧格式(CAN 2.0A 标准帧)¶
SOF │ 11-bit ID │ RTR │ IDE │ r0 │ 4-bit DLC │ 0~8 bytes DATA │ 15-bit CRC │ ACK │ EOF
1 │ 11 │ 1 │ 1 │ 1 │ 4 │ 0~64 bits │ 15 │ 2 │ 7
| 字段 | 说明 |
|---|---|
| ID(11-bit) | 报文标识符,越小优先级越高 |
| DLC | 数据长度码(0~8 字节) |
| DATA | 有效数据(最多 8 字节) |
| CRC | 15-bit 循环冗余校验 |
| ACK | 所有接收节点确认 |
CAN FD
CAN FD(Flexible Data Rate)是 CAN 2.0 的升级版,数据段最多 64 字节,速率可达 5~8 Mbps,STM32H7 系列支持 FDCAN。
总线仲裁(CSMA/CA)¶
当多个节点同时发送时,CAN 通过位仲裁决定优先级: - 显性位(0)会覆盖隐性位(1) - ID 最小的节点获得总线控制权(非破坏性仲裁)
终端电阻¶
CAN 总线两端各需要 120 Ω 终端电阻,防止信号反射。总线等效阻抗约 60 Ω。
二、STM32 使用¶
常见 STM32 CAN 控制器¶
| 系列 | 控制器 | 最大速率 | 说明 |
|---|---|---|---|
| STM32F1/F4 | bxCAN | 1 Mbps | 经典 CAN 2.0 |
| STM32H7 | FDCAN | 5+ Mbps | 支持 CAN FD |
| STM32G0/G4 | FDCAN | 5+ Mbps | 支持 CAN FD |
CAN 收发器(必须外接):MCU 的 CAN 控制器输出的是 TTL 电平,需要外接收发器芯片转换为差分信号。常用:TJA1050、TJA1051、SN65HVD230(3.3V)。
STM32 TJA1050 CAN 总线
CAN_TX ─────────► TX CANH ──────── CANH 双绞线
CAN_RX ◄───────── RX CANL ──────── CANL 双绞线
3.3V ────────────► VCC
GND ─────────────► GND
CubeMX 配置(STM32F4 bxCAN)¶
- CAN1 → Activated: ✓
- Bit Timings(以 APB1 = 42 MHz 为例,配置 1 Mbps):
- Prescaler: 3
- Time Quanta in Bit Segment 1: 11
- Time Quanta in Bit Segment 2: 2
- ReSynchronization Jump Width: 1
- NVIC:CAN1 TX、CAN1 RX0、CAN1 SCE interrupts 均勾选
- 引脚:PB8 (RX),PB9 (TX)(或 PA11/PA12,看型号)
波特率计算
CAN 波特率 = APB1 / (Prescaler × (1 + BS1 + BS2))
采样点建议在 75%~80%:(1 + BS1) / (1 + BS1 + BS2) ≈ 0.8
HAL bxCAN 发送与接收¶
/* ---- 初始化过滤器(接收所有帧)---- */
void can_filter_init(void) {
CAN_FilterTypeDef filter;
filter.FilterBank = 0;
filter.FilterMode = CAN_FILTERMODE_IDMASK; // ID掩码模式
filter.FilterScale = CAN_FILTERSCALE_32BIT;
filter.FilterIdHigh = 0x0000;
filter.FilterIdLow = 0x0000;
filter.FilterMaskIdHigh = 0x0000; // 掩码全0 = 接收所有
filter.FilterMaskIdLow = 0x0000;
filter.FilterFIFOAssignment = CAN_RX_FIFO0;
filter.FilterActivation = ENABLE;
HAL_CAN_ConfigFilter(&hcan1, &filter);
}
/* ---- 启动 CAN ---- */
// 在 MX_CAN1_Init() 后调用
HAL_CAN_Start(&hcan1);
HAL_CAN_ActivateNotification(&hcan1, CAN_IT_RX_FIFO0_MSG_PENDING);
/* ---- 发送帧 ---- */
void can_send(uint32_t id, uint8_t *data, uint8_t len) {
CAN_TxHeaderTypeDef header;
uint32_t mailbox;
header.StdId = id;
header.ExtId = 0;
header.IDE = CAN_ID_STD; // 标准帧
header.RTR = CAN_RTR_DATA; // 数据帧
header.DLC = len;
header.TransmitGlobalTime = DISABLE;
HAL_CAN_AddTxMessage(&hcan1, &header, data, &mailbox);
}
/* ---- 接收回调 ---- */
void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) {
CAN_RxHeaderTypeDef header;
uint8_t data[8];
HAL_CAN_GetRxMessage(hcan, CAN_RX_FIFO0, &header, data);
// 根据 ID 分发处理
uint32_t id = header.StdId;
uint8_t len = header.DLC;
process_can_frame(id, data, len);
}
实战:大疆 M3508/M2006 电机控制¶
大疆 M3508(配套 C620 电调)是机器人竞赛和科研中最常用的电机之一。
通信规范:
- 波特率:1 Mbps
- 控制帧 ID:0x200(电机 1~4)、0x1FF(电机 5~8)
- 反馈帧 ID:0x201 ~ 0x208(对应电机 1~8)
- 控制量:电流值,范围 -16384 ~ 16384(对应 -20A ~ 20A)
/* ---- 发送电流指令(控制 4 个电机)---- */
void rm_send_current(int16_t motor1, int16_t motor2, int16_t motor3, int16_t motor4) {
uint8_t data[8];
data[0] = (motor1 >> 8) & 0xFF;
data[1] = motor1 & 0xFF;
data[2] = (motor2 >> 8) & 0xFF;
data[3] = motor2 & 0xFF;
data[4] = (motor3 >> 8) & 0xFF;
data[5] = motor3 & 0xFF;
data[6] = (motor4 >> 8) & 0xFF;
data[7] = motor4 & 0xFF;
can_send(0x200, data, 8);
}
/* ---- 解析反馈帧 ---- */
typedef struct {
uint16_t angle; // 0 ~ 8191(机械角度)
int16_t rpm; // 转速 rpm
int16_t current; // 实际电流
uint8_t temp; // 温度 °C
} RM_MotorFeedback;
RM_MotorFeedback motors[4];
void process_can_frame(uint32_t id, uint8_t *data, uint8_t len) {
if (id >= 0x201 && id <= 0x204) {
int idx = id - 0x201;
motors[idx].angle = (data[0] << 8) | data[1];
motors[idx].rpm = (int16_t)((data[2] << 8) | data[3]);
motors[idx].current = (int16_t)((data[4] << 8) | data[5]);
motors[idx].temp = data[6];
}
}
/* ---- 简单速度 PID 控制示例 ---- */
typedef struct {
float kp, ki, kd;
float integral;
float prev_error;
float output_limit;
} PID;
float pid_update(PID *pid, float setpoint, float feedback, float dt) {
float error = setpoint - feedback;
pid->integral += error * dt;
pid->integral = fmaxf(-pid->output_limit/pid->ki,
fminf(pid->output_limit/pid->ki, pid->integral));
float derivative = (error - pid->prev_error) / dt;
pid->prev_error = error;
float out = pid->kp * error + pid->ki * pid->integral + pid->kd * derivative;
return fmaxf(-pid->output_limit, fminf(pid->output_limit, out));
}
// 在 1ms 定时器中调用:
PID speed_pid = {.kp=15, .ki=0.5, .kd=0, .output_limit=16384};
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
if (htim->Instance == TIM6) { // 1ms 定时器
float setpoint_rpm = 100.0f; // 目标转速
float feedback_rpm = motors[0].rpm;
int16_t current_cmd = (int16_t)pid_update(&speed_pid, setpoint_rpm, feedback_rpm, 0.001f);
rm_send_current(current_cmd, 0, 0, 0);
}
}
三、Linux 使用(SocketCAN)¶
SocketCAN 是 Linux 内核提供的 CAN 子系统,将 CAN 总线抽象为标准网络接口,可以用 socket 编程操作。
硬件选择¶
| 方案 | 接口 | 芯片 | 推荐度 |
|---|---|---|---|
| USB-CAN 适配器 | USB | CANable / PCAN-USB | ⭐⭐⭐⭐⭐(即插即用) |
| SPI-CAN 模块 | SPI | MCP2515 | ⭐⭐⭐⭐(树莓派常用) |
| PCIe-CAN 卡 | PCIe | PEAK、Kvaser | ⭐⭐⭐(工控机) |
| 隔离 CAN HAT | SPI | 树莓派专用扩展板 | ⭐⭐⭐⭐ |
配置 CAN 接口¶
# USB-CAN(CANable 等)通常自动识别为 can0 或 slcan0
# MCP2515 需要在 /boot/config.txt 配置:
dtoverlay=mcp2515-can0,oscillator=12000000,interrupt=25
dtoverlay=spi-bcm2835-overlay
# 配置并启动 CAN 接口
sudo ip link set can0 type can bitrate 1000000
sudo ip link set can0 up
# 查看接口状态
ip -details link show can0
# 安装 CAN 工具
sudo apt install can-utils
# 抓包(实时显示)
candump can0
# 过滤特定 ID
candump can0,201:7FF # 只看 0x201~0x207
# 发送帧(ID + 数据)
cansend can0 200#0000000000000000
Python python-can 基础¶
import can
import struct
import time
# 初始化 CAN 总线
bus = can.interface.Bus(
channel='can0',
bustype='socketcan',
bitrate=1_000_000
)
# 发送帧
def send_frame(can_id: int, data: bytes):
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
# 接收帧(阻塞,带超时)
msg = bus.recv(timeout=0.01)
if msg:
print(f"ID: 0x{msg.arbitration_id:03X} Data: {msg.data.hex()}")
完整大疆 M3508 控制(Python)¶
import can
import struct
import threading
import time
from dataclasses import dataclass, field
@dataclass
class MotorFeedback:
angle: int = 0 # 0~8191
rpm: int = 0
current: int = 0
temp: int = 0
class RM3508Controller:
"""大疆 M3508 / M2006 CAN 控制器(最多 4 台,ID 1~4)"""
CMD_ID = 0x200
def __init__(self, channel='can0', bitrate=1_000_000):
self.bus = can.interface.Bus(channel=channel, bustype='socketcan')
self.feedback: dict[int, MotorFeedback] = {i: MotorFeedback() for i in range(1, 5)}
self._running = True
self._rx_thread = threading.Thread(target=self._rx_loop, daemon=True)
self._rx_thread.start()
def _rx_loop(self):
"""后台持续接收反馈帧"""
while self._running:
msg = self.bus.recv(timeout=0.1)
if msg and 0x201 <= msg.arbitration_id <= 0x204:
motor_id = msg.arbitration_id - 0x200
d = msg.data
fb = self.feedback[motor_id]
fb.angle, = struct.unpack_from(">H", d, 0)
fb.rpm, = struct.unpack_from(">h", d, 2)
fb.current,= struct.unpack_from(">h", d, 4)
fb.temp = d[6]
def send_current(self, currents: dict[int, int]):
"""
发送电流指令
currents: {motor_id(1~4): current_value(-16384~16384)}
未指定的电机默认 0
"""
cmds = [currents.get(i, 0) for i in range(1, 5)]
data = struct.pack(">4h", *cmds)
msg = can.Message(arbitration_id=self.CMD_ID, data=data, is_extended_id=False)
self.bus.send(msg)
def get_rpm(self, motor_id: int) -> int:
return self.feedback[motor_id].rpm
def get_angle(self, motor_id: int) -> float:
return self.feedback[motor_id].angle / 8191.0 * 360.0
def stop_all(self):
self.send_current({})
def close(self):
self._running = False
self.stop_all()
self._rx_thread.join(timeout=1)
self.bus.shutdown()
# 使用示例
import signal, sys
ctrl = RM3508Controller()
def on_exit(sig, frame):
ctrl.close()
sys.exit(0)
signal.signal(signal.SIGINT, on_exit)
# 简单速度闭环
KP = 10.0
target_rpm = 100
try:
while True:
error = target_rpm - ctrl.get_rpm(1)
cmd = int(KP * error)
cmd = max(-16384, min(16384, cmd))
ctrl.send_current({1: cmd})
print(f"RPM: {ctrl.get_rpm(1)}, CMD: {cmd}")
time.sleep(0.01)
finally:
ctrl.close()
四、CANopen 简介¶
CANopen 是基于 CAN 的应用层协议,广泛用于工业自动化(电机控制器、传感器、PLC)。
| 概念 | 说明 |
|---|---|
| 对象字典(OD) | 每个节点有一个参数/数据字典,用索引+子索引访问 |
| PDO | Process Data Object,高频实时数据(周期性发送) |
| SDO | Service Data Object,配置/参数读写(请求-响应) |
| NMT | Network Management,节点状态控制(启动/停止/复位) |
| SYNC | 同步报文,触发 PDO 同步发送 |
CANopen 常用于对接商业伺服驱动器(如汇川 IS620N、松下 MINAS A6 等)。
五、注意事项¶
硬件
- 必须两端各接 120 Ω 终端电阻,否则信号反射导致误码,距离越长影响越大
- 使用双绞线,不要用普通平行线,双绞线大幅降低共模干扰
- CAN 收发器是必须的,不能把 MCU 的 CANTX 直接接到总线
- 多节点系统中,每个节点的 GND 必须通过低阻抗路径连接
软件
- 过滤器配置:生产环境中应配置 CAN 过滤器,只接收本节点需要的 ID,降低 CPU 负载
- 总线离线恢复:CAN 控制器有 Bus-Off 状态,需要软件检测并重新初始化
- 发送邮箱满:bxCAN 只有 3 个发送邮箱,高频发送时需要检查
HAL_CAN_GetTxMailboxesFreeLevel
调试
- 用
candump -td can0抓包,-td显示时间戳,方便分析时序 cananalyzer(免费工具)或CANdb++可以解析 DBC 数据库文件,自动解码信号- 怀疑总线问题时,用万用表测量 CANH 和 CANL 对地电压:空闲时约 2.5V,差值约 0V
- 使用
canbusload can0@1000000统计总线负载率