DAMIAO DM-J10010L-2EC V1.1 Motor Instruction Manual
DAMIAO DM-J10010L-2EC V1.1 Motor User Guide
Safety Precautions
- Operate the motor strictly within the specified environmental conditions and maximum winding temperature limits. Failure to do so may result in permanent damage.
- Prevent foreign objects from entering the rotor. Otherwise, abnormal operation may occur.
- Inspect all components before use. Do not operate the motor if any components are missing, wom, or damaged.
- Ensure correct wiring and proper, secure motor installation.
- Do not touch the rotating or energized parts during operation to avoid injury. High torque operation may generate heat. Avoid contact to prevent burns.
- Do not disassemble the motor. Unauthorized disassembly may affect control accuracy or cause malfunction.
Motor Features
- Dual encoders provide single-turn absolute position feedback at the output shaft, ensuring position information is retained even after power loss.
- Integrated motor and driver design offers compact structure with high integration.
- Supports PC-based configuration, monitoring, and firmware upgrades.
- Provides real-time feedback of motor Velocity, position, torque, and temperature via CAN bus.
- Features dual temperature protection mechanisms.
Packing List
- Motor (with integrated driver) ×1
- Power cable: XT60 male-to-female cable × 1
- CAN interface: GH1.25 2-Pin Cable × 1
- Debug serial cable: GH1.25 3-pin cable × 1
Interface & Pin Description

Specific Name - No. | Description |
Power Connection Interface-1 | 1. Connect the power supply using an XT30 male-to-female power extension cable. The rated voltage is 24V (supports 24-48V), providing power to the motor.
2. The motor includes two power interfaces. Either interface can be used individually for a single motor, or multiple motors can be connected in daisy‑chain for convenient cabling. It is recommended not to exceed 2 motors in series. |
Power Connection Interface-2 | 1. Connect the power supply using an XT30 male-to-female power extension cable. The rated voltage is 24V (supports 24-48V), providing power to the motor.
2. The motor includes two power interfaces. Either interface can be used individually for a single motor, or multiple motors can be connected in daisy‑chain for convenient cabling. It is recommended not to exceed 2 motors in series. |

Specific Name - No. | Description |
CAN Communication Terminal-1 | 1. Connect to external control device via CAN communication cable. Receives CAN control commands and feedback motor status.
2. Two CAN terminals; either can be used. |
CAN Communication Terminal-2 | 1. Connect to external control device via CAN communication cable. Receives CAN control commands and feedback motor status.
2. Two CAN terminals; either can be used. |
Specific Name - No. | Description |
Debug Serial Port – 1 | Connect to PC via GH1.25 3-pin cable and a USB-to-CAN tool (or general USB-to-serial module). Use DAMIAO debugging assistant for parameter setting and firmware upgrade. |

Specific Name - No. | Description |
Terminal Resistor DIP Switch | 3 - 485 120Ω Terminal Resistor
4 - CAN 120Ω Terminal Resistor
1,2 – Reserved (currently unused) |

Specific Name - No. | Description |
RS485 Communication Terminal 1 | RS485 communication is not yet available. |
RS485 Communication Terminal 2 | RS485 communication is not yet available. |
Motor Dimensions and Mounting
Please refer to the motor mounting hole dimensions and positions to install the motor onto the corresponding equipment.


