Skip to main content

参考:厂商能力矩阵

厂商概览

厂商添加方法典型传输协议
达妙 (Damiao)add_damiao_motor()SocketCAN, DM 串口DM-J4310/4340
RobStrideadd_robstride_motor()SocketCANRobStride MIT
MyActuatoradd_myactuator_motor()SocketCANMyActuator RMD
HighTorqueadd_hightorque_motor()SocketCANHighTorque 原生
Hexfellowadd_hexfellow_motor()CAN-FDHexfellow MIT

控制模式支持

厂商MITPOS_VELVELFORCE_POS
达妙 (Damiao)
RobStride
MyActuator
HighTorque
Hexfellow

模式说明

模式说明参数
MIT全阻抗控制pos, vel, kp, kd, tau
POS_VEL带速度限制的位置控制pos, vlim
VEL纯速度控制vel
FORCE_POS带力限制的柔顺位置控制pos, vlim, ratio

模式选择指南

你需要什么?

├── 完全控制刚度/阻尼
│   └── MIT 模式(如果厂商支持)

├── 简单位置控制
│   └── POS_VEL 模式

├── 持续旋转(轮子、传送带)
│   └── VEL 模式

└── 夹爪或力控应用
    └── FORCE_POS 模式(如果厂商支持)

传输支持

厂商SocketCANCAN-FDDM 串口
达妙 (Damiao)
RobStride
MyActuator
HighTorque
Hexfellow✅ 必须

传输说明

传输说明使用场景
SocketCAN标准 Linux CAN大多数应用
CAN-FDCAN with Flexible Data-rateHexfellow 必须
DM 串口达妙 USB-CAN 适配器开发调试

传输选择

# 标准 SocketCAN(大多数情况)
with Controller("can0") as ctrl:
    motor = ctrl.add_damiao_motor(0x01, 0x11, "4340P")

# CAN-FD(Hexfellow 必须)
with Controller.from_socketcanfd("can0") as ctrl:
    motor = ctrl.add_hexfellow_motor(0x01, 0x00, "hexfellow")

# DM 串口桥(达妙专用)
with Controller.from_dm_serial("/dev/ttyACM0", 921600) as ctrl:
    motor = ctrl.add_damiao_motor(0x01, 0x11, "4340P")

寄存器访问

厂商读寄存器写寄存器保存到闪存
达妙 (Damiao)✅ 完整✅ 完整
RobStride✅ 参数 API✅ 参数 API
MyActuator⚠️ 有限⚠️ 有限
HighTorque⚠️ 有限⚠️ 有限
Hexfellow⚠️ 有限⚠️ 有限

达妙寄存器表

RID名称类型说明
7MST_IDu32反馈 ID
8ESC_IDu32电机 ID
9TIMEOUTu32通信超时
10CTRL_MODEu32控制模式
21PMAXf32位置范围
22VMAXf32速度范围
23TMAXf32力矩范围
25KP_ASRf32速度环 Kp
26KI_ASRf32速度环 Ki
27KP_APRf32位置环 Kp
28KI_APRf32位置环 Ki

RobStride 参数 API

# RobStride 使用参数 API,不是通用寄存器
value = motor.robstride_get_param_f32(param_id, timeout_ms)
motor.robstride_write_param_f32(param_id, value)

# 支持的类型
motor.robstride_get_param_i8(param_id, timeout_ms)
motor.robstride_get_param_u8(param_id, timeout_ms)
motor.robstride_get_param_u16(param_id, timeout_ms)
motor.robstride_get_param_u32(param_id, timeout_ms)
motor.robstride_get_param_f32(param_id, timeout_ms)

反馈状态

厂商位置速度力矩MOS 温度转子温度
达妙 (Damiao)
RobStride
MyActuator
HighTorque
Hexfellow

特殊功能

达妙 (Damiao)

功能说明
✅ 最完整的协议支持35+ 寄存器可访问
✅ 串口桥选项DM Serial 适配器
✅ 电机 ID 配置通过寄存器修改 ID
✅ 完整寄存器访问读/写/存储

RobStride

功能说明
✅ Ping 命令发现设备/响应者 ID
✅ 参数 API类型化参数访问
✅ 设备 ID 配置修改设备 ID

MyActuator

功能说明
✅ 标准反馈格式一致的状态结构
⚠️ 无 MIT 模式使用 POS_VEL 或 VEL

HighTorque

功能说明
✅ 原生厂商协议完整模式支持
✅ 标准反馈一致的状态结构

Hexfellow

