DM-J8009-2EC Motor Instruction Manual
DM-J8009-2EC 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.
- Supports trapezoidal acceleration and deceleration profiles in position mode.
Naming Conventions
For example:DM - J8009 X - 2EC VX.X (48V)
DM | (Brand)DAMIAO Technology |
J | J:Joint Motor Series
S:Separable Motor Series |
80 | Stator Diameter 35、43、60、62、80、100(mm) |
09 | Reduction Ratio 06、07、09、10、19、40、48 |
X - | Output Bearing Version
-By default:Deep Groove Ball Bearing.
-P:Crossed Roller Bearing.
-L:Lite version (not related to bearing type). |
2EC | Encoder
-By default:single encoder.
-1EC:Single encoder, CAN communication.
-2EC:Dual encoders (single-turn absolute, output shaft),CAN communication.
-1EE:Single encoder, EtherCAT communication.
-2EE:Dual encoder (single-turn absolute, output shaft), EtherCAT communication. |
VX.X | Motor Version |
(48V) | Driver Rated Voltage
-By default:24V drive voltage
-48V :48V drive voltage |
Specifications
Please operate the motor within the specifications listed below.
Type | Characteristic Parameters | Description |
Motor parameters | Rated Voltage | 24V(Support 24-48V) |
Rated Phase / Supply Current | 20A | |
Peak Phase / Supply Current | 50A | |
Rated Torque | 20NM | |
Peak Torque | 40NM | |
Rated speed | 100rpm@24V
200rpm@48V | |
Maximum No-Load Speed | 160rpm@24V
320rpm@48V | |
Motor Characteristic Values | Reduction Ratio | 9 : 1 |
Number of Pole Pairs | 21 | |
Phase Inductance | 61uh(@25℃ ) | |
Phase Resistance | 0.09Ω(@25℃ ) | |
Structure and Weight | Outer Diameter | 98mm |
Height | 61.7mm | |
Motor Weight | ~ 896g | |
Encoder | Encoder Resolution | 14bit |
Number of Encoders | 2 | |
Encoder Type | Magnetic Encoder (single-turn absolute) | |
Communication Method | Control interface type | CAN@1Mbps |
Parameter Tuning Interface | UART@921600bps | |
Control and Protection | Control Mode | MIT Mode |
Velocity Mode | ||
Position Mode | ||
Force-Position Hybrid Control Mode | ||
Protection | Drive over-temperature protection: shutdown at 120° C; the motor exits Enable Mode when triggered. | |
Motor over-temperature protection (configurable,recommended ≤ 100° C); the motor exits Enable Mode when triggered. | ||
Over-voltage protection (configurable,
recommended ≤ 52V); exits Enable Mode when triggered. | ||
Communication Loss Protection: the motor exits Enable Mode if no CAN command is received within the specified timeout period. | ||
Over-current protection (configurable,recommended ≤ 39A); exits Enable Mode when triggered. | ||
Under-voltage protection: the motor exits Enable Mode if supply voltage falls below the threshold (recommended ≥ 15V). |
Operating Voltage
The operating voltage range for the driver is 24V to 48V. Hot-swapping is not recommended above 36V. The minimum operating voltage is 15V, and the maximum operating voltage is 52V.
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%.
Maximum Rotational Speed
The maximum rotational speed is limited by multiple factors, including the power supply voltage (V_BUS), rotor flux linkage (ψ_t), and gear ratio (GR). An upper limit can typically be calculated using the following formula:
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.
Torque–Speed (T–N) Curve
The following curve shows the measured performance at 24 V and an ambient temperature of 25° C:

Packing List
- Motor (with integrated driver) ×1
- Power cable: XT30 male-to-female cable×1
- CAN interface: GH1.25 2-Pin Cable ×1
- Debug serial cable: GH1.25 3-pin cable ×1
Interface and wiring sequence description

Specific Name - No. | Description |
Power Interface-1 | Connect the power supply using the XT30
male-to-female cable. The rated voltage is
24V(supports 24–48 V). |

Specific Name - No. | Description |
CAN interface-2 | Connect external controller via the CAN communication interface to receive CAN control commands and transmit motor status feedback. |

Specific Name - No. | Description |
Debug Serial Interface(Port3) | Connect to a PC via the GH1.25 3-pin cable using a USB-to-CAN adapter (or USB-toserial module) for parameters configuration and firmware upgrades. |
Motor Dimensions and Installation
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:
3 – Output shaft calibration error;
4 – Sensor output error;
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).
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 Control 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.
Mode modification
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
After calibration, parameter identification, and parameter configuration are completed, the motor is ready for operation.
Control is performed using CAN standard frames (STD). The default baud rate is 1 Mbps, which can be modified via commands. Refer to the "CAN Baud Rate" section for details.
Frame Types:
CAN communication is divided into two types:
- Command Frames
Frames received by the driver, used to send control commands to the motor.
- Feedback Frames
Frames transmitted by the driver to the upper-level controller, containing motor status data.
Feedback Mechanism:
Feedback operates in a request-response manner. When the driver receives a CAN frame whose ID matches the configured motor CAN ID:
- The lower 8 bits are used for validation.
- The upper 3 bits are ignored.
Once a match is detected, the driver will transmit the current motor status to the CAN bus.
Frame Format:
The command frame format and frame ID vary depending on the selected control mode. The feedback frame format remains the same across all control modes.
CAN Baud Rate Configuration
The CAN baud rate can be configured in two ways:
- Configuration via Serial Interface,.
- Select the desired baud rate.
- Click "Write Parameters" to apply.
- The motor will automatically reboot.
- The baud rate will be stored in the driver.
- The setting will persist after power cycling.
- Configuration via CAN Interface The baud rate can also be modified via the CAN interface by writing to the corresponding baud rate register. See "CAN Baud Rate" in this chapter for details.
The baud rate can be set through the host PC software via the serial interface.
After the setting is successfully written:
Note: When modifying the baud rate via CAN, the operation may fail if multiple devices are present on the bus.
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.
See the figure 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, ±45, and ±54. These values can be adjusted according to the motor specifications. When sending control commands, the scaling ranges must remain consistent with the configured values.
Otherwise, the commands will be scaled incorrectly.
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 defines the maximum allowable velocity during operation.
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.
Enable
After the power-on self-test is completed, the "Enable" command must be sent before control can be performed. The "Enable" frame is a control frame, with the frame ID as described previously. The difference lies in the data field. Regardless of which mode the motor is in, the data definition for "Enable" is the same, 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 |
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 Modification
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,4] | 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.
- Motor output shaft position is calculated form the rotor position, in radians (rad)
- Output shaft position refers is measured directly by the output shaft encoder, in radians (rad).
Host Computer Guide
DAMIAO Host Computer User ManualOn this page
- DM-J8009-2EC Motor Instruction Manual
- Safety Precautions
- Motor Features
- Naming Conventions
- Specifications
- Operating Voltage
- Maximum Phase Current
- Maximum Rotational Speed
- Torque Constant
- Torque–Speed (T–N) Curve
- Packing List
- Interface and wiring sequence description
- Motor Dimensions and Installation
- LED Status
- Operating Modes
- MIT Mode
- Position-Velocity Mode
- Velocity Mode
- Force-Position Hybrid Control Mode
- Mode modification
- 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
- Enable
- Disable
- Set Zero Position
- Clear Faults
- Read parameters
- Write parameters
- Save parameters
- Mode Switching
- CAN Baud Rate Modification
- Register Map
- Host Computer Guide

