DAMIAO DM-H6215 V1.0 Motor Instruction Manual
DAMIAO DM-H6215 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
- Integrated design of motor and driver, compact structure, high integration.
- Supports firmware upgrade.
- Capable of providing feedback on motor speed, position, torque, and motor temperature via CAN bus.
- Dual temperature protection function.
- Low speed, high torque.
Packing List
- Motor (including driver, power interface with 240 mm cable outlet) × 1
Interface & Pin Description

Interface / Pin No. | Instruction |
Power connection interface | 1. Connect the power supply via the power cable with XT30(2+2)-F connector. The rated voltage is 24V, which powers the motor.
2. Connect to external control devices via the CAN communication terminal. It can receive CAN control commands and feedback motor status information. |
Motor Dimensions and Mounting
Please install the motor onto the target equipment according to the motor mounting hole dimensions and layout.


Operating Modes
MIT Mode
The MIT mode is compatible with the standard MIT control method, enabling seamless switching while allowing flexible configuration of control limits (P_MAX, V_MAX, T_MAX),CAN commands are converted into torque values. The torque is then used as the reference for current control. See block diagram below.
Based on the MIT model, various control strategies can be derived. For instance, when kp=0 and kd ≠ 0, a constant rotational speed can be achieved by setting v_des. When kp=0 and kd=0, a torque output is applied directly by setting t_ff (feedforward torque).
Note: When controlling position, kd must not be set to zero, as this may cause motor oscillation or even loss of control.
Position-Velocity Mode
This mode uses three control loops: position, velocity, and current(torque). The position loop sets the target for the velocity loop. The velocity loop then sets the target for the current loop. See block diagram below.
p_des represents the target position, while v_des limits the maximum absolute velocity during motion.
When tuned using recommended parameters from the configuration tool, this mode provides high accuracy and smooth motion, at the cost of slower response time.
In addition to v_des, acceleration and deceleration can also be configured. If additional oscillations occur, increasing acceleration/deceleration may help stabilize the system.
Note:
- After power-on, the motor position is fixed at 0.0 rad.
- The units of p_des and v_des are rad and rad/s respectively, and the data type is float. The damping factor must be set to a non-zero positive number. Refer to the precautions for velocity mode for further details.
Velocity Mode
This mode keeps the motor running at the target velocity. See block diagram below.
Note:
- After power-on, the motor position is fixed at 0.0 rad.
- The unit of v_des is rad/s, and the data type is float. If you need to use the debugging assistant to automatically calculate parameters, you must set the damping factor to a non-zero positive number. Typically, the value ranges from 2.0 to 10.0. A damping factor that is too small will cause velocity oscillation and a large overshoot, while a damping factor that is too large will result in a long rise time. The recommended setting is 4.0.
Control Protocol Description
The control uses the CAN standard frame format, with a default baud rate of 1 Mbps, which can be changed via commands. Based on functionality, frames can be divided into receive frames and feedback frames. Receive frames are the received control data used to issue commands to the motor. Feedback frames are the status data sent by the motor to the host controller. Depending on the selected mode of the motor, the definition of the receive frame format and the frame ID vary, but the feedback frames are the same across all modes.
Feedback Frame
The feedback frame ID is set via the configuration tool (Master ID), with a default value of 0. It primarily reports the motor position, velocity, and torque with the frame format 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
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 are are converted from floating-point data to signed fixed-point data using a linear mapping:
- Position: 16-bit signed fixed-point representation.
- Velocity: 12-bit signed fixed-point representation.
- Torque: 12-bit signed fixed-point representation.
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 | 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 for sending commands here is 0x100 + ID. The speed reference is the maximum speed allowed during motor operation.
Control Frame in Velocity Mode
Control Message | D[0] | D[1] | D[2] | D[3] |
0x200+ID | 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.
User Manual
Motor Calibration
Frame ID | Attribute | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x7FF | STD | CANID_L | CANID_H | 0x66 | 0x00 | xx(don't care) |
After calibration is completed, the motor will actively return a calibration completion status frame. Its frame format is as follows:
Frame ID | Attribute | D[0] | D[1] | D[2] | D[3] |
MST_ID | STD | CANID_L | CANID_H | 0x66 | 0x01 |
Parameter Calibration
Frame ID | Attribute | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x7FF | STD | CANID_L | CANID_H | 0x99 | 0x00 | xx(don't care) |
After parameter calibration is completed, the motor will actively return a calibration completion command. Its frame format is as follows:
Frame ID | Attribute | D[0] | D[1] | D[2] | D[3] |
MST_ID | STD | CANID_L | CANID_H | 0x99 | 0x01 |
Read Parameter
Frame ID | Attribute | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x7FF | STD | CANID_L | CANID_H | 0x33 | RID | xx(don’t care) |
RID is the register address.
Register Address | Variable | Description | R/W | Data Type |
0 | UV_Value | Under-voltage protection value | RW | float |
1 | KT_Value | Torque coefficient | RW | float |
2 | OT_Value | Over-temperature protection value | RW | float |
3 | OC_Value | Over-current protection value | RW | float |
4 | ACC | Acceleration | RW | float |
5 | DEC | Deceleration | RW | float |
6 | MAX_SPD | Maximum speed | RW | float |
7 | MST_ID | Feedback ID | RW | uint32 |
8 | ESC_ID | Receive ID | RW | uint32 |
9 | TIMEOUT | Timeout alarm time | RW | uint32 |
10 | CTRL_MODE | Control mode | RW | uint32 |
11 | Damp | Motor viscous damping coefficient | RO | float |
12 | Inertia | Motor moment of inertia | RO | float |
13 | Rsv1 | Reserved parameter 1 | RO | uint32 |
14 | sw_ver | Software version number | RO | uint32 |
15 | Rsv2 | Reserved parameter 2 | RO | uint32 |
16 | NPP | Number of motor pole pairs | RO | uint32 |
17 | Rs | Motor phase resistance | RO | float |
18 | Ls | Motor phase inductance | RO | float |
19 | Flux | Motor flux linkage value | RO | float |
20 | Gr | Gear reduction ratio | RO | float |
21 | PMAX | Position mapping range | RW | float |
22 | VMAX | Speed mapping range | RW | float |
23 | TMAX | Torque mapping range | RW | float |
24 | I_BW | Current loop control bandwidth | RW | float |
25 | KP_ASR | Speed loop Kp | RW | float |
26 | KI_ASR | Speed loop Ki | RW | float |
27 | KP_APR | Position loop Kp | RW | float |
28 | KI_APR | Position loop Ki | RW | float |
29 | OV_Value | Over-voltage protection value | RW | float |
30 | GREF | Gear torque efficiency | RW | float |
31 | Beta | Speed loop damping factor | RW | float |
32 | V_BW | Speed loop filter bandwidth | RW | float |
33 | IQ_cl | Current enhancement coefficient 1 | RW | float |
34 | VL_cl | Speed enhancement coefficient 1 | RW | float |
35 | can_br | CAN baud rate code | RW | uint32 |
36 | sub_ver | Sub-version number | RO | uint32 |
50 | u_off | U-phase offset | RO | float |
51 | v_off | V-phase offset | RO | float |
52 | k1 | Compensation factor 1 | RO | float |
53 | k2 | Compensation factor 2 | RO | float |
54 | e_off | Electrical angle offset | RO | float |
55 | p_m | Motor position | RO | float |
After a successful read, the data from the register will be returned. The frame format is as follows:
Frame 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 of floating-point type, with D[4] as the low byte and D[7] as the high byte. The same applies below.
Write Parameter
Frame 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 |
RID is as described above. After a successful write, the written data will be returned, and the frame format is the same as the one sent.
Frame 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 |
The written register data takes effect immediately but cannot be stored. It will be lost after power-off. To retain the changes, the command to store parameters must be sent, which will write all modified parameters into the internal memory.
Save Parameters
Frame ID | Attribute | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x7FF | STD | CANID_L | CANID_H | 0xAA | RID | xx (don’t care) |
After a successful write, the return format is as follows:
Frame ID | Attribute | D[0] | D[1] | D[2] | D[3] |
MST_ID | STD | CANID_L | CANID_H | 0xAA | 01 |
Mode Switching
Multiple control modes are supported and can be switched as follows:
Code/ID | Mode |
1 | MIT |
2 | Position-Velocity |
3 | Velocity |
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 from one mode to position control mode, to prevent impact, it is recommended to first read the precise position before considering the switch, and to perform the switch when the motor speed is zero.
After the mode is changed, it will not be stored in flash and will be lost after power-off. Upon re-powering, the control mode will be set to the mode last stored in flash.
Baud Rate Modification
Specific baud rate modification is supported. The currently supported baud rates are as follows:
Code | Baud Rate |
0 | 125K |
1 | 200K |
2 | 250K |
3 | 500K |
4 | 1M |
After the baud rate is modified, the CAN bus will automatically reinitialize and feedback data at the new baud rate.
Characteristic Parameters
Please use the motor properly according to the following parameters.
Type | Characteristic Parameters | Description |
Motor parameters | Rated Voltage | 24V |
Rated Phase / Supply Current | 2.5A | |
Peak Phase / Supply Current | 4.3A | |
Rated Torque | 1NM | |
Peak Torque | 2NM | |
Rated speed | 120rpm | |
Maximum No-Load Speed | 320rpm | |
Motor Characteristic Values | Reduction Ratio | 1: 1 |
Number of Pole Pairs | 14 | |
Phase Inductance | 2000uH | |
Phase Resistance | 2.5Ω | |
Structure and Weight | Outer Diameter | 68mm |
Height | 44.5mm | |
Motor Weight | 360g | |
Encoder | Encoder Type | Hall |
Communication Method | Control interface type | CAN |
Parameter Tuning Interface | CAN | |
Control and Protection | Control Mode | MIT Mode |
Velocity Mode | ||
Position Mode | ||
Protection | Driver over-temperature protection: Protection temperature: 120°C. If over-temperature occurs, the motor will exit the "Enable Mode". | |
Motor over-temperature protection: set according to usage requirements. It is recommended not to exceed 100°C. If over-temperature occurs, the motor will exit the "Enable Mode". | ||
Motor overvoltage protection: set according to usage requirements. It is recommended not to exceed 32 V. If overvoltage occurs, the motor will exit the "Enable Mode". | ||
Communication loss protection: If no CAN command is received within the set period, the motor will automatically exit the "Enable Mode". | ||
Motor overcurrent protection: set according to usage requirements. It is recommended not to exceed 9.8 A. If overcurrent occurs, the motor will exit the "Enable Mode". | ||
Motor undervoltage protection: If the power supply voltage falls below the set value, the motor will exit the "Enable Mode". It is recommended that the power supply voltage not fall below 15 V. |
On this page
- DAMIAO DM-H6215 V1.0 Motor Instruction Manual
- Safety Precautions
- Motor Features
- Packing List
- Interface & Pin Description
- Motor Dimensions and Mounting
- Operating Modes
- MIT Mode
- Position-Velocity Mode
- Velocity Mode
- Control Protocol Description
- Feedback Frame
- Control Frame in MIT Mode
- Control Frame in Position-Velocity Mode
- Control Frame in Velocity Mode
- User Manual
- Motor Calibration
- Parameter Calibration
- Read Parameter
- Write Parameter
- Save Parameters
- Mode Switching
- Baud Rate Modification
- Characteristic Parameters