Indicator Light Status
Normal Status | Green-Solid On | Enabled mode, normal operating status |
Red-Solid On | Disabled mode | |
Abnormal Status | Red – Blinking | Indicates a fault. Corresponding fault types include:
8 – Overvoltage
9 – Undervoltage
A – Overcurrent
B – MOS Overtemperature
C – Motor Coil Overtemperature
D – Communication Loss
E – Overload
You can check the fault type via the feedback frame or through the debugging assistant interface. |
Operating Modes
MIT Mode
MIT mode is designed to be compatible with the original MIT mode. It allows seamless switching while enabling flexible configuration of control ranges (P_ MAX, V_MAX, T_MAX). The ESC converts received CAN data into control variables to calculate the torque value, which serves as the current reference for the current loop. The current loop then regulates to achieve the specified torque current. The control block diagram is as follows:
Derived from the MIT mode, various control modes can be implemented. For example: When kp = 0 and kd ≠ 0, setting v_des enables constant speed rotation; When kp = 0 and kd = 0, setting t_ff enables constant torque output.
Note: When controlling position, kd must not be set to 0, otherwise it may cause motor oscillation or even loss of control.
Position-Velocity Mode
The position cascade mode adopts a three loop series control mode, where the position loop serves as the outermost loop and its output serves as the given value for the velocity loop, while the output of the velocity loop serves as the given value for the inner loop current loop, used to control the actual current output. The control schematic diagram is shown in the following figure:
p_des is the target position for control, and v_des is used to limit the maximum absolute velocity during motion.
When the position cascade mode is controlled using the recommended control parameters from the debugging assistant, it can achieve good control accuracy. The control process is relatively smooth, but the response time is comparatively longer. In addition to v_des, the configurable related parameters also include acceleration/deceleration settings. If additional oscillations occur during the control process, increasing the acceleration/deceleration can help mitigate them.
Note: The units of p_des and v_des are rad and rad/s, respectively, and their data type is float. The damping factor must be set to a positive non-zero number. Please refer to the precautions for the velocity mode.
Velocity Mode
Velocity mode allows the motor to run steadily at the set speed. The control block diagram is as follows:
Note: The unit of v_des is rad/s and its data type is float. To use the automatic parameter calculation function of the debugging assistant, the damping factor must be set to a positive non-zero number. Typically, its value ranges from 2.0 to 10.0. A damping factor that is too small will cause velocity oscillations and large overshoot, while a damping factor that is too large will result in a long rise time. The recommended setting value is 4.0.
Force-Position Hybrid Mode
The force-position hybrid control mode is based on position-velocity control, with additional torque adjustment. Allows control of both position and output torque at the same time. See block diagram below.
A current command saturation stage is added after the velocity loop output command. This limits the current loop reference within the specified range.
Usage
The control uses the CAN standard frame format with a default baud rate of 1 Mbps. Functionally, the frames can be divided into receive frames and feedback frames. Receive frames are the control data received, used to implement functions such as motor command control, parameter read/write, etc. Feedback frames are the status data and motor parameters sent from the motor to the host controller.
Read parameters
Message ID | Attribute | D[0] | D[1] | D[2] | D[3] |
0x7FF | STD | CANID_L | CANID_H | 0x33 | RID |
RID represents the register address; refer to the "Register Map" section for details in this manual.
Upon successful read, the value of the register is returned. The frame format is as follows:
Message ID | Attribute | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
MST_ID | STD | CANID_L | CANID_H | 0x33 | RID | data | data | data | data |
The data is either a floating-point value or an unsigned integer, occupying 32 bits (4 bytes) in total.
The least significant bit is D4, and the most significant bit is D7. The same convention applies below.
Write parameters
Message ID | Attribute | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x7FF | STD | CANID_L | CANID_H | 0x55 | RID | data | data | data | data |
RID is defined as above. Upon successful write, the written value is returned. The frame format is identical to the transmitted frame.
Message ID | Attribute | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
MST_ID | STD | CANID_L | CANID_H | 0x33 | RID | data | data | data | data |
Writing register data takes effect immediately but are not stored; They will be lost upon power-off unless a "Save Parameters" command is issued to store them in internal memory
Save parameters
Message ID | Attribute | D[0] | D[1] | D[2] | D[3] |
0x7FF | STD | CANID_L | CANID_H | 0xAA | 0x01 |
Upon successful execution, the return frame format is:
Message ID | Attribute | D[0] | D[1] | D[2] | D[3] |
MST_ID | STD | CANID_L | CANID_H | 0xAA | 0x01 |
Mode Switching
Multiple control modes are supported and can be switched as follows:
Encoding | Mode |
1 | MIT |
2 | Position-Velocity Mode |
3 | Velocity Mode |
4 | Force-Position Hybrid Control Mode |
The mode can be changed by modifying the mode register (0x0A). During switching, the motor resets all command values to zero, including position, velocity, and torque feed-forward, KP, and KD in MIT mode.
When switching to a position control mode, to avoid impact, it is recommended to first read the precise position (value in register 0x50) and perform the switch when the motor is at zero speed whenever possible.
Mode changes are not saved to flash memory and will be lost after power-off. Upon restart, the motor loads the last mode stored in flash.
CAN Baud Rate Configuration
The current CAN communication baud rate can be modified. Supported baud rates are listed below:
Encoding | Baud Rate |
0 | 125K |
1 | 200K |
2 | 250K |
3 | 500K |
4 | 1M |
After the baud rate is modified, the CAN automatically initializes and feeds back data at the new baud rate.
Feedback Frame
The feedback frame ID is set by the debug assistant (Master ID), with a default value of 0. It primarily feeds back the motor's position, speed, and torque information. Its frame format is defined as follows:
Feedback Message | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
MST_ID | ID|ERR<<4 | POS[15:8] | POS[7:0] | VEL[11:4] | VEL[3:0] | T[11:8] | T[7:0] | T_MOS | T_Rotor |
Where:
- ID: Controller ID, using the lower 8 bits of CAN_ID
- ERR : Status code, with the following meanings
- POS : Motor position
- VEL : Motor velocity
- T : Motor torque
- T_MOS : Average MOSFET temperature on the driver (℃ )
- T_Rotor : Average motor coil temperature (℃ )
0 – Disabled(Default state after power-on)
1 – Enabled
8 — Over-voltage
9 — Under-voltage
A — Over-current
B — MOSFET over-temperature
C — Motor coil over-temperature
D — Communication loss
E — Overload
Position, velocity, and torque use a linear mapping relationship to convert floating-point data into signed fixed-point data. Specifically, position uses 16-bit data, while both velocity and torque use 12-bit data.
Control Frame in MIT Mode
Control Message | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
ID | p_des [15:8] | p_des [7:0] | v_des [11:4] | v_des[3:0] | Kp[11:8] | Kp [7:0] | Kd [11:4] | Kd[3:0] | t_ff[11:8] | t_ff[7:0] |
- Frame ID: Equals the configured CAN ID
- p_des: Desired position
- v_des: Desired velocity
- Kp: Position proportional gain
- Kd: Position derivative gain
- T_ff: Feedforward torque
All parameter follows the mapping rules described in the previous section. The ranges for p_des, v_des, and t_ff can be configured via the configuration tool. Kp range: [0,500], Kd range: [0,5].
A standard CAN frame contains 8 bytes. In MIT mode, the control command packs Position, Velocity,Kp, Kd, and Torque into these 8 bytes:
- Position: 16 bits (2 bytes)
- Velocity: 12 bits
- Kp: 12 bits
- Kd: 12 bits
Control Frame in Position-Velocity Mode
Control Message | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x100+ID | p_des | p_des | p_des | p_des | v_des | v_des | v_des | v_des |
- Frame ID: equals the configured CAN ID plus an offset of 0x100.
- p_des: Desired position, float type, little-endian (low byte first, high byte last).
- v_des: Desired velocity, float type, little-endian (low byte first, high byte last).
The CAN ID used to send commands here is 0x100 + ID. The velocity command represents the maximum velocity during trapezoidal acceleration, i.e., the constant velocity segment.
Control Frame in Velocity Mode
Control Message | D[0] | D[1] | D[2] | D[3] |
0x200+ID | v_des | v_des | v_des | v_des |
- Frame ID: equals the configured CAN ID plus an offset of 0x200.
- v_des: Desired velocity, float type, little-endian (low byte first, high byte last).
The CAN ID used to send commands here is 0x200 + ID.
Control Frame in Force-Position Hybrid Control Mode
Control Message | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x300+ID | p_de | p_de | p_de | p_de | v_des | v_des | i_des | i_des |
- P_des: Desired position, in radians, float type, little-endian (low byte first, high byte last).
- V_des: Velocity limit, in rad/s, scaled by 100, unsigned 16-bit, little-endian (low byte first, high byte last). Valid range: 0-10000. Values exceeding 10000 are capped at 10000, corresponding to an actual velocity limit range of 0-100 rad/s.
- I_des: Torque current limit (per-unit), scaled by 10000, unsigned 16-bit type, little-endian (low byte first, high byte last). Valid range: 0-10000. Values exceeding 10000 are capped at 10000, corresponding to an actual current limit amplitude of 0-1.0.
- Per-unit current: Actual current divided by the maximum phase current.
Host Computer Guide
DAMIAO Host Computer User ManualOn this page
- DAMIAO DM-J10010L-2EC V1.1 Motor Instruction Manual
- Safety Precautions
- Motor Features
- Packing List
- Interface & Pin Description
- Motor Dimensions and Mounting
- Indicator Light Status
- Operating Modes
- MIT Mode
- Position-Velocity Mode
- Velocity Mode
- Force-Position Hybrid Mode
- Usage
- Read parameters
- Write parameters
- Save parameters
- Mode Switching
- CAN Baud Rate Configuration
- Feedback Frame
- Control Frame in MIT Mode
- Control Frame in Position-Velocity Mode
- Control Frame in Velocity Mode
- Control Frame in Force-Position Hybrid Control Mode
- Host Computer Guide

