Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package dynamixel_hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.4.12 (2025-08-11)
------------------
* Added support for all dynamixel models that supports dynamixel protocol 2.0
* Contributors: Woojin Wie

1.4.11 (2025-07-21)
------------------
* Added support for firmware version-aware model file selection
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>dynamixel_hardware_interface</name>
<version>1.4.11</version>
<version>1.4.12</version>
<description>
ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework.
</description>
Expand Down
17 changes: 17 additions & 0 deletions param/dxl_model/dynamixel.model
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
Number Name
30 mx_28.model
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

medium

For better readability and maintainability, it would be beneficial to keep the model numbers in this file sorted numerically. For example, the newly added model 30 is placed before 220. Sorting all entries would make it easier to find models and verify the list.

220 omy_hat.model
230 omy_end.model
231 omy_end_rh_p12_rn.model
311 mx_64.model
321 mx_106.model
350 xl320.model
536 sensorxel_joy.model
537 ffw_g40_imu.model
Expand Down Expand Up @@ -48,13 +51,27 @@ Number Name
1270 xw430_t333.model
1310 xw540_h260.model
2000 ph42_020_s300.model
2010 ph54_100_s500.model
2020 ph54_200_s500.model
2100 pm42_010_s260.model
2110 pm54_040_s250.model
2120 pm54_060_s250.model
4000 ym070_210_m001.model
4010 ym070_210_b001.model
4020 ym070_210_r051.model
4030 ym070_210_r099.model
4040 ym070_210_a051.model
4050 ym070_210_a099.model
4120 ym080_230_m001.model
4130 ym080_230_b001.model
4140 ym080_230_r051.model
4150 ym080_230_r099.model
4160 ym080_230_a051.model
4170 ym080_230_a099.model
35074 rh_p12_rn.model
43289 m42_10_s260_ra.model
46097 m54_40_s250_ra.model
46353 m54_60_s250_ra.model
51201 h42_20_s300_ra.model
53769 h54_100_s500_ra.model
54025 h54_200_s500_ra.model
82 changes: 82 additions & 0 deletions param/dxl_model/h42_20_s300_ra.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
[type info]
name value
value_of_zero_radian_position 0
value_of_max_radian_position 303750
value_of_min_radian_position -303750
min_radian -3.14159265
max_radian 3.14159265

[unit info]
Data Name value unit Sign Type
Present Velocity 0.0010471976 rad/s signed
Goal Velocity 0.0010471976 rad/s signed

[control table]
Address Size Data Name
0 2 Model Number
2 4 Model Information
6 1 Firmware Version
7 1 ID
8 1 Baud Rate
9 1 Return Delay Time
10 1 Drive Mode
11 1 Operating Mode
12 1 Secondary ID
20 4 Homing Offset
24 4 Moving Threshold
31 1 Temperature Limit
32 2 Max Voltage Limit
34 2 Min Voltage Limit
36 2 PWM Limit
38 2 Current Limit
40 4 Acceleration Limit
44 4 Velocity Limit
48 4 Max Position Limit
52 4 Min Position Limit
56 1 External Port Mode 1
57 1 External Port Mode 2
58 1 External Port Mode 3
59 1 External Port Mode 4
63 1 Shutdown
512 1 Torque Enable
513 1 LED Red
514 1 LED Green
515 1 LED Blue
516 1 Status Return Level
517 1 Registered Instruction
518 1 Hardware Error Status
524 2 Velocity I Gain
526 2 Velocity P Gain
528 2 Position D Gain
530 2 Position I Gain
532 2 Position P Gain
536 2 Feedforward 2nd Gain
538 2 Feedforward 1st Gain
546 1 Bus Watchdog
548 2 Goal PWM
550 2 Goal Current
552 4 Goal Velocity
556 4 Profile Acceleration
560 4 Profile Velocity
564 4 Goal Position
568 2 Realtime Tick
570 1 Moving
571 1 Moving Status
572 2 Present PWM
574 2 Present Current
576 4 Present Velocity
580 4 Present Position
584 4 Velocity Trajectory
588 4 Position Trajectory
592 2 Present Input Voltage
594 1 Present Temperature
600 2 External Port Data 1
602 2 External Port Data 2
604 2 External Port Data 3
606 2 External Port Data 4
168 2 Indirect Address 1
634 1 Indirect Data 1
168 2 Indirect Address Write
634 1 Indirect Data Write
296 2 Indirect Address Read
698 1 Indirect Data Read
82 changes: 82 additions & 0 deletions param/dxl_model/h54_100_s500_ra.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
[type info]
name value
value_of_zero_radian_position 0
value_of_max_radian_position 501923
value_of_min_radian_position -501923
min_radian -3.14159265
max_radian 3.14159265

