From ecb4106f1fdd8ef71e6517c15e47f656e82dca0f Mon Sep 17 00:00:00 2001 From: Woojin Wie Date: Mon, 28 Jul 2025 17:54:38 +0900 Subject: [PATCH 1/6] refactor: Add new Dynamixel model files and update existing models --- param/dxl_model/dynamixel.model | 17 +++ param/dxl_model/h42_20_s300_ra.model | 78 ++++++++++++ param/dxl_model/h54_100_s500_ra.model | 78 ++++++++++++ param/dxl_model/h54_200_s500_ra.model | 78 ++++++++++++ param/dxl_model/m42_10_s260_ra.model | 78 ++++++++++++ param/dxl_model/m54_40_s250_ra.model | 78 ++++++++++++ param/dxl_model/m54_60_s250_ra.model | 78 ++++++++++++ param/dxl_model/mx_106.model | 73 +++++++++++ param/dxl_model/mx_28.model | 71 +++++++++++ param/dxl_model/mx_64.model | 73 +++++++++++ param/dxl_model/ph42_020_s300.model | 13 +- param/dxl_model/ph54_100_s500.model | 85 +++++++++++++ param/dxl_model/ph54_200_s500.model | 85 +++++++++++++ param/dxl_model/pm42_010_s260.model | 85 +++++++++++++ param/dxl_model/pm54_040_s250.model | 85 +++++++++++++ param/dxl_model/pm54_060_s250.model | 85 +++++++++++++ ...80_220_m001.model => ym070_210_a051.model} | 0 param/dxl_model/ym070_210_b001.model | 113 ++++++++++++++++++ param/dxl_model/ym080_230_a051.model | 113 ++++++++++++++++++ param/dxl_model/ym080_230_m001.model | 113 ++++++++++++++++++ 20 files changed, 1477 insertions(+), 2 deletions(-) create mode 100644 param/dxl_model/h42_20_s300_ra.model create mode 100644 param/dxl_model/h54_100_s500_ra.model create mode 100644 param/dxl_model/h54_200_s500_ra.model create mode 100644 param/dxl_model/m42_10_s260_ra.model create mode 100644 param/dxl_model/m54_40_s250_ra.model create mode 100644 param/dxl_model/m54_60_s250_ra.model create mode 100644 param/dxl_model/mx_106.model create mode 100644 param/dxl_model/mx_28.model create mode 100644 param/dxl_model/mx_64.model create mode 100644 param/dxl_model/ph54_100_s500.model create mode 100644 param/dxl_model/ph54_200_s500.model create mode 100644 param/dxl_model/pm42_010_s260.model create mode 100644 param/dxl_model/pm54_040_s250.model create mode 100644 param/dxl_model/pm54_060_s250.model rename param/dxl_model/{ym080_220_m001.model => ym070_210_a051.model} (100%) create mode 100644 param/dxl_model/ym070_210_b001.model create mode 100644 param/dxl_model/ym080_230_a051.model create mode 100644 param/dxl_model/ym080_230_m001.model diff --git a/param/dxl_model/dynamixel.model b/param/dxl_model/dynamixel.model index 23a2f67..3f0db3e 100644 --- a/param/dxl_model/dynamixel.model +++ b/param/dxl_model/dynamixel.model @@ -1,7 +1,10 @@ Number Name +30 mx_28.model 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 @@ -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 diff --git a/param/dxl_model/h42_20_s300_ra.model b/param/dxl_model/h42_20_s300_ra.model new file mode 100644 index 0000000..fb23f2b --- /dev/null +++ b/param/dxl_model/h42_20_s300_ra.model @@ -0,0 +1,78 @@ +[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 +532 2 Position P Gain +530 2 Position I 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 +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 diff --git a/param/dxl_model/h54_100_s500_ra.model b/param/dxl_model/h54_100_s500_ra.model new file mode 100644 index 0000000..4a148fd --- /dev/null +++ b/param/dxl_model/h54_100_s500_ra.model @@ -0,0 +1,78 @@ +[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 +532 2 Position P Gain +530 2 Position I 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 +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 diff --git a/param/dxl_model/h54_200_s500_ra.model b/param/dxl_model/h54_200_s500_ra.model new file mode 100644 index 0000000..4a148fd --- /dev/null +++ b/param/dxl_model/h54_200_s500_ra.model @@ -0,0 +1,78 @@ +[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 +532 2 Position P Gain +530 2 Position I 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 +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 diff --git a/param/dxl_model/m42_10_s260_ra.model b/param/dxl_model/m42_10_s260_ra.model new file mode 100644 index 0000000..e14b36e --- /dev/null +++ b/param/dxl_model/m42_10_s260_ra.model @@ -0,0 +1,78 @@ +[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 +532 2 Position P Gain +530 2 Position I 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 +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 diff --git a/param/dxl_model/m54_40_s250_ra.model b/param/dxl_model/m54_40_s250_ra.model new file mode 100644 index 0000000..4a2084a --- /dev/null +++ b/param/dxl_model/m54_40_s250_ra.model @@ -0,0 +1,78 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 251417 +value_of_min_radian_position -251417 +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 +532 2 Position P Gain +530 2 Position I 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 +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 diff --git a/param/dxl_model/m54_60_s250_ra.model b/param/dxl_model/m54_60_s250_ra.model new file mode 100644 index 0000000..4a2084a --- /dev/null +++ b/param/dxl_model/m54_60_s250_ra.model @@ -0,0 +1,78 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 251417 +value_of_min_radian_position -251417 +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 +532 2 Position P Gain +530 2 Position I 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 +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 diff --git a/param/dxl_model/mx_106.model b/param/dxl_model/mx_106.model new file mode 100644 index 0000000..deaf047 --- /dev/null +++ b/param/dxl_model/mx_106.model @@ -0,0 +1,73 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 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(Shadow) ID +13 1 Protocol Type +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 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 BUS Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/param/dxl_model/mx_28.model b/param/dxl_model/mx_28.model new file mode 100644 index 0000000..05ec3f1 --- /dev/null +++ b/param/dxl_model/mx_28.model @@ -0,0 +1,71 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 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(Shadow) ID +13 1 Protocol Type +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 +40 4 Acceleration Limit +44 4 Velocity Limit +48 4 Max Position Limit +52 4 Min Position Limit +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 BUS Watchdog +100 2 Goal PWM +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Load +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/param/dxl_model/mx_64.model b/param/dxl_model/mx_64.model new file mode 100644 index 0000000..deaf047 --- /dev/null +++ b/param/dxl_model/mx_64.model @@ -0,0 +1,73 @@ +[type info] +name value +value_of_zero_radian_position 2048 +value_of_max_radian_position 4095 +value_of_min_radian_position 0 +min_radian -3.14159265 +max_radian 3.14159265 + +[unit info] +Data Name value unit Sign Type +Present Velocity 0.0239691227 rad/s signed +Goal Velocity 0.0239691227 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(Shadow) ID +13 1 Protocol Type +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 +63 1 Shutdown +64 1 Torque Enable +65 1 LED +68 1 Status Return Level +69 1 Registered Instruction +70 1 Hardware Error Status +76 2 Velocity I Gain +78 2 Velocity P Gain +80 2 Position D Gain +82 2 Position I Gain +84 2 Position P Gain +88 2 Feedforward 2nd Gain +90 2 Feedforward 1st Gain +98 1 BUS Watchdog +100 2 Goal PWM +102 2 Goal Current +104 4 Goal Velocity +108 4 Profile Acceleration +112 4 Profile Velocity +116 4 Goal Position +120 2 Realtime Tick +122 1 Moving +123 1 Moving Status +124 2 Present PWM +126 2 Present Current +128 4 Present Velocity +132 4 Present Position +136 4 Velocity Trajectory +140 4 Position Trajectory +144 2 Present Input Voltage +146 1 Present Temperature +168 2 Indirect Address 1 +224 1 Indirect Data 1 +168 2 Indirect Address Write +224 1 Indirect Data Write +578 2 Indirect Address Read +634 1 Indirect Data Read diff --git a/param/dxl_model/ph42_020_s300.model b/param/dxl_model/ph42_020_s300.model index df851f3..28b7e7c 100644 --- a/param/dxl_model/ph42_020_s300.model +++ b/param/dxl_model/ph42_020_s300.model @@ -10,7 +10,6 @@ max_radian 3.14159265 Data Name value unit Sign Type Present Velocity 0.0010471976 rad/s signed Goal Velocity 0.0010471976 rad/s signed -Velocity Limit 0.0010471976 rad/s signed [control table] Address Size Data Name @@ -22,7 +21,7 @@ Address Size Data Name 9 1 Return Delay Time 10 1 Drive Mode 11 1 Operating Mode -12 1 Secondary(Shadow) ID +12 1 Secondary ID 13 1 Protocol Type 20 4 Homing Offset 24 4 Moving Threshold @@ -35,6 +34,12 @@ Address Size Data Name 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 +60 1 Startup Configuration +63 1 Shutdown 512 1 Torque Enable 513 1 LED Red 514 1 LED Green @@ -67,6 +72,10 @@ Address Size Data Name 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 878 1 Backup Ready 168 2 Indirect Address 1 634 1 Indirect Data 1 diff --git a/param/dxl_model/ph54_100_s500.model b/param/dxl_model/ph54_100_s500.model new file mode 100644 index 0000000..ace8e5b --- /dev/null +++ b/param/dxl_model/ph54_100_s500.model @@ -0,0 +1,85 @@ +[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 +13 1 Protocol Type +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 +60 1 Startup Configuration +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 +878 1 Backup Ready +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 diff --git a/param/dxl_model/ph54_200_s500.model b/param/dxl_model/ph54_200_s500.model new file mode 100644 index 0000000..ace8e5b --- /dev/null +++ b/param/dxl_model/ph54_200_s500.model @@ -0,0 +1,85 @@ +[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 +13 1 Protocol Type +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 +60 1 Startup Configuration +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 +878 1 Backup Ready +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 diff --git a/param/dxl_model/pm42_010_s260.model b/param/dxl_model/pm42_010_s260.model new file mode 100644 index 0000000..6ead59f --- /dev/null +++ b/param/dxl_model/pm42_010_s260.model @@ -0,0 +1,85 @@ +[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 +13 1 Protocol Type +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 +60 1 Startup Configuration +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 +878 1 Backup Ready +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 diff --git a/param/dxl_model/pm54_040_s250.model b/param/dxl_model/pm54_040_s250.model new file mode 100644 index 0000000..39c8a40 --- /dev/null +++ b/param/dxl_model/pm54_040_s250.model @@ -0,0 +1,85 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 251417 +value_of_min_radian_position -251417 +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 +13 1 Protocol Type +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 +60 1 Startup Configuration +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 +878 1 Backup Ready +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 diff --git a/param/dxl_model/pm54_060_s250.model b/param/dxl_model/pm54_060_s250.model new file mode 100644 index 0000000..39c8a40 --- /dev/null +++ b/param/dxl_model/pm54_060_s250.model @@ -0,0 +1,85 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 251417 +value_of_min_radian_position -251417 +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 +13 1 Protocol Type +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 +60 1 Startup Configuration +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 +878 1 Backup Ready +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 diff --git a/param/dxl_model/ym080_220_m001.model b/param/dxl_model/ym070_210_a051.model similarity index 100% rename from param/dxl_model/ym080_220_m001.model rename to param/dxl_model/ym070_210_a051.model diff --git a/param/dxl_model/ym070_210_b001.model b/param/dxl_model/ym070_210_b001.model new file mode 100644 index 0000000..5dfcf10 --- /dev/null +++ b/param/dxl_model/ym070_210_b001.model @@ -0,0 +1,113 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +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 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/param/dxl_model/ym080_230_a051.model b/param/dxl_model/ym080_230_a051.model new file mode 100644 index 0000000..5dfcf10 --- /dev/null +++ b/param/dxl_model/ym080_230_a051.model @@ -0,0 +1,113 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +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 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/param/dxl_model/ym080_230_m001.model b/param/dxl_model/ym080_230_m001.model new file mode 100644 index 0000000..5dfcf10 --- /dev/null +++ b/param/dxl_model/ym080_230_m001.model @@ -0,0 +1,113 @@ +[type info] +name value +value_of_zero_radian_position 0 +value_of_max_radian_position 262144 +value_of_min_radian_position -262144 +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 2 Bus Watchdog +10 1 Secondary(Shadow) ID +11 1 Protocol Type +12 1 Baud Rate (Bus) +13 1 Return Delay Time +15 1 Status Return Level +16 1 Registered Instruction +32 1 Drive Mode +33 1 Operating Mode +34 1 Startup Configuration +38 2 Position Limit Threshold +40 4 In-Position Threshold +44 4 Following Error Threshold +48 4 Moving Threshold +52 4 Homing Offset +56 1 Inverter Temperature Limit +57 1 Motor Temperature Limit +60 2 Max Voltage Limit +62 2 Min Voltage Limit +64 2 PWM Limit +66 2 Current Limit +68 4 Acceleration Limit +72 4 Velocity Limit +76 4 Max Position Limit +84 4 Min Position Limit +96 4 Electronic GearRatio Numerator +100 4 Electronic GearRatio Denominator +104 2 Safe Stop Time +106 2 Brake Delay +108 2 Goal Update Delay +110 1 Overexcitation Voltage +111 1 Normal Excitation Voltage +112 2 Overexcitation Time +132 2 Present Velocity LPF Frequency +134 2 Goal Current LPF Frequency +136 2 Position FF LPF Time +138 2 Velocity FF LPF Time +152 1 Controller State +153 1 Error Code +154 1 Error Code History 1 +155 1 Error Code History 2 +156 1 Error Code History 3 +157 1 Error Code History 4 +158 1 Error Code History 5 +159 1 Error Code History 6 +160 1 Error Code History 7 +161 1 Error Code History 8 +162 1 Error Code History 9 +163 1 Error Code History 10 +164 1 Error Code History 11 +165 1 Error Code History 12 +166 1 Error Code History 13 +167 1 Error Code History 14 +168 1 Error Code History 15 +169 1 Error Code History 16 +170 1 Hybrid Save +212 4 Velocity I Gain +216 4 Velocity P Gain +220 4 Velocity FF Gain +224 4 Position D Gain +228 4 Position I Gain +232 4 Position P Gain +236 4 Position FF Gain +240 4 Profile Acceleration +244 4 Profile Velocity +248 4 Profile Acceleration Time +252 4 Profile Time +256 2 Indirect Address 1 +512 1 Torque Enable +513 1 LED +516 2 PWM Offset +518 2 Current Offset +520 4 Velocity Offset +524 2 Goal PWM +526 2 Goal Current +528 4 Goal Velocity +532 4 Goal Position +541 1 Moving Status +542 2 Realtime Tick +544 2 Present PWM +546 2 Present Current +548 4 Present Velocity +552 4 Present Position +560 4 Position Trajectory +564 4 Velocity Trajectory +568 2 Present Input Voltage +570 1 Present Inverter Temperature +571 1 Present Motor Temperature +634 1 Indirect Data 1 +919 1 Backup Ready +256 2 Indirect Address Write +634 1 Indirect Data Write +384 2 Indirect Address Read +698 1 Indirect Data Read From bae1f9196a4d6e5aad385f736160d9e5d6ffb83b Mon Sep 17 00:00:00 2001 From: Woojin Wie Date: Mon, 28 Jul 2025 17:55:58 +0900 Subject: [PATCH 2/6] fix: Correct spacing in Dynamixel model file for better readability --- param/dxl_model/dynamixel.model | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/param/dxl_model/dynamixel.model b/param/dxl_model/dynamixel.model index 3f0db3e..9d45f88 100644 --- a/param/dxl_model/dynamixel.model +++ b/param/dxl_model/dynamixel.model @@ -3,8 +3,8 @@ Number Name 220 omy_hat.model 230 omy_end.model 231 omy_end_rh_p12_rn.model -311 mx_64.model -321 mx_106.model +311 mx_64.model +321 mx_106.model 350 xl320.model 536 sensorxel_joy.model 537 ffw_g40_imu.model From 02544670e431dfa633d3904bfc05bd33465ac540 Mon Sep 17 00:00:00 2001 From: Woojin Wie Date: Mon, 4 Aug 2025 12:05:11 +0900 Subject: [PATCH 3/6] refactor: Update Dynamixel model files to include external port data entries --- param/dxl_model/h42_20_s300_ra.model | 6 +++++- param/dxl_model/h54_100_s500_ra.model | 6 +++++- param/dxl_model/h54_200_s500_ra.model | 6 +++++- param/dxl_model/m42_10_s260_ra.model | 6 +++++- param/dxl_model/m54_40_s250_ra.model | 6 +++++- param/dxl_model/m54_60_s250_ra.model | 6 +++++- 6 files changed, 30 insertions(+), 6 deletions(-) diff --git a/param/dxl_model/h42_20_s300_ra.model b/param/dxl_model/h42_20_s300_ra.model index fb23f2b..ce0d719 100644 --- a/param/dxl_model/h42_20_s300_ra.model +++ b/param/dxl_model/h42_20_s300_ra.model @@ -48,8 +48,8 @@ Address Size Data Name 524 2 Velocity I Gain 526 2 Velocity P Gain 528 2 Position D Gain -532 2 Position P 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 @@ -70,6 +70,10 @@ Address Size Data Name 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 diff --git a/param/dxl_model/h54_100_s500_ra.model b/param/dxl_model/h54_100_s500_ra.model index 4a148fd..cd4642d 100644 --- a/param/dxl_model/h54_100_s500_ra.model +++ b/param/dxl_model/h54_100_s500_ra.model @@ -48,8 +48,8 @@ Address Size Data Name 524 2 Velocity I Gain 526 2 Velocity P Gain 528 2 Position D Gain -532 2 Position P 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 @@ -70,6 +70,10 @@ Address Size Data Name 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 diff --git a/param/dxl_model/h54_200_s500_ra.model b/param/dxl_model/h54_200_s500_ra.model index 4a148fd..cd4642d 100644 --- a/param/dxl_model/h54_200_s500_ra.model +++ b/param/dxl_model/h54_200_s500_ra.model @@ -48,8 +48,8 @@ Address Size Data Name 524 2 Velocity I Gain 526 2 Velocity P Gain 528 2 Position D Gain -532 2 Position P 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 @@ -70,6 +70,10 @@ Address Size Data Name 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 diff --git a/param/dxl_model/m42_10_s260_ra.model b/param/dxl_model/m42_10_s260_ra.model index e14b36e..60e757e 100644 --- a/param/dxl_model/m42_10_s260_ra.model +++ b/param/dxl_model/m42_10_s260_ra.model @@ -48,8 +48,8 @@ Address Size Data Name 524 2 Velocity I Gain 526 2 Velocity P Gain 528 2 Position D Gain -532 2 Position P 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 @@ -70,6 +70,10 @@ Address Size Data Name 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 diff --git a/param/dxl_model/m54_40_s250_ra.model b/param/dxl_model/m54_40_s250_ra.model index 4a2084a..5466dc1 100644 --- a/param/dxl_model/m54_40_s250_ra.model +++ b/param/dxl_model/m54_40_s250_ra.model @@ -48,8 +48,8 @@ Address Size Data Name 524 2 Velocity I Gain 526 2 Velocity P Gain 528 2 Position D Gain -532 2 Position P 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 @@ -70,6 +70,10 @@ Address Size Data Name 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 diff --git a/param/dxl_model/m54_60_s250_ra.model b/param/dxl_model/m54_60_s250_ra.model index 4a2084a..5466dc1 100644 --- a/param/dxl_model/m54_60_s250_ra.model +++ b/param/dxl_model/m54_60_s250_ra.model @@ -48,8 +48,8 @@ Address Size Data Name 524 2 Velocity I Gain 526 2 Velocity P Gain 528 2 Position D Gain -532 2 Position P 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 @@ -70,6 +70,10 @@ Address Size Data Name 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 From 5f4c1fbec3a68c121613b001622535f337ead829 Mon Sep 17 00:00:00 2001 From: Woojin Wie Date: Mon, 11 Aug 2025 15:58:17 +0900 Subject: [PATCH 4/6] chore: Bump version to 1.4.12 and update CHANGELOG with support for all Dynamixel models using protocol 2.0 --- CHANGELOG.rst | 5 +++++ package.xml | 2 +- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 371c7a7..5ac2db6 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -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 diff --git a/package.xml b/package.xml index 383b20c..36de9f2 100644 --- a/package.xml +++ b/package.xml @@ -2,7 +2,7 @@ dynamixel_hardware_interface - 1.4.11 + 1.4.12 ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework. From be81d36f8bacc792111b8fb9ad90f6778e11e571 Mon Sep 17 00:00:00 2001 From: Woojin Wie Date: Mon, 11 Aug 2025 15:59:09 +0900 Subject: [PATCH 5/6] feat: Add script to cluster Dynamixel model files by control table sections --- scripts/cluster_model_files.py | 67 ++++++++++++++++++++++++++++++++++ 1 file changed, 67 insertions(+) create mode 100644 scripts/cluster_model_files.py diff --git a/scripts/cluster_model_files.py b/scripts/cluster_model_files.py new file mode 100644 index 0000000..d00ee68 --- /dev/null +++ b/scripts/cluster_model_files.py @@ -0,0 +1,67 @@ +#!/usr/bin/env python3 +# +# Copyright 2025 ROBOTIS CO., LTD. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# Author: Woojin Wie + +import os +import hashlib +from collections import defaultdict + +MODEL_DIR = os.path.join(os.path.dirname(__file__), '..', 'param', 'dxl_model') + +# Get all files in the model directory +files = [f for f in os.listdir(MODEL_DIR) if os.path.isfile(os.path.join(MODEL_DIR, f))] + +# Dictionary to map file content hash to list of files +hash_to_files = defaultdict(list) + +def extract_control_table(filepath): + with open(filepath, 'r', encoding='utf-8') as f: + lines = f.readlines() + in_control_table = False + control_table_lines = [] + for line in lines: + if line.strip() == '[control table]': + in_control_table = True + continue + if in_control_table: + if line.startswith('[') and not line.strip().startswith('[control table]'): + break + if line.strip() == '': + continue + control_table_lines.append(line.strip()) + return '\n'.join(control_table_lines) + +def control_table_hash(control_table_str): + return hashlib.sha256(control_table_str.encode('utf-8')).hexdigest() + +for filename in files: + path = os.path.join(MODEL_DIR, filename) + control_table = extract_control_table(path) + h = control_table_hash(control_table) + hash_to_files[h].append(filename) + +# Print clusters of files with identical [control table] sections +print('Clusters of files with identical [control table] sections:') +for file_list in hash_to_files.values(): + if len(file_list) > 1: + print(', '.join(file_list)) + +# Print files with unique [control table] sections +print('\nFiles with unique [control table] sections:') +for file_list in hash_to_files.values(): + if len(file_list) == 1: + print(file_list[0]) From 77341ea53f3e4eb9a64a2928c14945954ca8375e Mon Sep 17 00:00:00 2001 From: Woojin Wie Date: Mon, 11 Aug 2025 16:02:36 +0900 Subject: [PATCH 6/6] refactor: fix lint errors --- scripts/cluster_model_files.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/scripts/cluster_model_files.py b/scripts/cluster_model_files.py index d00ee68..357ed5a 100644 --- a/scripts/cluster_model_files.py +++ b/scripts/cluster_model_files.py @@ -16,9 +16,9 @@ # # Author: Woojin Wie -import os -import hashlib from collections import defaultdict +import hashlib +import os MODEL_DIR = os.path.join(os.path.dirname(__file__), '..', 'param', 'dxl_model') @@ -28,6 +28,7 @@ # Dictionary to map file content hash to list of files hash_to_files = defaultdict(list) + def extract_control_table(filepath): with open(filepath, 'r', encoding='utf-8') as f: lines = f.readlines() @@ -45,9 +46,11 @@ def extract_control_table(filepath): control_table_lines.append(line.strip()) return '\n'.join(control_table_lines) + def control_table_hash(control_table_str): return hashlib.sha256(control_table_str.encode('utf-8')).hexdigest() + for filename in files: path = os.path.join(MODEL_DIR, filename) control_table = extract_control_table(path)