DAMIAO DM-JH11-2EC V1.0 Motor Instruction Manual
DAMIAO DM-JH11-2EC V1.0 Motor User Guide
Safety Precautions
- Strictly use the motor within the specified operating environment and maximum allowable winding temperature range; failure to do so may cause permanent and irreversible damage to the product.
- Prevent foreign objects from entering the rotor interior; otherwise, abnormal rotor operation may occur.
- Before use, check that all components are intact. If any part is missing, aged, damaged, etc., stop using the product.
- Ensure correct wiring and that the motor is installed correctly and securely.
- Do not touch the electronic rotor parts during operation to avoid accidents. The motor may heat up during high-torque output; be careful to avoid burns.
- Do not disassemble the motor without authorization, as this may affect the control accuracy of the motor or even cause abnormal operation.
- When using a host computer to control cyclic synchronous position, speed, or torque modes, the new host computer version 2.0.3.6 or higher is required.
- Service life note: The service life of the harmonic reducer mainly depends on the wear of the wave generator bearing and the flexspline, as expressed by the formula.The theoretical service life of the reducer can be calculated using the formula:
- Where:
- Tr:is the rated torque of the reducer,
- Tav :is the actual average load torque of the reducer,
- Nr:is the rated speed of the reducer,
- Nav:is the actual average operating speed of the reducer,
- Ln:is the design life of the reducer (theoretical value: 7000 hours).Torque overload behavior has a very serious impact on the service life of the reducer.
- The harmonic reducer is a high-precision transmission component, and its flexspline and flexible bearing are extremely sensitive to load conditions. Any overload operation exceeding the rated parameters may lead to increased fatigue and shortened service life. Ensure that the harmonic joint module is used within the rated operating conditions. Damage to the flexspline or flexible bearing caused by prolonged overload or unexpected impact conditions is not covered under the company’s warranty.
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.
- Supports CAN FD, with a maximum baud rate of 5Mbps.
- Provides real-time feedback of motor Velocity, position, torque, and temperature via CAN bus.
- Features dual temperature protection mechanisms.
- CAN upgrade is supported.
Specifications
Please operate the motor within the specifications listed below.
Type | Characteristic Parameters | DM-JH11-51-2EC | DM-JH11-101-2EC |
Motor parameters | Rated Voltage | 24V-48V | 24V-48V |
Rated Phase / Supply Current | 2.23A/1.19A@24V;
2.23A/0.54A@48V; | 2.3A/1.0A@24V;
2.3A/0.5A@48V; | |
Peak Phase / Supply Current | 4.26A/4.25A@24V;
4.26A/1.85A@48V; | 3.6A/2.2A@24V;
3.6A/1.0A@48V; | |
Rated Torque | 3.2NM | 4.8NM | |
Peak Torque | 7.8NM | 10.5NM | |
Rated speed | 40rpm | 20rpm | |
Maximum No-Load Speed | 60rpm | 30rpm | |
Motor Characteristic Values | Reduction Ratio | 51 : 1 | 101:1 |
Number of Pole Pairs | 7 | 7 | |
Phase Inductance | 538uH(@25℃) | 538uH(@25℃) | |
Phase Resistance | 1.1Ω(@25℃) | 1.1Ω(@25℃) | |
Structure and Weight | Outer Diameter | 52mm | 52mm |
Height | 60mm | 60mm | |
Central hole size | 8.5mm | 8.5mm | |
Motor Weight | 345g | 345g | |
Encoder | Encoder Resolution | 17bit | 17bit |
Number of Encoders | 2 | 2 | |
Encoder Type | Double editor (single circle) | Double editor (single circle) | |
Communication Method | Control interface type | CAN@5Mbps(Max) | CAN@5Mbps(Max) |
Parameter Tuning Interface | UART@921600bps | UART@921600bps | |
Control and Protection | Control Mode | MIT Mode | MIT Mode |
Velocity Mode | Velocity Mode | ||
Position Mode | Position Mode | ||
Force-Position Hybrid Control Mode | Force-Position Hybrid Control Mode | ||
Periodic Synchronous Position Mode | Periodic Synchronous Position Mode | ||
Cycle Synchronization Speed Mode | Cycle Synchronization Speed Mode | ||
periodic synchronous torque mode | periodic synchronous torque mode | ||
Protection | Drive over-temperature protection: shutdown at 100° C; the motor exits Enable Mode when triggered. | Drive over-temperature protection: shutdown at 100° C; the motor exits Enable Mode when triggered. | |
Motor over-temperature protection (configurable, recommended ≤ 90° C); the motor exits Enable Mode when triggered. | Motor over-temperature protection (configurable, recommended ≤ 90° C); the motor exits Enable Mode when triggered. | ||
Over-voltage protection(configurable, recommended ≤ 54V); exits Enable Mode when triggered. | Over-voltage protection(configurable, recommended ≤ 54V); exits Enable Mode when triggered. | ||
Communication Loss Protection: the motor exits Enable Mode if no CAN command is received within the specified timeout period. | Communication Loss Protection: the motor exits Enable Mode if no CAN command is received within the specified timeout period. | ||
Over-current protection (configurable, recommended ≤ 0.98A); exits Enable Mode when triggered. | Over-current protection (configurable, recommended ≤ 0.98A); exits Enable Mode when triggered. | ||
Under-voltage protection: the motor exits Enable Mode if supply voltage falls below the threshold (recommended ≥ 20V). | Under-voltage protection: the motor exits Enable Mode if supply voltage falls below the threshold (recommended ≥ 20V). |
Operating Voltage
The operating voltage range of the drive is 24V to 48V. It is recommended to reduce hot-plugging when the voltage exceeds 36V. The minimum operating voltage is 20V, and the maximum operating voltage is 54V.
Maximum Phase Current
The maximum phase current of the driver can be obtained from the startup serial output:

