Skip to content

Commit ff75941

Browse files
authored
Merge pull request #25 from ROBOTIS-GIT/feature-add-p-model
Modified the model file
2 parents ae9927c + 41887f4 commit ff75941

8 files changed

+180
-9
lines changed

CHANGELOG.rst

+5
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,11 @@
22
Changelog for package dynamixel_hardware_interface
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
1.4.1 (2025-03-31)
6+
------------------
7+
* Modified the Model File
8+
* Contributors: Wonho Yun
9+
510
1.4.0 (2025-03-20)
611
------------------
712
* Added Torque Constant Parameter to DXL Model Files

package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version='1.0' encoding='UTF-8'?>
22
<package format="3">
33
<name>dynamixel_hardware_interface</name>
4-
<version>1.4.0</version>
4+
<version>1.4.1</version>
55
<description>
66
ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework.
77
</description>

param/dxl_model/dynamixel.model

+3-1
Original file line numberDiff line numberDiff line change
@@ -33,12 +33,14 @@ Number Name
3333
1240 xc330_m288.model
3434
1270 xw430_t333.model
3535
1310 xw540_h260.model
36+
2000 ph42_020_s300.model
3637
4000 ym070_210_m001.model
3738
4020 ym070_210_r051.model
3839
4030 ym070_210_r099.model
3940
4050 ym070_210_a099.model
4041
4120 ym080_230_m001.model
42+
4130 ym080_230_b001.model
4143
4140 ym080_230_r051.model
4244
4150 ym080_230_r099.model
4345
4170 ym080_230_a099.model
44-
35074 rh_p12_rn.model
46+
35074 rh_p12_rn.model

param/dxl_model/ph42_020_s300.model

+68
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,68 @@
1+
[type info]
2+
name value
3+
value_of_zero_radian_position 0
4+
value_of_max_radian_position 303750
5+
value_of_min_radian_position -303750
6+
min_radian -3.14159265
7+
max_radian 3.14159265
8+
9+
[control table]
10+
Address Size Data Name
11+
0 2 Model Number
12+
2 4 Model Information
13+
6 1 Firmware Version
14+
7 1 ID
15+
8 1 Baud Rate
16+
9 1 Return Delay Time
17+
10 1 Drive Mode
18+
11 1 Operating Mode
19+
12 1 Secondary(Shadow) ID
20+
13 1 Protocol Type
21+
20 4 Homing Offset
22+
24 4 Moving Threshold
23+
31 1 Temperature Limit
24+
32 2 Max Voltage Limit
25+
34 2 Min Voltage Limit
26+
36 2 PWM Limit
27+
38 2 Current Limit
28+
40 4 Acceleration Limit
29+
44 4 Velocity Limit
30+
48 4 Max Position Limit
31+
52 4 Min Position Limit
32+
512 1 Torque Enable
33+
513 1 LED Red
34+
514 1 LED Green
35+
515 1 LED Blue
36+
516 1 Status Return Level
37+
517 1 Registered Instruction
38+
518 1 Hardware Error Status
39+
524 2 Velocity I Gain
40+
526 2 Velocity P Gain
41+
528 2 Position D Gain
42+
530 2 Position I Gain
43+
532 2 Position P Gain
44+
536 2 Feedforward 2nd Gain
45+
538 2 Feedforward 1st Gain
46+
546 1 Bus Watchdog
47+
548 2 Goal PWM
48+
550 2 Goal Current
49+
552 4 Goal Velocity
50+
556 4 Profile Acceleration
51+
560 4 Profile Velocity
52+
564 4 Goal Position
53+
568 2 Realtime Tick
54+
570 1 Moving
55+
571 1 Moving Status
56+
572 2 Present PWM
57+
574 2 Present Current
58+
576 4 Present Velocity
59+
580 4 Present Position
60+
584 4 Velocity Trajectory
61+
588 4 Position Trajectory
62+
592 2 Present Input Voltage
63+
594 1 Present Temperature
64+
878 1 Backup Ready
65+
168 2 Indirect Address Write
66+
634 1 Indirect Data Write
67+
350 2 Indirect Address Read
68+
698 1 Indirect Data Read

param/dxl_model/xh430_v210.model

+1-1
Original file line numberDiff line numberDiff line change
@@ -64,4 +64,4 @@ Address Size Data Name
6464
168 2 Indirect Address Write
6565
224 1 Indirect Data Write
6666
578 2 Indirect Address Read
67-
634 1 Indirect Data Read
67+
634 1 Indirect Data Read

