DAMIAO DM-H3510 V1.0 Motor Instruction Manual
DAMIAO DM-H3510 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, and high integration.
- Motor speed, position, torque, and temperature can be fed back via the CAN bus.
- Dual temperature protection.
- Visual parameter tuning via host computer software; ready to use after simple configuration.
- Supports CAN FD, with a maximum baud rate of up to 5 Mbps.
- Low speed, high torque.
- Flexible switching between multiple control modes.
Packing List
Type | List |
Motor (including driver) | 1. Motor (including driver) ×1
2. Power + CAN communication terminal connector cable: SH1.0 connector cable - 8pin (200mm) ×1
3. Debugging serial port signal cable: SH1.0 connector cable - 3pin (200mm) ×1
It is recommended to purchase the adapter board separately: Adapter board (SH1.0 3pin + 8pin to XT30 + GH1.25), as it is not included with the motor. |
Motor + USB-to-CAN | 1. Motor (including driver) ×1
2. Power + CAN communication terminal connector cable: SH1.0 connector cable - 8pin (200mm) ×1
3. Debugging serial port signal cable: SH1.0 connector cable - 3pin (200mm) ×1
4. USB-to-CAN debugging tool ×1
It is recommended to purchase the adapter board separately: Adapter board (SH1.0 3pin + 8pin to XT30 + GH1.25), as it is not included with the motor. |
Motor + USB-to-CAN + adapter board | 1. Motor (including driver) ×1
2. Power + CAN communication terminal connector cable: SH1.0 connector cable - 8pin (200mm) ×1
3. Debugging serial port signal cable: SH1.0 connector cable - 3pin (200mm) ×1
4. USB-to-CAN debugging tool ×1
5. Adapter board (SH1.0 3pin + 8pin to XT30 + GH1.25) |
Motor + adapter board | 1. Motor (including driver) ×1
2. Power + CAN communication terminal connector cable: SH1.0 connector cable - 8pin (200mm) ×1
3. Debugging serial port signal cable: SH1.0 connector cable - 3pin (200mm) ×1
4. Adapter board (SH1.0 3pin + 8pin to XT30 + GH1.25) |
Interface & Pin Description

Interface / Pin No. | Instruction |
Power + CAN communication terminal | 1. Connect the power supply via the SH1.0 8-pin power cable. The rated voltage is 24V (supports 24-30V) to power the motor.
2. Connect to external control devices via the CAN communication terminal to receive CAN control commands and feedback motor status information. |

Interface / Pin No. | Instruction |
Debug Serial Interface | Connect the SH1.0 3-pin cable to the adapter board (SH1.0 3pin+8pin to XT30+GH1.25), then use the USB-to-CAN debugging tool (or a general USB-to-serial module) to connect to a PC. Use Damiao Technology Debug Assistant to configure motor parameters and perform firmware upgrades. |

