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/README.md

motor_cli (English)

Complete parameter reference for the Rust motor_cli binary.
  • Crate: motor_cli
  • Recommended (release package): ./bin/motor_cli [ARGS...]
  • Optional (source build): ./target/release/motor_cli [ARGS...]

Release-first Usage

Download and extract the release package (GitHub Releases asset like motor-cli-vX.Y.Z-linux-x86_64.tar.gz), then run directly:
./bin/motor_cli -h
./bin/motor_cli --vendor damiao --mode scan --start-id 1 --end-id 16
If you want motor_cli as a plain command:
export PATH="$(pwd)/bin:$PATH"
motor_cli -h

Additional Damiao Command/Register Reference

  • Detailed Damiao command + register tuning doc (English): DAMIAO_API.md
  • Chinese version (command/register reference): DAMIAO_API.zh-CN.md

Additional RobStride Command/Parameter Reference

  • Detailed RobStride command + parameter guide (English): ROBSTRIDE_API.md
  • Chinese version (parameter/capability reference): ROBSTRIDE_API.zh-CN.md

Additional MyActuator Command/Mode Reference

  • Detailed MyActuator command + mode guide (English): MYACTUATOR_API.md
  • Chinese version (command/mode reference): MYACTUATOR_API.zh-CN.md

HighTorque Notes

  • Protocol analysis (Chinese): ../docs/zh/hightorque_protocol_analysis.md
  • Current vendor=hightorque is a native ht_can v1.5.5 direct-CAN mode, not the official serial-CANboard transport.

CAN Debugging Entry

  • Professional Linux slcan + Windows pcan troubleshooting: ../docs/en/can_debugging.md
  • Chinese troubleshooting guide: ../docs/zh/can_debugging.md

Transport Legend

  • [STD-CAN] => --transport auto|socketcan
  • [CAN-FD] => --transport socketcanfd (Linux-only; required by Hexfellow)
  • [DM-SERIAL] => --transport dm-serial (Damiao-only)
Current status:
  • Hexfellow: validated on socketcanfd with unified mit / pos-vel.
  • HighTorque: validated on standard CAN with unified mit / vel (kp/kd ignored by protocol).
  • Damiao: baseline implementation for unified mit / pos-vel / vel / force-pos.

Validated Capability Matrix (Damiao + RobStride, 2026-04)

CapabilityDamiaoRobStride
ScanYesYes
Ping / online probeYes (scan/register path)Yes (ping)
Enable / DisableYesYes
MIT (pos/vel/kp/kd/tau)YesYes
POS_VEL unified modeYesYes (mapped to native Position path)
VEL unified modeYesYes
Parameter read/writeYesYes
Set zeroYes (disable first)Yes (experimental sequence; firmware-dependent ack behavior)
Set motor IDYes (--set-motor-id)Yes (--set-motor-id)
Set feedback IDYes (--set-feedback-id)No (host id is configured by --feedback-id)
Notes:
  • RobStride default --feedback-id is 0xFD; scan defaults to --feedback-ids 0xFD,0xFF,0xFE,0x00,0xAA.
  • RobStride feedback_id / host_id is not the motor device_id; scan reports the motor ID as probe / device_id.
  • RobStride --model is still passed for limits and logging, while v0.2.9 parameter read/write uses the common section 4 runtime table.
  • RobStride pos-vel ignores --vel/--kd/--tau by design (warning only, no hard error).

1. Argument Parsing Rules

  • Only --key value style options are parsed.
  • A bare mode word, for example motor_cli scan --vendor robstride ..., is accepted as shorthand for --mode scan.
  • A standalone flag (for example --help) is treated as value 1.
  • Numeric IDs accept decimal (20) and hex (0x14).
  • Unknown keys are parsed but ignored unless used by code paths.

2. Top-Level Arguments (All Vendors)