The maximum phase current percentage can be limited by setting a percentage in the configuration tool. The default value is 0.8 (i.e., 80% of the measurable maximum current). It is recommended that this value not exceed 98%.
Encoder version
The encoder version currently used by the motor can be queried through the serial port print information during power-on. “isensor” represents the encoder at the motor rotor side, “osensor” represents the encoder at the output shaft side, “app” indicates the version number, and “boot” refers to the bootloader serial number.

Maximum Rotational Speed
The maximum rotational speed is limited by multiple factors, including the power supply voltage (VBUS), rotor flux linkage (ψf), and gear ratio (GR). An upper limit can usually be calculated using the formula below. During operation, the speed is limited to 2000 rpm (rotor side).
where VBUS is the supply voltage, Npp is the number of pole pairs, and ψf is the rotor flux linkage.
Torque Constant
The torque constant of the motor can be considered constant within its rated range. With a gearbox, it can be calculated using the following formula:
Where Npp is the number of pole pairs, ψf is the rotor flux linkage, GR is the gear ratio, and GREF is the gearbox torque transmission coefficient.
Packing List
- Motor (with integrated driver) ×1
- Power cable (with CAN interface) : SH1.0 cable 8-pin (200mm) ×1
- Debug serial cable: SH1.0 cable 3-pin (200mm) ×1
Interface & Pin Description


Interface / Pin No. | Instruction |
Power + CAN Communication Terminal(1) (2) | 1. Connect the power supply using an SH1.0 8-pin power cable. The rated voltage is 24V (supports 24–48V) to supply power to the motor.
2. Connect 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(Port 3) | Connect using an SH1.0 3-pin cable and an intermediate adapter board (SH1.0 3-pin + 8-pin to XT30 + GH1.25). Use a USB-to-CAN debugging tool (or a general-purpose USB-to-serial module) to connect to a PC. Use the Damiao Technology Debug Assistant to configure motor parameters and perform firmware upgrades. |
Interface / Pin No. | Instruction |
Motor Indicator Light(5) | Red light always on: Motor is in the disabled state.
Green light always on: Motor is in the enabled state.
Red light flashing: Motor has reported an error. Check the feedback frame to determine the specific error type.
Green light flashing: Motor power-on self-test failed. Take a screenshot of the power-on print information and contact customer service. |

Interface / Pin No. | Instruction |
Termination Resistor Switch(4) | The motor is equipped with a termination resistor, which is enabled by default. |
Motor Dimensions and Mounting
Please install the motor onto the target equipment according to the motor mounting hole dimensions and layout.