[unit info]
Data Name value unit Sign Type
Present Velocity 0.0010471976 rad/s signed
Goal Velocity 0.0010471976 rad/s signed

[control table]
Address Size Data Name
0 2 Model Number
2 4 Model Information
6 1 Firmware Version
7 1 ID
8 1 Baud Rate
9 1 Return Delay Time
10 1 Drive Mode
11 1 Operating Mode
12 1 Secondary ID
20 4 Homing Offset
24 4 Moving Threshold
31 1 Temperature Limit
32 2 Max Voltage Limit
34 2 Min Voltage Limit
36 2 PWM Limit
38 2 Current Limit
40 4 Acceleration Limit
44 4 Velocity Limit
48 4 Max Position Limit
52 4 Min Position Limit
56 1 External Port Mode 1
57 1 External Port Mode 2
58 1 External Port Mode 3
59 1 External Port Mode 4
63 1 Shutdown
512 1 Torque Enable
513 1 LED Red
514 1 LED Green
515 1 LED Blue
516 1 Status Return Level
517 1 Registered Instruction
518 1 Hardware Error Status
524 2 Velocity I Gain
526 2 Velocity P Gain
528 2 Position D Gain
530 2 Position I Gain
532 2 Position P Gain
536 2 Feedforward 2nd Gain
538 2 Feedforward 1st Gain
546 1 Bus Watchdog
548 2 Goal PWM
550 2 Goal Current
552 4 Goal Velocity
556 4 Profile Acceleration
560 4 Profile Velocity
564 4 Goal Position
568 2 Realtime Tick
570 1 Moving
571 1 Moving Status
572 2 Present PWM
574 2 Present Current
576 4 Present Velocity
580 4 Present Position
584 4 Velocity Trajectory
588 4 Position Trajectory
592 2 Present Input Voltage
594 1 Present Temperature
600 2 External Port Data 1
602 2 External Port Data 2
604 2 External Port Data 3
606 2 External Port Data 4
168 2 Indirect Address 1
634 1 Indirect Data 1
168 2 Indirect Address Write
634 1 Indirect Data Write
296 2 Indirect Address Read
698 1 Indirect Data Read
82 changes: 82 additions & 0 deletions param/dxl_model/h54_200_s500_ra.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
[type info]
name value
value_of_zero_radian_position 0
value_of_max_radian_position 501923
value_of_min_radian_position -501923
min_radian -3.14159265
max_radian 3.14159265

[unit info]
Data Name value unit Sign Type
Present Velocity 0.0010471976 rad/s signed
Goal Velocity 0.0010471976 rad/s signed