ArgumentTypeDefaultNotes
--helpflagoffPrints CLI help and exits
--vendorstringdamiaodamiao, robstride, hightorque, myactuator, hexfellow, all
--transportstringautoauto, socketcan, socketcanfd, dm-serial (socketcanfd is Hexfellow-required path; dm-serial is Damiao-only)
--channelstringcan0Linux: SocketCAN interface name (can0/slcan0); Windows (PCAN backend): can0/can1 with optional @bitrate suffix (for example can0@1000000); macOS (PCBUSB backend): can0/can1
--serial-portstring/dev/ttyACM0Used when --transport dm-serial
--serial-baudu64921600Used when --transport dm-serial
--modelstringvendor dependent4340 for Damiao; physical rs-00 through rs-06 for RobStride; hightorque for HighTorque; X8 for MyActuator
--motor-idu16 (hex/dec)0x01Motor CAN ID
--feedback-idu16 (hex/dec)vendor dependentDamiao 0x11, RobStride 0xFD, HighTorque 0x01, MyActuator 0x241 (for motor-id 1)
--modestringvendor dependentDamiao mit, RobStride ping, HighTorque read, MyActuator status, all -> scan
--loopu641Control loop cycles
--dt-msu6420Loop interval in ms
--ensure-mode0/11Auto-switch mode before control

2.1 Channel Quick Reference (--channel)

  • Linux SocketCAN:
    • Use interface names directly: can0, can1, slcan0.
    • Configure bitrate at interface setup time (ip link / slcand), not in --channel.
    • can0@1000000 is invalid on Linux SocketCAN.
  • Windows PCAN:
    • can0 maps to PCAN_USBBUS1, can1 maps to PCAN_USBBUS2.
    • Optional bitrate suffix is supported: can0@1000000.
  • macOS PCBUSB (PCAN backend):
    • can0 maps to PCAN_USBBUS1, can1 maps to PCAN_USBBUS2.
    • Install libPCBUSB.dylib first (see root README.md macOS section).

2.2 Damiao Serial-Bridge Quick Reference (--transport dm-serial)

  • This path is adapter-specific and intended for Damiao motors.
  • Typical flags: --transport dm-serial --serial-port /dev/ttyACM1 --serial-baud 921600.
  • In dm-serial mode, --channel is ignored by transport creation.

2.3 Damiao Dedicated CAN-FD Quick Reference (--transport socketcanfd)

  • This path is Linux-only and independent from classic SocketCAN transport.
  • Hexfellow must use this path (--vendor hexfellow --transport socketcanfd).
  • Typical flags: --transport socketcanfd --channel can0.
  • Ensure the interface is in FD mode first (scripts/canfd_restart.sh can0).
  • Current status: Hexfellow validated; Damiao CAN-FD matrix can be validated per model.

3. Vendor = damiao

3.1 Supported Modes

  • scan
  • enable
  • disable
  • mit
  • pos-vel
  • vel
  • force-pos

3.2 Damiao Extra Arguments

ArgumentTypeDefaultUsed InNotes
--verify-model0/11non-scanVerify PMAX/VMAX/TMAX matches --model
--verify-timeout-msu64500non-scanRegister read timeout for model handshake
--verify-tolf320.2non-scanModel limit tolerance
--start-idu161scanScan start, must be 1..255
--end-idu16255scanScan end, must be 1..255
--set-motor-idu16 optnoneid-set flowWrite ESC_ID (RID 8)
--set-feedback-idu16 optnoneid-set flowWrite MST_ID (RID 7)
--store0/11id-set flowPersist parameters
--verify-id0/11id-set flowRe-read RID7/RID8 and verify

3.3 Control Arguments by Mode

ModeArgumentsDefaults
mit--pos --vel --kp --kd --tau0 0 2 1 0
pos-vel--pos --vlim0 1.0
vel--vel0
force-pos--pos --vlim --ratio0 1.0 0.1
enable/disableno extra requiredn/a

