Skip to main content

Reference: Vendor Capability Matrix

Vendor Overview

VendorAdd MethodTypical TransportProtocol
Damiaoadd_damiao_motor()SocketCAN, DM SerialDM-J4310/4340
RobStrideadd_robstride_motor()SocketCANRobStride MIT
MyActuatoradd_myactuator_motor()SocketCANMyActuator RMD
HighTorqueadd_hightorque_motor()SocketCANHighTorque native
Hexfellowadd_hexfellow_motor()CAN-FDHexfellow MIT

Control Mode Support

VendorMITPOS_VELVELFORCE_POS
Damiao
RobStride
MyActuator
HighTorque
Hexfellow

Mode Details

  • MIT: Full impedance control (pos, vel, kp, kd, tau)
  • POS_VEL: Position control with velocity limit
  • VEL: Pure velocity control
  • FORCE_POS: Compliant position with force ratio

Transport Support

VendorSocketCANCAN-FDDM Serial
Damiao
RobStride
MyActuator
HighTorque
Hexfellow✅ Required

Register Access

VendorRead RegistersWrite RegistersStore to Flash
Damiao✅ Full✅ Full
RobStride✅ Params✅ Params
MyActuator⚠️ Limited⚠️ Limited
HighTorque⚠️ Limited⚠️ Limited
Hexfellow⚠️ Limited⚠️ Limited

Damiao Register Summary

RIDNameTypeDescription
7MST_IDu32Feedback ID
8ESC_IDu32Motor ID
9TIMEOUTu32Communication timeout
10CTRL_MODEu32Control mode
21PMAXf32Position range
22VMAXf32Velocity range
23TMAXf32Torque range
25KP_ASRf32Speed loop Kp
26KI_ASRf32Speed loop Ki
27KP_APRf32Position loop Kp
28KI_APRf32Position loop Ki

RobStride Parameter Access

# RobStride uses parameter API, not generic registers
motor.robstride_get_param_f32(param_id, timeout_ms)
motor.robstride_write_param_f32(param_id, value)

Feedback State

VendorPositionVelocityTorqueMOS TempRotor Temp
Damiao
RobStride
MyActuator
HighTorque
Hexfellow

Special Features

Damiao

  • Most complete protocol support
  • Full register access - All 35+ registers
  • Serial bridge option - DM Serial adapter
  • Motor ID configuration - Change IDs via register

RobStride

  • Ping command - Discover device/responder IDs
  • Parameter API - Typed parameter access (i8, u8, u16, u32, f32)
  • Device ID configuration - Change device ID

MyActuator

  • Standard feedback format
  • Simple control interface
  • No MIT mode - Use POS_VEL or VEL

HighTorque

  • Native vendor protocol
  • Full mode support
  • Standard feedback

Hexfellow

  • Requires CAN-FD - Must use from_socketcanfd()
  • No velocity mode - Use MIT or POS_VEL
  • High bandwidth communication

Model Strings

Damiao

ModelDescriptionTypical Use
4310Small form factorGrippers, small joints
4340Medium torqueArms, medium joints
4340P4340 with position modeGeneral purpose
6001Large torqueLegs, heavy loads

RobStride

ModelDescription
rs-00Standard RobStride motor

MyActuator

ModelDescription
X8Standard MyActuator motor

HighTorque

ModelDescription
hightorqueGeneric HighTorque motor

Hexfellow

ModelDescription
hexfellowGeneric Hexfellow motor

CAN ID Conventions

Damiao

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

RobStride

motor_id:    127 (device ID)
feedback_id: 0xFE, 0xFF (responder ID)

MyActuator

motor_id:    1 - 32
feedback_id: 0x240 + motor_id

HighTorque

motor_id:    1 - 127
feedback_id: 0x01

Hexfellow

motor_id:    0x01 - 0xFF
feedback_id: 0x00

Code Examples by Vendor

Damiao

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 first
    device_id, responder_id = motor.robstride_ping()
    print(f"Device: {device_id}, Responder: {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)  # No MIT mode
    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

# MUST use 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)  # No VEL mode
    motor.send_pos_vel(0.5, vlim=1.5)

Best Practices

Vendor Selection

  1. Damiao: Best for development - most complete protocol
  2. RobStride: Good for production robots - reliable protocol
  3. MyActuator: Good for simple applications - limited modes
  4. HighTorque: Good for high-torque applications
  5. Hexfellow: Requires CAN-FD hardware

Mixed Vendor Systems

# Use separate controllers for different vendors
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()

        # Control both
        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)
Do not mix vendors in the same Controller instance. Each vendor has a different protocol implementation.

See Also