Interface / Pin No. | Instruction |
Terminal resistor switch | The motor is equipped with a terminal resistor, which is enabled by default. |
Note: When inserting the connector cable into the motor port, pay attention to the correct orientation of the connector to avoid bending or damaging the pins.
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: The units of p_des and v_des are rad and rad/s respectively, and both are of type float. The damping factor must be set to a non-zero positive value.Refer to the notes for velocity mode.
Velocity Mode
This mode keeps the motor running at the target velocity. See block diagram below.
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.
Instruction Manual
Control uses the CAN standard frame format with a fixed baud rate of 1 Mbps. Frames can be divided into receive frames and feedback frames based on their function. Receive frames are the received control data used to command the motor; feedback frames are the status data sent from the motor to the higher-level controller. Depending on the selected mode of the motor, the frame format definition and frame ID of the receive frames 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(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 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 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 |
- 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 Mode
Control Message | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x300+ID | p_des | v_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.
Enable
After power-up self-test, an "Enable" command must be sent to allow motor control. The "Enable" frame is a control frame, with the frame ID as described above. The data payload is identical across all modes as follows:
D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFC |
Disable
The default power-on state of the motor is "Disable." In this state, the three-phase terminal voltages are identical, each being a 50% modulation of the power supply voltage. The "Disable" frame is a control frame, with the frame ID as described above. The data payload is defined as follows:
D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFD |
Set Zero Position
The "Set Zero Position" frame is a control frame. This command sets the current output shaft position as the zero reference and resets the position command value to 0. The frame ID follows the definition above, and the data payload is defined as follows:
D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFE |
Clear Faults
When faults such as overheating, sending a "Clear" can be sent to reset the fault state. The "Clear" frame is a control frame. The frame ID follows the definition above, and the data payload is defined as follows:
D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFF | 0xFB |
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 |
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 |
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 | 0x55 | RID | 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 |
【Note】:
- The "Save Parameters" command is only effective in Disabled Mode.
- All parameters are stored simultaneously during this operation.
- This operation writes parameters to the on-chip flash memory. The maximum execution time is 30ms; please allow sufficient time.
- The flash memory supports approximately 10,000 erase/write cycles. Avoid frequent execution of the "Save Parameters" command.
Mode Switching
Multiple control modes are supported and can be switched as follows:
Code/ID | Mode |
1 | MIT |
2 | Position-Velocity |
3 | Velocity |
4 | Force-Position Hybrid Control |
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
By writing specific value to the baud rate register (address 0x23), the current CAN communication baud rate can be modified. Supported baud rates are listed below:
Code/ID | Baud Rate |
0 | 125K |
1 | 200K |
2 | 250K |
3 | 500K |
4 | 1M |
5 | 2M |
6 | 2.5M |
7 | 3.2M |
8 | 4M |
9 | 5M |
Baud Rate Switching Behavior:
After a successful update, the driver first transmits feedback using the original baud rate and then switch to communication using the new baud rate.
Baud Rate Handling at Power-Up:
At power-up, the driver determines the communication mode based on the stored baud rate.
- If the stored baud rate exceeds 5Mbps, the baud rate is reset to 1Mbps by default.
- If the baud rate is greater than 1 Mbps (excluding 1 Mbps), the driver operates in CAN FD mode.
- If the baud rate is ≤ 1 Mbps, the driver operates in CAN 2.0B mode.
CAN FD Compatibility Note: A motor configured in CAN FD mode can still receive CAN 2.0B data frames. However, feedback frames are transmitted using CAN FD. As a result, if the upper-level controller only supports CAN 2.0B, it will not receive feedback data, the driver may continuously report communication errors.
Recovery Note: For controllers operating in CAN 2.0B mode, even if the CAN ID is incorrectly configured, the baud rate can still be restored by sending a baud rate configuration command.
Register Map
Address(HEX) | Address(DEC) | Variable | Description | R/W | Range | Type |
0x00 | 0 | UV_Value | Undervoltage Threshold | RW | (10.0,fmax] | float |
0x01 | 1 | KT_Value | Torque Constant | RW | [0.0,fmax] | float |
0x02 | 2 | OT_Value | Over-temperature Threshold | RW | [80.0,200) | float |
0x03 | 3 | OC_Value | Overcurrent Threshold | RW | (0.0,1.0) | float |
0x04 | 4 | ACC | Acceleration | RW | (0.0,fmax) | float |
0x05 | 5 | DEC | Deceleration | RW | [-fmax,0.0) | float |
0x06 | 6 | MAX_SPD | Max Velocity | RW | (0.0,fmax] | float |
0x07 | 7 | MST_ID | Master ID | RW | [0,0x7FF] | uint32 |
0x08 | 8 | ESC_ID | Command CAN ID | RW | [0,0x7FF] | uint32 |
0x09 | 9 | TIMEOUT | Timeout Threshold | RW | [0,2^32-1] | uint32 |
0x0A | 10 | CTRL_MODE | Control Mode | RW | [0,4] | uint32 |
0x0B | 11 | Damp | Viscous Damping | RO | / | float |
0x0C | 12 | Inertia | Rotor Inertia | RO | / | float |
0x0D | 13 | hw_ver | Reserved | RO | / | uint32 |
0x0E | 14 | sw_ver | Firmware Version | RO | / | uint32 |
0x0F | 15 | SN | Reservd | RO | / | uint32 |
0x10 | 16 | NPP | Number of Pole Pairs | RO | / | uint32 |
0x11 | 17 | Rs | Phase Resistance | RO | / | float |
0x12 | 18 | Ls | Phase Inductance | RO | / | float |
0x13 | 19 | Flux | Flux Linkage | RO | / | float |
0x14 | 20 | Gr | Gear Reduction Ratio | RO | / | float |
0x15 | 21 | PMAX | Position Mapping Range | RW | (0.0,fmax] | float |
0x16 | 22 | VMAX | Velocity Mapping Range | RW | (0.0,fmax] | float |
0x17 | 23 | TMAX | Torque Mapping Range | RW | (0.0,fmax] | float |
0x18 | 24 | I_BW | Current-loop Bandwidth | RW | [100.0,1.0e4] | float |
0x19 | 25 | KP_ASR | Velocity Loop Kp | RW | [0.0,fmax] | float |
0x1A | 26 | KI_ASR | Velocity Loop Ki | RW | [0.0,fmax] | float |
0x1B | 27 | KP_APR | Position Loop Kp | RW | [0.0,fmax] | float |
0x1C | 28 | KI_APR | Position Loop Ki | RW | [0.0,fmax] | float |
0x1D | 29 | OV_Value | Overvoltage Threshold | RW | TBD | float |
0x1E | 30 | GREF | Gear Torque Efficiency | RW | (0.0,1.0] | float |
0x1F | 31 | Deta | Velocity Loop Damping Coefficient | RW | [1.0,30.0] | float |
0x20 | 32 | V_BW | Velocity Loop Filter Bandwidth | RW | (0.0,500.0) | float |
0x21 | 33 | IQ_c1 | Iq Gain | RW | [100.0, 1.0e4] | float |
0x22 | 34 | VL_c1 | Velocity Loop Gain Factor | RW | (0.0,1.0e4] | float |
0x23 | 35 | can_br | CAN Baud Rate | RW | [0,9] | uint32 |
0x24 | 36 | sub_ver | Sub-version | RO | / | uint32 |
0x32 | 50 | u_off | Phase U Current Offset | RO | / | float |
0x33 | 51 | v_off | Phase V Current Offset | RO | / | float |
0x34 | 52 | k1 | Compensation Coefficient 1 | RO | / | float |
0x35 | 53 | k2 | Compensation Coefficient 2 | RO | / | float |
0x36 | 54 | m_off | Angle Offset | RO | / | float |
0x37 | 55 | dir | Direction | RO | / | float |
0x50 | 80 | p_m | Motor Position | RO | / | float |
0x51 | 81 | xout | Output Shaft Position | RO | / | float |
Note:
- RW: Read/Write.
- RO: Read-only.
On this page
- DAMIAO DM-H3510 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
- Force-Position Hybrid Mode
- Instruction Manual
- Feedback Frame
- Control Frame in MIT Mode
- Control Frame in Position-Velocity Mode
- Control Frame in Velocity Mode
- Control Frame in Force-Position Hybrid Mode
- Enable
- Disable
- Set Zero Position
- Clear Faults
- Read parameters
- Write parameters
- Save parameters
- Mode Switching
- CAN Baud Rate Configuration
- Register Map