3.4 Scan Behavior Details

  • The scanner is model-agnostic in practice: it internally tries a built-in model-hint list.
  • For each candidate ID, it also tries multiple feedback-ID hints: inferred (id+0x10), user --feedback-id, 0x11, 0x17.
  • Detection first attempts register reads (RID 21/22/23), then feedback fallback.

3.5 Damiao Examples

# Scan a range
motor_cli \
  --vendor damiao --channel can0 --mode scan --start-id 1 --end-id 16
# [STD-CAN]

# MIT control
motor_cli \
  --vendor damiao --channel can0 --model 4310 --motor-id 0x04 --feedback-id 0x14 \
  --mode mit --pos 1.57 --vel 2.0 --kp 35 --kd 1.2 --tau 0.3 --loop 120 --dt-ms 20
# [STD-CAN]

# MIT control via Damiao serial bridge
motor_cli \
  --vendor damiao --transport dm-serial --serial-port /dev/ttyACM1 --serial-baud 921600 \
  --model 4310 --motor-id 0x04 --feedback-id 0x14 \
  --mode mit --verify-model 0 --ensure-mode 0 \
  --pos 1.0 --vel 0 --kp 2 --kd 1 --tau 0 --loop 80 --dt-ms 20
# [DM-SERIAL]

# Position-velocity control
motor_cli \
  --vendor damiao --channel can0 --model 4310 --motor-id 0x04 --feedback-id 0x14 \
  --mode pos-vel --pos 3.14 --vlim 4.0 --loop 120 --dt-ms 20
# [STD-CAN]

# Update ID and persist
motor_cli \
  --vendor damiao --channel can0 --model 4310 --motor-id 0x01 --feedback-id 0x11 \
  --set-motor-id 0x04 --set-feedback-id 0x14 --store 1 --verify-id 1

4. Vendor = robstride

4.1 Supported Modes

  • ping
  • scan
  • enable
  • disable
  • mit
  • pos-vel
  • vel
  • read-param
  • write-param

4.2 RobStride Extra Arguments

ArgumentTypeDefaultUsed InNotes
--start-idu161scanScan start, 1..255
--end-idu16255scanScan end, 1..255
--feedback-idscsv u160xFD,0xFF,0xFE,0x00,0xAAscanRobStride host_id candidates, 0..255; not motor IDs
--timeout-msu6480scanPing timeout
--param-timeout-msu64120scanParameter fallback timeout
--manual-velf320.2scan fallbackBlind pulse velocity
--manual-msu64200scan fallbackPulse duration per ID
--manual-gap-msu64200scan fallbackGap between IDs
--set-motor-idu16 optnoneid-set flowSet device ID, 1..255
--store0/11id-set flowSave parameters
--param-idu16required for param modesread/write paramParameter ID
--param-valuetypedrequired for writewrite-paramParsed by selected RobStride model metadata

4.3 Control Arguments by Mode

ModeArgumentsDefaults
mit--pos --vel --kp --kd --tau0 0 8 0.2 0
pos-vel--pos --vlim [--kp]0 1.0 [none]
vel--vel0
enable/disableno extra requiredn/a
Notes:
  • RobStride unified control currently supports MIT / POS_VEL / VEL.
  • Supported RobStride models are rs-00, rs-01, rs-02, rs-03, rs-04, rs-05, and rs-06.
  • Always pass the real motor model. Basic control command shape is shared, but native function-code parameters differ by model; a parameter ID may have a different name or type on a different RS model.
  • The built-in RS00-RS06 parameter tables are aligned with RobStride/Product_Information commit ba7236bc26417766fda71e75ae128c66dbd21aba.
  • Torque/current is currently parameter-level only (via write-param, for example iq_ref and limit registers), not a first-class high-level mode.
  • In RobStride mit, all five unified inputs are effective: --pos, --vel, --kp, --kd, --tau.
  • RobStride mit units follow unified semantics: pos in rad, vel in rad/s, tau in Nm (kp/kd are MIT loop gains).
  • In RobStride pos-vel, only --pos, --vlim, and optional --kp/--loc-kp are consumed.
  • In RobStride pos-vel, --vel, --kd, and --tau are ignored (CLI prints a warning if provided).

