在调用 MotorDriver::create_motor() 创建电机实例之前,必须确保 Linux 系统的 CAN 总线接口已经正确初始化并处于 UP 状态。本页面向初学者讲解如何在 Ubuntu/Debian 系统中使用 ip 命令激活 SocketCAN 接口,涵盖标准 CAN 2.0 与 CAN-FD 两种模式,并说明接口名称(如 can0)在 SDK 内部是如何被使用的。完成本节配置后,方可继续编译 SDK 或运行示例程序。
Sources: README_CN.md
前置条件
开始配置前,请确认硬件与内核环境满足以下要求。若缺失对应硬件或内核模块,后续所有 ip 命令都会报错 No such device。
Sources: socket_can.cpp
| 检查项 | 期望结果 | 自检命令 |
|---|---|---|
| CAN 适配器已连接 | USB-CAN 分析仪或板载 CAN 控制器已接入系统 | lsusb 或 lspci 能看到设备 |
| CAN 内核模块已加载 | can、can_raw、vcan(可选)等模块已加载 |
`lsmod |
| 存在 CAN 网络接口 | 系统已生成 can0、can1 等网络设备 |
ip link show type can |
若使用虚拟 CAN(vcan)进行本地测试,可额外加载 vcan 模块并创建虚拟接口,但真实电机控制必须使用物理 CAN 适配器。
Sources: socket_can.cpp
配置流程概览
下面的流程图展示了从硬件连接到代码运行的完整准备路径。建议按照编号顺序执行。
flowchart TD
A[连接CAN适配器到PC] --> B{确认接口名称}
B -->|can0 / can1| C[选择通信模式]
C -->|DM EVO LRO| D[标准CAN 2.0]
C -->|Xynova| E[CAN-FD]
D --> F[执行ip link set up]
E --> G[执行ip link set up fd on]
F --> H[验证接口状态]
G --> H
H --> I[运行SDK或示例程序]
Sources: motor_driver.hpp
标准 CAN 2.0 配置(DM / EVO / LeadRobot)
大多数电机驱动器使用标准 CAN 2.0 协议,数据段长度固定为 8 字节,波特率通常设置为 1 Mbps。假设系统识别的接口名为 can0,在终端执行以下命令:
sudo ip link set can0 down
sudo ip link set can0 up type can bitrate 1000000
命令拆解如下:down 先关闭接口以确保状态重置;up 激活接口;type can 指定为经典 CAN;bitrate 1000000 将仲裁段与数据段均设为 1 Mbps。若系统存在多条 CAN 总线,请将 can0 替换为实际接口名(如 can1)。
Sources: socket_can.cpp
接口名称与 SDK 的关联
在创建电机对象时,第三个参数 interface 必须与上述 ip link 命令中的接口名保持一致。如下表所示,字符串 "can0" 会原样传入 MotorsSocketCAN,随后通过 ioctl(SIOCGIFINDEX) 绑定到内核的对应网络设备。
Sources: dm_motor_driver.cpp
| 位置 | 代码/命令示例 | 说明 |
|---|---|---|
| 系统配置 | sudo ip link set can0 up ... |
接口名 can0 |
| C++ 创建电机 | MotorDriver::create_motor(0x01, "can", "can0", "DM", 0) |
第三个参数为 "can0" |
| Python 创建电机 | MotorDriver.create_motor(..., interface="can0", ...) |
interface 参数为 "can0" |
| 驱动内部绑定 | MotorsCAN::get("can0") |
单例管理,同一名称共享同一 socket |
若接口名拼写错误(例如写成 can0 但系统实际为 can1),MotorsSocketCAN::open() 会在 ioctl 阶段抛出异常并提示 Unable to detect CAN interface。
Sources: socket_can.cpp
CAN-FD 配置(Xynova)
CAN-FD 在经典 CAN 基础上扩展了数据段长度(最高 64 字节)与数据段波特率。若使用支持 CAN-FD 的电机,需要在激活接口时显式开启 FD 模式并设置数据段速率。以 can0 为例:
sudo ip link set can0 down
sudo ip link set can0 up type can bitrate 1000000 dbitrate 5000000 fd on
其中 bitrate 1000000 为仲裁段速率,dbitrate 5000000 为数据段速率,fd on 启用 CAN-FD 支持。具体波特率应以电机厂商手册为准。
Sources: socket_canfd.cpp
在 SDK 层面,CAN-FD 与标准 CAN 的接口命名规则完全相同,仍通过 interface="can0" 指定。区别在于 DmMotorDriver(或其他驱动)内部会根据 interface_type=="canfd" 调用 MotorsCANFD::get(),后者在创建 socket 时会额外执行 setsockopt(sockfd_, SOL_CAN_RAW, CAN_RAW_FD_FRAMES, ...) 以启用 FD 帧解析。
Sources: socket_canfd.cpp
配置持久化(重启后保持生效)
上述 ip 命令在系统重启后会失效。若希望接口开机自动激活,推荐使用 systemd-networkd。创建配置文件 /etc/systemd/network/80-can.network:
[Match]
Name=can*
[CAN]
BitRate=1000000
对于 CAN-FD,则需额外指定数据段速率,部分发行版需借助自定义 udev 规则或 @after 脚本。由于不同 Linux 发行版的网络管理工具差异较大,本页仅提供最常见方案,具体持久化方法请参考对应系统文档。
验证与排错
配置完成后,使用以下命令检查接口状态:
ip -details link show can0
期望输出应包含 <UP, RUNNING, NOARP> 状态字样,且 qlen 不为 0。
Sources: socket_can.cpp
常见问题速查表
| 现象 | 根因 | 解决方法 |
|---|---|---|
No such device |
接口名错误或未识别到硬件 | 执行 ip link show type can 确认真实接口名 |
Device or resource busy |
接口已被其他程序占用 | 先 sudo ip link set can0 down 再重新 up |
Operation not permitted |
权限不足 | 使用 sudo 执行,或将用户加入 netdev 组 |
SDK 日志提示 Unable to detect CAN interface |
create_motor() 中的接口名与系统不一致 |
核对 ip link 输出与代码中的 interface 参数 |
| 能发送但收不到数据 | 波特率不匹配或终端电阻缺失 | 确认电机与适配器波特率一致,检查总线终端电阻 |
| CAN-FD 帧发送失败 | 未启用 fd on 或适配器不支持 FD |
确认 ip link 命令包含 fd on,并核实硬件规格 |
Sources: socket_can.cpp, socket_canfd.cpp
SDK 内部是如何绑定接口的
对于希望理解底层机制的读者,下图展示了从操作系统网络接口到电机驱动实例的映射关系。MotorsSocketCAN 采用单例模式管理每个接口名称:同一进程内,所有使用 "can0" 的电机共享同一个 socket 文件描述符,从而避免重复创建内核对象;不同接口(如 "can0" 与 "can1")则各自拥有独立实例。
graph LR
subgraph 操作系统层
A[can0<br/>ip link set up]
B[can1<br/>ip link set up]
end
subgraph SDK协议层
C[MotorsSocketCAN<br/>单例: "can0"]
D[MotorsSocketCAN<br/>单例: "can1"]
end
subgraph 驱动层
E[DM电机 #1<br/>can_=MotorsCAN::get("can0")]
F[EVO电机 #2<br/>can_=MotorsCAN::get("can0")]
G[LRO电机 #3<br/>can_=MotorsCAN::get("can1")]
end
A -->|socket+ioctl+bind| C
B -->|socket+ioctl+bind| D
C -->|共享| E
C -->|共享| F
D -->|独享| G
当电机驱动被销毁时,它会调用 remove_can_callback() 注销自身的接收回调,但不会关闭 socket;直到所有引用该接口的驱动实例均释放后,MotorsSocketCAN 析构函数才会关闭底层 socket 并恢复线程资源。
Sources: can_iso.hpp, socket_can.hpp, motor_driver.hpp
下一步
完成 CAN 接口配置后,请继续阅读:
- 编译依赖与安装 — 安装
spdlog、Boost、pybind11等依赖并编译本库 - Python SDK快速上手 — 在 Python 中创建电机并发送控制指令
- C++ SDK快速上手 — 在 C++ 中集成电机驱动库
- SocketCAN单例与无锁发送队列 — 深入了解实时线程优先级、CPU 亲和性与 TX 队列实现