param/dxl_model/ym070_210_r099.model

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
[type info]
22
name value
3-
value_of_zero_radian_position 25952256
4-
value_of_max_radian_position 51904511
5-
value_of_min_radian_position 0
3+
value_of_zero_radian_position 0
4+
value_of_max_radian_position 262144
5+
value_of_min_radian_position -262144
66
min_radian -3.14159265
77
max_radian 3.14159265
88

param/dxl_model/ym080_230_b001.model

+96
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,96 @@
1+
[type info]
2+
name value
3+
value_of_zero_radian_position 0
4+
value_of_max_radian_position 262144
5+
value_of_min_radian_position -262144
6+
min_radian -3.14159265
7+
max_radian 3.14159265
8+
9+
[control table]
10+
Address Size Data Name
11+
0 2 Model Number
12+
2 4 Model Information
13+
6 1 Firmware Version
14+
7 1 ID
15+
8 2 Bus Watchdog
16+
10 1 Secondary(Shadow) ID
17+
11 1 Protocol Type
18+
12 1 Baud Rate (Bus)
19+
13 1 Return Delay Time
20+
15 1 Status Return Level
21+
16 1 Registered Instruction
22+
32 1 Drive Mode
23+
33 1 Operating Mode
24+
34 1 Startup Configuration
25+
38 2 Position Limit Threshold
26+
40 4 In-Position Threshold
27+
44 4 Following Error Threshold
28+
48 4 Moving Threshold
29+
52 4 Homing Offset
30+
56 1 Inverter Temperature Limit
31+
57 1 Motor Temperature Limit
32+
60 2 Max Voltage Limit
33+
62 2 Min Voltage Limit
34+
64 2 PWM Limit
35+
66 2 Current Limit
36+
68 4 Acceleration Limit
37+
72 4 Velocity Limit
38+
76 4 Max Position Limit
39+
84 4 Min Position Limit
40+
96 4 Electronic GearRatio Numerator
41+
100 4 Electronic GearRatio Denominator
42+
104 2 Safe Stop Time
43+
106 2 Brake Delay
44+
108 2 Goal Update Delay
45+
110 1 Overexcitation Voltage
46+
111 1 Normal Excitation Voltage
47+
112 2 Overexcitation Time
48+
132 2 Present Velocity LPF Frequency
49+
134 2 Goal Current LPF Frequency
50+
136 2 Position FF LPF Time
51+
138 2 Velocity FF LPF Time
52+
152 1 Controller State
53+
153 1 Error Code
54+
154 1 Error Code History 1
55+
155 1 Error Code History 2
56+
168 1 Error Code History 15
57+
169 1 Error Code History 16
58+
170 1 Hybrid Save
59+
212 4 Velocity I Gain
60+
216 4 Velocity P Gain
61+
220 4 Velocity FF Gain
62+
224 4 Position D Gain
63+
228 4 Position I Gain
64+
232 4 Position P Gain
65+
236 4 Position FF Gain
66+
240 4 Profile Acceleration
67+
244 4 Profile Velocity
68+
248 4 Profile Acceleration Time
69+
252 4 Profile Time
70+
256 2 Indirect Address 1
71+
512 1 Torque Enable
72+
513 1 LED
73+
516 2 PWM Offset
74+
518 2 Current Offset
75+
520 4 Velocity Offset
76+
524 2 Goal PWM
77+
526 2 Goal Current
78+
528 4 Goal Velocity
79+
532 4 Goal Position
80+
541 1 Moving Status
81+
542 2 Realtime Tick
82+
544 2 Present PWM
83+
546 2 Present Current
84+
548 4 Present Velocity
85+
552 4 Present Position
86+
560 4 Position Trajectory
87+
564 4 Velocity Trajectory
88+
568 2 Present Input Voltage
89+
570 1 Present Inverter Temperature
90+
571 1 Present Motor Temperature
91+
634 1 Indirect Data 1
92+
919 1 Backup Ready
93+
256 2 Indirect Address Write
94+
634 1 Indirect Data Write
95+
384 2 Indirect Address Read
96+
698 1 Indirect Data Read

param/dxl_model/ym080_230_r099.model

+3-3
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
[type info]
22
name value
3-
value_of_zero_radian_position 25952256
4-
value_of_max_radian_position 51904511
5-
value_of_min_radian_position 0
3+
value_of_zero_radian_position 0
4+
value_of_max_radian_position 262144
5+
value_of_min_radian_position -262144
66
min_radian -3.14159265
77
max_radian 3.14159265
88

0 commit comments

Comments
 (0)