diff --git a/CHANGELOG.rst b/CHANGELOG.rst index 2db904f..4b50831 100644 --- a/CHANGELOG.rst +++ b/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package dynamixel_hardware_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.4.1 (2025-03-31) +------------------ +* Modified the Model File +* Contributors: Wonho Yun + 1.4.0 (2025-03-20) ------------------ * Added Torque Constant Parameter to DXL Model Files diff --git a/package.xml b/package.xml index fd090d8..0d7f149 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ dynamixel_hardware_interface - 1.4.0 + 1.4.1 ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework. diff --git a/param/dxl_model/dynamixel.model b/param/dxl_model/dynamixel.model index 3fd5e86..985850d 100644 --- a/param/dxl_model/dynamixel.model +++ b/param/dxl_model/dynamixel.model @@ -33,12 +33,14 @@ Number Name 1240 xc330_m288.model 1270 xw430_t333.model 1310 xw540_h260.model +2000 ph42_020_s300.model 4000 ym070_210_m001.model 4020 ym070_210_r051.model 4030 ym070_210_r099.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 4170 ym080_230_a099.model -35074 rh_p12_rn.model +35074 rh_p12_rn.model diff --git a/param/dxl_model/ph42_020_s300.model b/param/dxl_model/ph42_020_s300.model new file mode 100644 index 0000000..4a05469 --- /dev/null +++ b/param/dxl_model/ph42_020_s300.model @@ -0,0 +1,68 @@ +[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 + +[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 +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 +878 1 Backup Ready +168 2 Indirect Address Write +634 1 Indirect Data Write +350 2 Indirect Address Read +698 1 Indirect Data Read diff --git a/param/dxl_model/xh430_v210.model b/param/dxl_model/xh430_v210.model index da137fd..6ca9523 100644 --- a/param/dxl_model/xh430_v210.model +++ b/param/dxl_model/xh430_v210.model @@ -64,4 +64,4 @@ Address Size Data Name 168 2 Indirect Address Write 224 1 Indirect Data Write 578 2 Indirect Address Read -634 1 Indirect Data Read \ No newline at end of file +634 1 Indirect Data Read diff --git a/param/dxl_model/ym070_210_r099.model b/param/dxl_model/ym070_210_r099.model index 900af9f..a530828 100644 --- a/param/dxl_model/ym070_210_r099.model +++ b/param/dxl_model/ym070_210_r099.model @@ -1,8 +1,8 @@ [type info] name value -value_of_zero_radian_position 25952256 -value_of_max_radian_position 51904511 -value_of_min_radian_position 0 +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 diff --git a/param/dxl_model/ym080_230_b001.model b/param/dxl_model/ym080_230_b001.model new file mode 100644 index 0000000..994a64c --- /dev/null +++ b/param/dxl_model/ym080_230_b001.model @@ -0,0 +1,96 @@ +[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 + +[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 +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_r099.model b/param/dxl_model/ym080_230_r099.model index 900af9f..a530828 100644 --- a/param/dxl_model/ym080_230_r099.model +++ b/param/dxl_model/ym080_230_r099.model @@ -1,8 +1,8 @@ [type info] name value -value_of_zero_radian_position 25952256 -value_of_max_radian_position 51904511 -value_of_min_radian_position 0 +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