LED Status
Normal Status | Solid Green | Enable Mode (ERR = 1), normal operation |
Solid Red | Disable Mode (ERR = 0)(Default state after power-on) | |
Fault Status | Flashing Red | Fault codes and fault conditions:
2 – Motor-side encoder not recognized
3 – Output shaft encoder not recognized
5 – Motor encoder calibration error;
8 – Over-voltage;
9 – Under-voltage;
A – Over-current;
B – MOS over-temperature;
C – Motor winding over-temperature;
D – Communication loss;
E – Overload;
Fault conditions can be identified via the feedback frames or
displayed in the the Damiao configuration software. |
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).The electronic speed controller (ESC) converts the received CAN data into control variables and calculates a torque value, which is used as the current reference for the current loop. The current loop then follows its regulation scheme to ultimately achieve the given torque current.
(This motor features a newly added speed limiter, which prevents the motor from exceeding the maximum allowable speed.) The control block diagram is shown 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: v_des is in rad/s, and the data type is float.
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.
Cyclic Synchronous Position Mode (CSP)
In this mode, absolute position preset values are sent to the controller via the fieldbus at fixed time intervals (referred to as the “cycle”). In this case, the controller no longer calculates the ramp; it simply follows the preset values to execute motion. The control block diagram is shown in the figure below.

In this mode, position commands should be issued in a gradually progressive manner. Avoid sending abrupt or sudden position commands; otherwise, motor vibration may occur (this mode has input parameter limits). Upper-level trajectory planning should be performed, and the planned trajectory should be sent to the motor incrementally.
Cyclic Synchronous Velocity Mode (CSV)
In Cyclic Synchronous Velocity Mode (CSV), the host controller periodically and synchronously sends the calculated target velocity to the servo drive. The velocity and torque regulation are executed internally by the servo drive. The control block diagram is shown in the figure below.

In this mode, position commands should be issued in a gradually progressive manner. Avoid sending abrupt or sudden position commands; otherwise, motor vibration may occur (this mode has input parameter limits). Upper-level trajectory planning should be performed, and the planned trajectory should be sent to the motor incrementally.
Cyclic Synchronous Torque Mode (CST)
In Cyclic Synchronous Torque Mode (CST), the host controller periodically and synchronously sends the calculated target torque to the servo drive. Torque regulation is executed internally by the servo drive. When the speed reaches the limit value, the drive enters the speed regulation phase. The control block diagram is shown in the figure below.