[control table]
Address Size Data Name
0 2 Model Number
2 4 Model Information
6 1 Firmware Version
7 1 ID
8 1 Baud Rate
9 1 Return Delay Time
10 1 Drive Mode
11 1 Operating Mode
12 1 Secondary ID
20 4 Homing Offset
24 4 Moving Threshold
31 1 Temperature Limit
32 2 Max Voltage Limit
34 2 Min Voltage Limit
36 2 PWM Limit
38 2 Current Limit
40 4 Acceleration Limit
44 4 Velocity Limit
48 4 Max Position Limit
52 4 Min Position Limit
56 1 External Port Mode 1
57 1 External Port Mode 2
58 1 External Port Mode 3
59 1 External Port Mode 4
63 1 Shutdown
512 1 Torque Enable
513 1 LED Red
514 1 LED Green
515 1 LED Blue
516 1 Status Return Level
517 1 Registered Instruction
518 1 Hardware Error Status
524 2 Velocity I Gain
526 2 Velocity P Gain
528 2 Position D Gain
530 2 Position I Gain
532 2 Position P Gain
536 2 Feedforward 2nd Gain
538 2 Feedforward 1st Gain
546 1 Bus Watchdog
548 2 Goal PWM
550 2 Goal Current
552 4 Goal Velocity
556 4 Profile Acceleration
560 4 Profile Velocity
564 4 Goal Position
568 2 Realtime Tick
570 1 Moving
571 1 Moving Status
572 2 Present PWM
574 2 Present Current
576 4 Present Velocity
580 4 Present Position
584 4 Velocity Trajectory
588 4 Position Trajectory
592 2 Present Input Voltage
594 1 Present Temperature
600 2 External Port Data 1
602 2 External Port Data 2
604 2 External Port Data 3
606 2 External Port Data 4
168 2 Indirect Address 1
634 1 Indirect Data 1
168 2 Indirect Address Write
634 1 Indirect Data Write
296 2 Indirect Address Read
698 1 Indirect Data Read
82 changes: 82 additions & 0 deletions param/dxl_model/m42_10_s260_ra.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
[type info]
name value
value_of_zero_radian_position 0
value_of_max_radian_position 263187
value_of_min_radian_position -263187
min_radian -3.14159265
max_radian 3.14159265

[unit info]
Data Name value unit Sign Type
Present Velocity 0.0010471976 rad/s signed
Goal Velocity 0.0010471976 rad/s signed

[control table]
Address Size Data Name
0 2 Model Number
2 4 Model Information
6 1 Firmware Version
7 1 ID
8 1 Baud Rate
9 1 Return Delay Time
10 1 Drive Mode
11 1 Operating Mode
12 1 Secondary ID
20 4 Homing Offset
24 4 Moving Threshold
31 1 Temperature Limit
32 2 Max Voltage Limit
34 2 Min Voltage Limit
36 2 PWM Limit
38 2 Current Limit
40 4 Acceleration Limit
44 4 Velocity Limit
48 4 Max Position Limit
52 4 Min Position Limit
56 1 External Port Mode 1
57 1 External Port Mode 2
58 1 External Port Mode 3
59 1 External Port Mode 4
63 1 Shutdown
512 1 Torque Enable
513 1 LED Red
514 1 LED Green
515 1 LED Blue
516 1 Status Return Level
517 1 Registered Instruction
518 1 Hardware Error Status
524 2 Velocity I Gain
526 2 Velocity P Gain
528 2 Position D Gain
530 2 Position I Gain
532 2 Position P Gain
536 2 Feedforward 2nd Gain
538 2 Feedforward 1st Gain
546 1 Bus Watchdog
548 2 Goal PWM
550 2 Goal Current
552 4 Goal Velocity
556 4 Profile Acceleration
560 4 Profile Velocity
564 4 Goal Position
568 2 Realtime Tick
570 1 Moving
571 1 Moving Status
572 2 Present PWM
574 2 Present Current
576 4 Present Velocity
580 4 Present Position
584 4 Velocity Trajectory
588 4 Position Trajectory
592 2 Present Input Voltage
594 1 Present Temperature
600 2 External Port Data 1
602 2 External Port Data 2
604 2 External Port Data 3
606 2 External Port Data 4
168 2 Indirect Address 1
634 1 Indirect Data 1
168 2 Indirect Address Write
634 1 Indirect Data Write
296 2 Indirect Address Read
698 1 Indirect Data Read
Loading
Loading