4.4 Scan Behavior Details

  • Fast pass: ping + query-parameter probe per ID.
  • If no hits in full range: fallback to blind velocity pulses for manual movement observation.
  • Fallback hit criteria includes state feedback presence.

4.5 RobStride Examples

# Ping
motor_cli \
  --vendor robstride --channel can0 --model rs-06 --motor-id 20 --feedback-id 0xFD --mode ping

# Scan
motor_cli \
  --vendor robstride --channel can0 --model rs-06 --mode scan --start-id 1 --end-id 255

# MIT control
motor_cli \
  --vendor robstride --channel can0 --model rs-00 --motor-id 2 --feedback-id 0xFD \
  --mode mit --ensure-mode 1 \
  --pos 0.5 --vel 0 --kp 20.0 --kd 0.5 --tau 0 \
  --loop 100 --dt-ms 20

# POS_VEL (mapped to native Position)
motor_cli \
  --vendor robstride --channel can0 --model rs-00 --motor-id 2 --feedback-id 0xFD \
  --mode pos-vel --pos 1.5 --vlim 1.0 --loc-kp 5.0 --loop 1 --dt-ms 20

# Velocity mode
motor_cli \
  --vendor robstride --channel can0 --model rs-06 --motor-id 20 --feedback-id 0xFD \
  --mode vel --vel 2.0 --loop 100 --dt-ms 20

# Read parameter
motor_cli \
  --vendor robstride --channel can0 --model rs-06 --motor-id 20 --feedback-id 0xFD \
  --mode read-param --param-id 0x7005

# Write parameter
motor_cli \
  --vendor robstride --channel can0 --model rs-06 --motor-id 20 --feedback-id 0xFD \
  --mode write-param --param-id 0x7005 --param-value 2

# Set motor ID (old 1 -> new 11) and persist
motor_cli \
  --vendor robstride --channel can0 --model rs-06 --motor-id 1 --feedback-id 0xFD \
  --set-motor-id 11 --store 1

# Python CLI equivalent for RobStride ID update
motorbridge-cli id-set \
  --vendor robstride --channel can0 --model rs-06 \
  --motor-id 1 --feedback-id 0xFD --new-motor-id 11 --store 1 --verify 1

# Zero (experimental sequence)
motor_cli \
  --vendor robstride --channel can0 --model rs-06 --motor-id 11 --feedback-id 0xFD \
  --mode zero --zero-exp 1 --store 1

5. Vendor = all

vendor=all currently supports only --mode scan.

5.1 Additional Arguments for all-scan

ArgumentDefaultNotes
--damiao-model4340PModel hint used when invoking Damiao scan path
--robstride-modelrs-00Model hint used when invoking RobStride scan path
--hightorque-modelhightorqueModel hint used when invoking HighTorque scan path
--myactuator-modelX8Model hint used when invoking MyActuator scan path
--start-id1Passed to all scans
--end-id255Passed to Damiao/RobStride; MyActuator path auto-clamps to 32

5.2 Example

motor_cli \
  --vendor all --channel can0 --mode scan --start-id 1 --end-id 255

5.3 Vendor = hightorque (native ht_can v1.5.5)

  • This path uses native HighTorque ht_can v1.5.5 direct-CAN protocol.
  • It is intended for setups where motors are exposed directly on SocketCAN (can0 etc.).
  • Official Panthera/HighTorque SDK serial chain (USB serial -> CANboard -> motors) is separate from this CLI direct-CAN path.
  • Supported modes: scan | read | ping | mit | pos | vel | tqe | pos-vel-tqe | volt | cur | stop | brake | rezero | conf-write | timed-read.
  • Unified unit interface:
    • --pos in rad
    • --vel in rad/s
    • --tau in Nm
    • --kp, --kd are accepted for MIT signature compatibility but ignored by ht_can.
    • Raw debug parameters: --raw-pos, --raw-vel, --raw-tqe.

