Skip to main content

Documentation Index

Fetch the complete documentation index at: https://motorbridge.seeedstudio.com/llms.txt

Use this file to discover all available pages before exploring further.

Source: motor_cli/DAMIAO_API.md

Damiao API and Tuning Reference (Complete)

Channel Compatibility (PCAN + slcan + Damiao Serial Bridge)

  • Linux SocketCAN uses interface names directly: can0, can1, slcan0.
  • For USB-serial CAN adapters, bring up slcan0 first: sudo slcand -o -c -s8 /dev/ttyUSB0 slcan0 && sudo ip link set slcan0 up.
  • Damiao-only serial bridge transport is also available in CLI (--transport dm-serial --serial-port /dev/ttyACM0 --serial-baud 921600).
  • On Linux SocketCAN, do not append bitrate in --channel (for example can0@1000000 is invalid).
  • On Windows (PCAN backend), can0/can1 map to PCAN_USBBUS1/2; optional @bitrate suffix is supported.
This page is a practical reference for all commonly adjustable control/configuration parameters currently available in motorbridge for Damiao motors.
Chinese version: DAMIAO_API.zh-CN.md

1) Common Device Parameters

ParameterMeaningTypical value
channelCAN interface namecan0
modelMotor model string (4310, 4340P, etc.)matches real device
motor-idCommand ID (ESC_ID)e.g. 0x01
feedback-idFeedback ID (MST_ID)e.g. 0x11
loopNumber of send cycles100
dt-msSend interval per cycle (ms)20

2) Real-time Control Mode Parameters

2.1 MIT Mode

Command fields:
  • pos: target position
  • vel: target velocity
  • kp: position stiffness gain
  • kd: velocity damping gain
  • tau: feedforward torque
Example (motor_cli):
motor_cli \
  --channel can0 --model 4340P --motor-id 0x01 --feedback-id 0x11 \
  --mode mit --pos 0 --vel 0 --kp 20 --kd 1 --tau 0 --loop 200 --dt-ms 20

2.2 POS_VEL Mode

Command fields:
  • pos: target position
  • vlim: velocity limit
Example:
motor_cli \
  --channel can0 --model 4340P --motor-id 0x01 --feedback-id 0x11 \
  --mode pos-vel --pos 3.10 --vlim 1.50 --loop 300 --dt-ms 20

2.3 VEL Mode

Command field:
  • vel: target velocity
Example:
motor_cli \
  --channel can0 --model 4340P --motor-id 0x01 --feedback-id 0x11 \
  --mode vel --vel 0.5 --loop 100 --dt-ms 20

2.4 FORCE_POS Mode

Command fields:
  • pos: target position
  • vlim: velocity limit
  • ratio: torque limit ratio
Example:
motor_cli \
  --channel can0 --model 4340P --motor-id 0x01 --feedback-id 0x11 \
  --mode force-pos --pos 0.8 --vlim 2.0 --ratio 0.3 --loop 100 --dt-ms 20

2.5 Mode Selection (CTRL_MODE)

Register:
  • rid=10 (CTRL_MODE), values:
    • 1=MIT
    • 2=POS_VEL
    • 3=VEL
    • 4=FORCE_POS

3) High-impact Registers (Priority)

These have major control impact and should be tuned carefully.
RIDNameTypeMeaning
21PMAXf32Position mapping range
22VMAXf32Velocity mapping range
23TMAXf32Torque mapping range
25KP_ASRf32Speed loop Kp
26KI_ASRf32Speed loop Ki
27KP_APRf32Position loop Kp
28KI_APRf32Position loop Ki
4ACCf32Acceleration
5DECf32Deceleration
6MAX_SPDf32Maximum speed
9TIMEOUTu32Communication timeout register

4) Protection Registers

RIDNameTypeMeaning
0UV_Valuef32Under-voltage threshold
2OT_Valuef32Over-temperature threshold
3OC_Valuef32Over-current threshold
29OV_Valuef32Over-voltage threshold

5) How to Read/Write Parameters

Recommended write workflow:
  1. get_register read old value
  2. write_register write new value
  3. get_register read back
  4. store_parameters persist
Python SDK API example:
from motorbridge import Controller

with Controller("can0") as ctrl:
    m = ctrl.add_damiao_motor(0x01, 0x11, "4340P")
    old = m.get_register_f32(22, 1000)
    print("old VMAX", old)
    m.write_register_f32(22, old * 0.9)
    new = m.get_register_f32(22, 1000)
    print("new VMAX", new)
    m.store_parameters()
    m.close()
WS gateway command examples:
{"op":"get_register_f32","rid":22,"timeout_ms":1000}
{"op":"write_register_f32","rid":22,"value":25.0}
{"op":"store_parameters"}

6) ID and Calibration Parameters

  • rid=8 (ESC_ID): command ID
  • rid=7 (MST_ID): feedback ID
Tools:
  • Rust CLI: motor_cli --vendor damiao --mode scan ... and --set-motor-id/--set-feedback-id --store --verify-id
  • Python: motorbridge-cli scan/id-set/id-dump, damiao-read-param, damiao-write-param, and Rust-style run --set-motor-id/--set-feedback-id
  • WS: scan, set_id, verify

7) Safety Notes

  • Tune one parameter group at a time.
  • Use small steps, verify each change.
  • Keep safe mechanical load and emergency stop ready.
  • For protection thresholds (0/2/3/29), avoid aggressive changes without hardware margin analysis.

8) Gripper Motor Calibration

Damiao motors use a single-turn encoder (position range approx. ±PMAX rad). Zero position is NOT retained across power cycles. When a motor is used as a gripper, calibrate the zero position after each power-on:
  1. Use MIT mode with low kp and tau=0 to move toward the mechanical limit — the motor stops softly on contact.
  2. Wait until feedback shows vel ≈ 0 and pos is stable, then run --mode set-zero.
  3. After calibration, use MIT mode for closing (force-limited, safe) and pos-vel mode for opening (fast, precise).
For full command examples, see the Operation Manual Section 9.