Damiao QDD Motors — Reference Guide
Complete reference for the Damiao (达妙科技) quasi-direct-drive actuator series: motor specifications, CAN bus configuration, motor ID assignment, control commands, LED diagnostics, and calibration guidelines as used in OpenArm and TRLC-DK1.
1. What Are Damiao Motors?
Damiao (达妙科技) motors are Quasi-Direct-Drive (QDD) actuators designed for research-grade robot arms and legged platforms. Unlike high-reduction gearbox motors, QDD actuators use a low-reduction planetary gear stage (typically 6:1 to 10:1) that preserves the motor's inherent backdrivability and compliance while delivering useful torque at robot-arm speeds.
Key properties that make them popular in research robotics:
- Backdrivable — the output shaft can be pushed back by external forces, enabling safe human interaction and force control without explicit torque sensing
- High transparency — reflected inertia and friction are low, so the arm feels "light" and compliant during gravity compensation and teleoperation
- CAN bus interface — all motors communicate over a shared CAN or CAN FD bus, simplifying wiring in daisy-chain topologies
- Integrated encoder — each motor contains a high-resolution encoder for accurate position feedback without external sensors
- Multiple control modes — motors support MIT-style hybrid position-velocity-torque (PVT) control, pure position, pure velocity, and pure torque modes selectable over CAN
The DM-J43xx-2EC family is used across SVRC hardware. The "2EC" suffix indicates dual encoder (motor-side + output-side), enabling backlash estimation and accurate output-shaft position. The "p" suffix on the J4340p indicates a higher-torque variant with a different winding configuration.
2. Motor Series
Comparison Table
The three models used across SVRC hardware platforms, ordered by torque capability:
| Model | Peak Torque | No-Load Speed | Gear Ratio | Typical Application |
|---|---|---|---|---|
| DM-J4310-2EC V1.1 | ~10 Nm | ~30 rpm | 10:1 | Wrist joints, gripper (J7, J8 on OpenArm) |
| DM-J4340-2EC | ~18 Nm | ~15 rpm | 10:1 | Elbow, mid-arm joints (J4, J5, J6 on OpenArm) |
| DM-J4340p-2EC | ~25 Nm | ~12 rpm | 10:1 | Base/shoulder joints, heavy loads (J1, J2, J3 on OpenArm; DK1 base) |
Detailed Specifications
| Parameter | DM-J4310-2EC V1.1 | DM-J4340-2EC | DM-J4340p-2EC |
|---|---|---|---|
| Stator diameter | 43 mm | 43 mm | 43 mm |
| Nominal voltage | 24 V | 24 V | 24 V |
| Communication | CAN 2.0 / CAN FD | CAN 2.0 / CAN FD | CAN 2.0 / CAN FD |
| Encoder | Dual (motor + output) | Dual (motor + output) | Dual (motor + output) |
| Control modes | MIT PVT, position, velocity, torque | MIT PVT, position, velocity, torque | MIT PVT, position, velocity, torque |
| CAN nominal baud | 1 Mbit/s | 1 Mbit/s | 1 Mbit/s |
| CAN FD data baud | up to 5 Mbit/s | up to 5 Mbit/s | up to 5 Mbit/s |
| Position range | Multi-turn | Multi-turn | Multi-turn |
| Operating temp. | −20 °C to 80 °C | −20 °C to 80 °C | −20 °C to 80 °C |
3. Motor ID Assignment
Each motor on the CAN bus must have a unique CAN ID pair: a transmitter ID (the ID used to send commands to the motor) and a receiver ID (the ID the motor uses when sending feedback frames back). IDs are configured using the Damiao Windows debugging tool before assembly and must not overlap on the same bus.
OpenArm (J1–J8) Standard Assignment
OpenArm uses 8 Damiao motors per arm, communicating over a single CAN bus at CAN FD 1M/5M baud. The standard ID mapping is:
| Joint | Motor Model | TX ID (host → motor) | RX ID (motor → host) |
|---|---|---|---|
| J1 (base rotation) | DM-J4340p-2EC | 0x01 | 0x11 |
| J2 (shoulder pitch) | DM-J4340p-2EC | 0x02 | 0x12 |
| J3 (shoulder roll) | DM-J4340p-2EC | 0x03 | 0x13 |
| J4 (elbow pitch) | DM-J4340-2EC | 0x04 | 0x14 |
| J5 (elbow roll) | DM-J4340-2EC | 0x05 | 0x15 |
| J6 (wrist pitch) | DM-J4340-2EC | 0x06 | 0x16 |
| J7 (wrist roll) | DM-J4310-2EC V1.1 | 0x07 | 0x17 |
| J8 (gripper) | DM-J4310-2EC V1.1 | 0x08 | 0x18 |
For a bimanual OpenArm setup, the second arm uses a separate CAN bus (e.g., can1) with the same ID scheme — IDs only need to be unique per bus, not globally.
Configuring Motor IDs
Motor IDs must be set before installation using the Damiao USB-CAN debugging tool (Windows only). The procedure for each motor is:
-
Connect one motor at a time. Connect a single motor to the Damiao USB-CAN adapter. Never configure IDs with multiple motors on the bus simultaneously — ID collisions will prevent proper communication.
-
Open the Damiao debugging tool. Launch Debugging_Tools_v.1.6.8.8.exe on Windows. Select the correct COM port for the USB-CAN adapter and connect.
-
Read current motor ID. Use the "Read Parameter" function in the tool to query the motor's current TX/RX IDs. Verify the motor is detected before making changes.
-
Set the new TX and RX IDs. Enter the desired transmitter ID and receiver ID from the table above. Write the values to the motor. The tool will confirm with a success message.
-
Power-cycle and verify. Disconnect power, reconnect, and re-read the motor parameters to confirm IDs were saved correctly. The flash write is persistent across power cycles.
4. CAN Bus Setup
Damiao motors communicate over a standard SocketCAN interface on Linux. Two modes are supported: CAN 2.0 (classic, 8-byte payload) and CAN FD (Flexible Data-Rate, up to 64-byte payload). CAN FD at 1 Mbit/s nominal + 5 Mbit/s data rate is recommended for OpenArm and all new deployments.
| Mode | Nominal Baud | Data Baud | Max Payload | Recommended |
|---|---|---|---|---|
| CAN 2.0 | 1 Mbit/s | — | 8 bytes | Legacy / compatibility |
| CAN FD | 1 Mbit/s | 5 Mbit/s | 64 bytes | Yes — use for all new setups |
CAN 2.0 Setup
Bring the CAN interface up at 1 Mbit/s classic CAN:
# Bring interface down first if already up sudo ip link set can0 down # Configure as CAN 2.0 at 1 Mbit/s sudo ip link set can0 type can bitrate 1000000 # Bring interface up sudo ip link set can0 up # Verify ip link show can0
CAN FD Setup (Recommended)
Bring the CAN interface up at 1 Mbit/s nominal / 5 Mbit/s data with FD enabled:
# Bring interface down first if already up sudo ip link set can0 down # Configure as CAN FD: 1M nominal baud, 5M data baud, FD mode enabled sudo ip link set can0 type can bitrate 1000000 dbitrate 5000000 fd on # Bring interface up sudo ip link set can0 up # Verify — should show "fd on" in output ip link show can0
openarm-can-configure-socketcan helper wraps these commands:
# CAN FD (recommended) openarm-can-configure-socketcan can0 -fd -b 1000000 -d 5000000 # CAN 2.0 openarm-can-configure-socketcan can0 # Four-arm bimanual setup (can0–can3) openarm-can-configure-socketcan-4-arms -fd
Installing can-utils
The candump and cansend utilities used for debugging are part of can-utils:
sudo apt update && sudo apt install -y can-utils
Monitor the Bus
Always monitor the bus before sending commands to verify connectivity and detect ID conflicts:
# Dump all frames (Ctrl+C to stop) candump -x can0 # Dump with timestamps and frame count candump -td can0
5. Motor Control Commands
Use cansend to send raw CAN frames for low-level motor control. These commands are essential for commissioning, debugging, and error recovery. Replace 001 with the hexadecimal transmitter ID of the target motor (e.g., 002 for J2).
CAN 2.0 Commands
Standard 8-byte CAN frames. The frame format is <can_id>#<8-byte-data>:
# Enable motor (motor will hold position and accept commands) cansend can0 001#FFFFFFFFFFFFFFFC # Disable motor (motor becomes free-wheeling) cansend can0 001#FFFFFFFFFFFFFFFD # Clear motor error (required before re-enabling after a fault) cansend can0 001#FFFFFFFFFFFFFFFB
CAN FD Commands
CAN FD frames use the ##<flags> syntax. The 1 after ## sets the BRS (Bit Rate Switch) flag, enabling the higher data-phase baud rate:
# Enable motor (CAN FD with BRS) cansend can0 001##1FFFFFFFFFFFFFFFC # Disable motor (CAN FD with BRS) cansend can0 001##1FFFFFFFFFFFFFFFD # Clear motor error (CAN FD with BRS) cansend can0 001##1FFFFFFFFFFFFFFFB
#) when the interface is configured as CAN 2.0, and CAN FD commands (##1) when the interface is configured with fd on. Mixing frame types on the same bus will cause errors.
Changing Motor Baud Rate
If you need to change a motor's CAN FD data baud rate (e.g., when switching from a 1M-only setup to 5M), use the OpenArm utility:
# Set motor 1 data baud to 5 Mbit/s (runtime only) openarm-can-change-baudrate --baudrate 5000000 --canid 1 --socketcan can0 # Persist across power cycles (uses one flash write) openarm-can-change-baudrate --baudrate 5000000 --canid 1 --socketcan can0 --flash
6. LED Status Indicators
Each Damiao motor has a single onboard LED visible through a small window in the housing. Learn to read this indicator before proceeding with any motor commissioning:
| LED Pattern | State | Action Required |
|---|---|---|
| Green (steady) | Motor enabled and ready | None — motor is active and accepting commands |
| Red (steady) | Motor disabled (powered but not enabled) | Send the Enable command to activate the motor |
| Red (flashing) | Motor fault / error state | Send Clear Error command, investigate cause, then re-enable |
Common Fault Causes
- Over-current — commanded torque exceeded motor limits; reduce gains or load
- Over-temperature — motor ran hot; allow it to cool before re-enabling
- Encoder error — encoder signal lost or corrupted; check cable connections
- Under-voltage — supply voltage dropped below minimum (typically <18 V on a 24 V system); check power supply and connections
- CAN bus error — bus-off state caused by wiring issues, missing termination resistor, or baud rate mismatch
7. Calibration & Flash Writes
Damiao motors store calibration data and configuration parameters in internal flash memory. Understanding the flash write lifecycle helps avoid premature wear.
What Requires a Flash Write
- Setting motor CAN IDs (TX/RX)
- Persisting a baud rate change with
--flash - Writing PID gains or zero-position offsets with the persistence flag
Flash Write Limit
--flash flag) are applied in RAM only and do not consume flash cycles.
Zero-Position Calibration
After assembling the arm, the zero position of each joint must be established. For OpenArm, this is handled by the openarm_can library's calibration utilities. The general procedure:
- Manually position the arm in its defined zero-pose (all joints at the mechanical reference mark)
- Run the calibration routine which reads current encoder positions and stores them as offsets
- Verify by commanding the arm to zero — it should return to the reference pose
For the TRLC-DK1 follower arm, calibration is handled through the LeRobot calibration workflow triggered by lerobot-setup-motors.
8. Damiao Debugging Tool (Windows)
Damiao provides a Windows application for USB-CAN motor configuration. This tool is required for initial motor ID assignment and is useful for reading fault codes, adjusting PID gains, and verifying motor health before deployment.
Download
What the Tool Can Do
- Read and write motor CAN IDs (TX/RX)
- Read and write PID control gains (position, velocity, torque loops)
- Read motor fault codes and temperature
- Send enable, disable, and error-clear commands interactively
- Command position, velocity, and torque setpoints for bench testing
- Change CAN baud rate and persist to flash
- Read encoder counts and verify dual-encoder consistency
Requirements
- Windows 10 or 11 (64-bit)
- Damiao USB-CAN adapter (included with motor kits)
- USB-CAN driver installed (usually auto-installed by Windows)
- One motor connected at a time for ID configuration
9. Where Damiao Motors Are Used
OpenArm
OpenArm uses 8 Damiao motors per arm (J1–J8) over a single CAN FD bus at 1 Mbit/s nominal / 5 Mbit/s data. The motors are daisy-chained using the CAN connectors built into each motor housing. The arm communicates with a host PC running Ubuntu + SocketCAN via a CAN FD USB adapter.
- J1–J3: DM-J4340p-2EC (base and shoulder — highest torque)
- J4–J6: DM-J4340-2EC (elbow and forearm)
- J7–J8: DM-J4310-2EC V1.1 (wrist and gripper — lowest torque, highest speed)
Read the OpenArm Software Guide for full setup instructions including CAN interface configuration and motor test utilities.
TRLC-DK1 Follower Arm
The TRLC-DK1 follower arm uses Damiao motors for all joints, connected via a USB serial CAN bridge (not native SocketCAN). This allows the DK1 to work on macOS and Windows as well as Linux, without requiring a dedicated CAN FD adapter.
- Base joints: DM-J4340p-2EC — highest-torque joints for supporting the arm against gravity
- Mid joints: DM-J4340-2EC — elbow and forearm range
- Wrist and gripper: DM-J4310-2EC V1.1 — lighter, faster distal joints
Read the TRLC-DK1 guide for LeRobot integration, port discovery, and bimanual recording setup.
| Platform | Motors | Bus | Interface |
|---|---|---|---|
| OpenArm (single arm) | 8x Damiao (J1–J8) | CAN FD 1M/5M | SocketCAN (Linux) |
| OpenArm (bimanual) | 16x Damiao | 2x CAN FD buses | SocketCAN (Linux) |
| TRLC-DK1 follower | 7x Damiao per arm | CAN via USB serial bridge | Serial (cross-platform) |
10. Troubleshooting
Motor not responding to cansend
- Verify the CAN interface is UP:
ip link show can0should showUPstate - Confirm the motor is powered (LED should be red-steady, not off)
- Check you are using the correct TX ID for the target motor
- Ensure you are using the correct frame format:
#for CAN 2.0,##1for CAN FD - Run
candump -x can0and send a command — you should see the frame appear even if the motor does not respond
Bus goes into error state (BUS-OFF)
- Check termination resistors — each CAN bus segment requires 120 Ω termination at both ends
- Verify CAN H and CAN L wiring are not swapped
- Confirm all motors on the bus are configured for the same baud rate
- Try reducing bus length or using shielded twisted-pair cable
- Bring the interface down and back up to clear the BUS-OFF state:
sudo ip link set can0 down && sudo ip link set can0 up
Motor shows red-flashing (error) immediately after power-on
- Send the Clear Error command (
FFFFFFFFFFFFFFFB/##1FFFFFFFFFFFFFFFB) before enabling - Check for over-voltage — supply should not exceed 28 V for 24 V rated motors
- Verify encoder cables are fully seated in the motor connectors
Inconsistent position feedback
- Power-cycle the motor and re-enable; encoder position resets to absolute on boot
- Verify the dual-encoder consistency using the Damiao debugging tool (Windows) — large discrepancy between motor-side and output-side encoder suggests mechanical slip
Further reading
- CAN Communication Anomaly Diagnosis — diagnosing intermittent and persistent CAN bus errors (Chinese)
- Common Wiring Issues — connector polarity, termination, and cable shielding (Chinese)
- openarm_can on GitHub — C++ SocketCAN library with Python bindings for motor control