6. Vendor = myactuator

6.1 Supported Modes

  • scan
  • enable
  • disable
  • stop
  • set-zero
  • status
  • current
  • vel
  • pos
  • version
  • mode-query

6.2 MyActuator Extra Arguments

ArgumentTypeDefaultUsed InNotes
--start-idu161scanScan start, 1..32
--end-idu1632scanScan end, 1..32 (input >32 will be clamped)
--currentf320.0currentCurrent setpoint in A
--velf320.0velVelocity setpoint in rad/s (converted to deg/s internally)
--posf320.0posAbsolute position in rad (converted to deg internally)
--max-speedf328.726646posPosition move max speed in rad/s (converted internally)
Status output note:
  • angle comes from 0x9C status-2 near-turn angle.
  • mt_angle comes from 0x92 multi-turn angle and should be used for absolute-position judgement.

6.3 MyActuator Examples

# Scan IDs in MyActuator range
motor_cli \
  --vendor myactuator --channel can0 --mode scan --start-id 1 --end-id 32

# Query status repeatedly
motor_cli \
  --vendor myactuator --channel can0 --model X8 --motor-id 1 --feedback-id 0x241 \
  --mode status --loop 40 --dt-ms 50

# Velocity control
motor_cli \
  --vendor myactuator --channel can0 --model X8 --motor-id 1 --feedback-id 0x241 \
  --mode vel --vel 0.5236 --loop 100 --dt-ms 20

# Absolute position control
motor_cli \
  --vendor myactuator --channel can0 --model X8 --motor-id 1 --feedback-id 0x241 \
  --mode pos --pos 3.1416 --max-speed 5.236 --loop 1

# Set current position as zero (persistent after power-cycle)
motor_cli \
  --vendor myactuator --channel can0 --model X8 --motor-id 1 --feedback-id 0x241 \
  --mode set-zero --loop 1

7. Vendor = hexfellow

Transport constraint:
  • Hexfellow is CAN-FD-only in this repository (--transport socketcanfd).
  • Current support scope: scan / status / pos-vel / mit / enable / disable.
  • Current status: transport integrated; model validation matrix pending.

7.1 Hexfellow Examples

# Scan IDs
motor_cli \
  --vendor hexfellow --transport socketcanfd --channel can0 \
  --mode scan --start-id 1 --end-id 32

# Status query
motor_cli \
  --vendor hexfellow --transport socketcanfd --channel can0 \
  --model hexfellow --motor-id 1 --feedback-id 0 \
  --mode status

# Position-velocity (pos in rad, vlim in rad/s)
motor_cli \
  --vendor hexfellow --transport socketcanfd --channel can0 \
  --model hexfellow --motor-id 1 --feedback-id 0 \
  --mode pos-vel --pos 3.1415926 --vlim 2.0

# MIT (pos/vel in rad / rad/s)
motor_cli \
  --vendor hexfellow --transport socketcanfd --channel can0 \
  --model hexfellow --motor-id 1 --feedback-id 0 \
  --mode mit --pos 0.0 --vel 0.0 --kp 1000 --kd 100 --tau 0

8. Practical Notes

  • For Damiao ID updates, prefer keeping --store 1 --verify-id 1.
  • If scan intermittently misses motors, retry after CAN restart.
  • RobStride supports CLI --mode pos-vel (mapped to native Position); in this mode use --pos/--vlim/[--kp|--loc-kp].
  • MyActuator low-voltage protection returns error code 0x0004 in status-1 (0x9A) and blocks motion.