In this mode, torque commands should be issued in a gradually progressive manner. Avoid sending abrupt or sudden torque commands; otherwise, motor vibration may occur (this mode has input parameter limits). Upper-level trajectory planning should be performed, and the planned trajectory should be sent to the motor incrementally.
Mode Switching
Mode switching can be configured via the host computer using the serial port. Simply select the desired mode and click "Write Parameters". After successful configuration using this method, the motor will automatically reset, and the mode will be stored inside the motor driver without being lost after power cycling.
Additionally, mode switching can also be performed via the CAN interface by modifying the content of the mode register. For details, refer to the "Mode Switching" section in the next chapter.
When using the CAN method, the motor will not reset, but the following five variables will be cleared to zero:
- Position command value
- Velocity command value
- Torque command value (MIT mode)
- kp (MIT mode)
- kd (MIT mode)
Note: If the "Save Parameters" command is not issued, the mode will not be stored. It will be lost after power loss and will load the last saved mode upon power-up.
CAN communication
The motor can be used after completing calibration, parameter setting, and configuration. Control uses the CAN standard frame (STD) format, with a default baud rate of 1 Mbps. The baud rate can be changed using commands; refer to the CAN Baud Rate Modification section for details. Functionally, frames can be divided into receive frames and feedback frames. Receive frames are the control data received for commanding the motor. Feedback frames are the status data sent by the motor to the host controller. The feedback mechanism is query-based: whenever the drive receives a frame whose ID matches the motor’s configured CAN ID (the lower 8 bits are checked for matching, while the upper 3 bits are ignored), the drive transmits the current status data onto the bus. Depending on the selected mode of the motor, the receive frame format and frame ID vary, but the feedback frame is the same across all modes.
CAN Baud Rate Configuration
The baud rate can be modified using the host computer via the serial port. Simply select the desired baud rate and click “Write Parameter”. After successful configuration using this method, the motor will automatically reset, and the baud rate will be stored inside the motor driver. The setting will not be lost after power cycling.
Another method is to modify the baud rate via the CAN interface by writing to the baud rate register. Refer to the “CAN Baud Rate Modification” subsection in this chapter for details.
Note: Modifying the baud rate via CAN may fail when multiple devices are present on the bus. Therefore, proceed with caution. It is strongly recommended to configure the baud rate before system integration.
Use this method with caution. It is strongly recommended to configure the baud rate before connecting multiple devices.
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
2 – Motor-side encoder not recognized 3 – Output shaft encoder not recognized
5 – Motor encoder calibration error;
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.
See the figures below:
- Position linear mapping
- Velocity linear mapping
- Torque Linear Mapping
Note:
- After power-on, the reported position is limited to the range [-π, π] rad.
- The unit of position is rad (radians), representing the output shaft position (after gear reduction). All references to position below follow this definition.
- The unit of velocity is rad/s, representing the output shaft velocity (after gear reduction). All references to velocity below follow this definition.
- The unit of torque is Nm, representing the output shaft torque (after gear reduction). All references to torque below follow this definition.
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
MIT commands are transmitted by linearly scaling floating-point values into integer representations. The driver converts the received integers back into floating-point values using the same scaling. Two conversion functions are used: float_to_uint, uint_to_float.
Conversion Method:
The conversion requires predefined minimum and maximum values for each variable, which can be configured on the parameter setting page. Default ranges: KP: 0.0 ~ 500.0, KD: 0.0 ~ 5.0.
Position, velocity, and torque are preset to ±12.5, ±10, and ±12. These values can be adjusted according to the motor specifications. When sending control commands, the scaling ranges must remain consistent with the configured values.

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_des | p_des | p_des | p_des | 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.
Control Frame in Cyclic Synchronous Velocity-Position Mode
Control Message | D[0] | D[1] | D[2] | D[3] | D[4] | D[5] | D[6] | D[7] |
0x400+ID | p_des | p_des | p_des | p_des | v_des | v_des | v_des | v_des |
The frame ID is the configured CAN ID value plus an offset of 0x400.
- p_des: Position command, floating-point type, little-endian (low byte first, high byte after).
- v_des: Velocity command, floating-point type, little-endian (low byte first, high byte after).
The CAN ID for sending commands here is 0x400 + ID. The velocity command is the maximum speed limit during operation.
Control Frame in Cyclic Synchronous Velocity Mode (CSV)
Control Message | D[0] | D[1] | D[2] | D[3] |
0x500+ID | v_des | v_des | v_des | v_des |
The frame ID is the configured CAN ID value plus an offset of 0x500.
- v_des: Velocity command, floating-point type, little-endian (low byte first, high byte after).
The CAN ID for sending commands here is 0x500 + ID.
Control Frame in Cyclic Synchronous Torque Mode (CST)
Control Message | D[0] | D[1] | D[2] | D[3] |
0x600+ID | t_des | t_des | t_des | t_des |
The frame ID is the configured CAN ID value plus an offset of 0x600.
- t_des: Torque command, floating-point type, little-endian (low byte first, high byte after).
The CAN ID for sending commands here is 0x600 + ID.
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 | 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 |
【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:
Encoding | Mode |
1 | MIT |
2 | Position-Velocity Mode |
3 | Velocity Mode |
4 | Force-Position Hybrid Control Mode |
5 | Cyclic Synchronous Position Mode |
6 | Cyclic Synchronous Velocity Mode |
7 | Cyclic Synchronous Torque 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
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:
Encoding | 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,4] | uint32 |
0x25 | 37 | Boot_ver | Boot Version | RO | / | uint32 |
0x36 | 54 | x_off | Output shaft angle deviation | RO | / | float |
0x37 | 55 | dir | Direction | RO | / | float |
0x38 | 56 | m_off | Motor-side Angle Offset | RO | / | float |
0x3C | 60 | VBus | Bus Voltage | 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.
Host Computer Guide
DAMIAO Host Computer User ManualNext →
DAMIAO DocsOn this page
- DAMIAO DM-JH11-2EC V1.0 Motor Instruction Manual
- Safety Precautions
- Motor Features
- Specifications
- Operating Voltage
- Maximum Phase Current
- Encoder version
- Maximum Rotational Speed
- Torque Constant
- Packing List
- Interface & Pin Description
- Motor Dimensions and Mounting
- LED Status
- Operating Modes
- MIT Mode
- Position-Velocity Mode
- Velocity Mode
- Force-Position Hybrid Mode
- Cyclic Synchronous Position Mode (CSP)
- Cyclic Synchronous Velocity Mode (CSV)
- Cyclic Synchronous Torque Mode (CST)
- Mode Switching
- CAN communication
- 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
- Control Frame in Cyclic Synchronous Velocity-Position Mode
- Control Frame in Cyclic Synchronous Velocity Mode (CSV)
- Control Frame in Cyclic Synchronous Torque Mode (CST)
- Enable
- Disable
- Set Zero Position
- Clear Faults
- Read parameters
- Write parameters
- Save parameters
- Mode Switching
- CAN Baud Rate Configuration
- Register Map
- Host Computer Guide