功能说明
⚠️ 需要 CAN-FD必须使用 from_socketcanfd()
⚠️ 无速度模式使用 MIT 或 POS_VEL
✅ 高带宽通信CAN-FD 数据速率

型号字符串

达妙型号

型号说明峰值力矩典型应用
4310小型~1 Nm夹爪、小关节
4340中型~4 Nm手臂、中等关节
4340P中型(位置)~4 Nm通用
6001大型~10 Nm腿部、重载

RobStride 型号

型号说明
rs-00标准 RobStride 电机

MyActuator 型号

型号说明
X8标准 MyActuator 电机

HighTorque 型号

型号说明
hightorque通用 HighTorque 电机

Hexfellow 型号

型号说明
hexfellow通用 Hexfellow 电机

CAN ID 规则

达妙

motor_id:    0x01 - 0x20(命令 ID)
feedback_id: 0x11 - 0x30(motor_id + 0x10)

示例:
  motor_id = 0x01 → feedback_id = 0x11
  motor_id = 0x0A → feedback_id = 0x1A

RobStride

motor_id:    127(设备 ID,可配置 1-127)
feedback_id: 0xFE 或 0xFF(响应者 ID)

默认:
  motor_id = 127
  feedback_id = 0xFE

MyActuator

motor_id:    1 - 32
feedback_id: 0x240 + motor_id

示例:
  motor_id = 1 → feedback_id = 0x241
  motor_id = 8 → feedback_id = 0x248

HighTorque

motor_id:    1 - 127
feedback_id: 0x01(固定)

Hexfellow

motor_id:    0x01 - 0xFF
feedback_id: 0x00(固定)

各厂商代码示例

达妙

from motorbridge import Controller, Mode

with Controller("can0") as ctrl:
    motor = ctrl.add_damiao_motor(0x01, 0x11, "4340P")
    ctrl.enable_all()
    motor.ensure_mode(Mode.MIT, 1000)
    motor.send_mit(0.5, 0.0, 30.0, 1.0, 0.0)

RobStride

from motorbridge import Controller, Mode

with Controller("can0") as ctrl:
    motor = ctrl.add_robstride_motor(127, 0xFE, "rs-00")
    ctrl.enable_all()

    # 先 Ping
    device_id, responder_id = motor.robstride_ping()
    print(f"设备: {device_id}, 响应者: {responder_id}")

    motor.ensure_mode(Mode.MIT, 1000)
    motor.send_mit(0.5, 0.0, 2.0, 0.1, 0.0)

MyActuator

from motorbridge import Controller, Mode

with Controller("can0") as ctrl:
    motor = ctrl.add_myactuator_motor(1, 0x241, "X8")
    ctrl.enable_all()
    motor.ensure_mode(Mode.POS_VEL, 1000)  # 无 MIT 模式
    motor.send_pos_vel(0.5, vlim=1.5)

HighTorque

from motorbridge import Controller, Mode

with Controller("can0") as ctrl:
    motor = ctrl.add_hightorque_motor(1, 0x01, "hightorque")
    ctrl.enable_all()
    motor.ensure_mode(Mode.MIT, 1000)
    motor.send_mit(0.5, 0.0, 30.0, 1.0, 0.0)

Hexfellow

from motorbridge import Controller, Mode

# 必须用 CAN-FD
with Controller.from_socketcanfd("can0") as ctrl:
    motor = ctrl.add_hexfellow_motor(0x01, 0x00, "hexfellow")
    ctrl.enable_all()
    motor.ensure_mode(Mode.POS_VEL, 1000)  # 无 VEL 模式
    motor.send_pos_vel(0.5, vlim=1.5)

最佳实践

厂商选择

需求推荐厂商
开发调试达妙 - 协议最完整
生产机器人RobStride - 协议可靠
简单应用MyActuator - 接口简单
大力矩需求HighTorque
高带宽通信Hexfellow(需要 CAN-FD 硬件)

混合厂商系统

# 不同厂商使用独立控制器
with Controller("can0") as dm_ctrl:
    dm = dm_ctrl.add_damiao_motor(0x01, 0x11, "4340P")
    dm_ctrl.enable_all()

    with Controller("can0") as rs_ctrl:
        rs = rs_ctrl.add_robstride_motor(127, 0xFE, "rs-00")
        rs_ctrl.enable_all()

        # 同时控制
        dm.send_mit(0.5, 0.0, 30.0, 1.0, 0.0)
        rs.send_mit(0.3, 0.0, 2.0, 0.1, 0.0)
不要把不同厂商的电机加到同一个 Controller 实例!每个厂商有不同的协议实现。

参见