Skip to content

Commit

Permalink
Merge pull request #3 from ROBOTIS-GIT/feature-dxl-x-support
Browse files Browse the repository at this point in the history
Support for All Dynamixel X-Series Actuators Including XC330 Series
  • Loading branch information
sunghowoo authored Dec 27, 2024
2 parents de43d91 + 8348e8c commit 945fc5c
Show file tree
Hide file tree
Showing 44 changed files with 1,916 additions and 57 deletions.
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.1.0 (2024-12-27)
------------------
* Added new control table entries for Dynamixel X
* Contributors: Woojin Wie, Hye-Jong Kim

1.0.0 (2024-12-04)
------------------
* First release of dynamixel_hardware_interface package
Expand Down
8 changes: 4 additions & 4 deletions param/dxl_model/2xc430_w250.model
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ Address Size Data Name
146 1 Present Temperature
168 2 Indirect Address 1
224 1 Indirect Data 1
168 2 Indirect Address Read
224 1 Indirect Data Read
578 2 Indirect Address Write
634 1 Indirect Data Write
168 2 Indirect Address Write
224 1 Indirect Data Write
578 2 Indirect Address Read
634 1 Indirect Data Read
65 changes: 65 additions & 0 deletions param/dxl_model/2xl430_w250.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
[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

[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
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
28 changes: 28 additions & 0 deletions param/dxl_model/dynamixel.model
Original file line number Diff line number Diff line change
@@ -1,10 +1,38 @@
Number Name
350 xl320.model
1000 xh430_w350.model
1001 xd430_t350.model
1010 xh430_w210.model
1011 xd430_t210.model
1020 xm430_w350.model
1030 xm430_w210.model
1040 xh430_v350.model
1050 xh430_v210.model
1060 xl430_w250.model
1070 xc430_w150.model
1070 xc430_w150.model
1080 xc430_w240.model
1080 xc430_w240.model
1090 2xl430_w250.model
1100 xh540_w270.model
1101 xd540_t270.model
1110 xh540_w150.model
1111 xd540_t150.model
1120 xm540_w270.model
1130 xm540_w150.model
1140 xh540_v270.model
1150 xh540_v150.model
1160 2xc430_w250.model
1170 xw540_t260.model
1180 xw540_t140.model
1190 xl330_m077.model
1200 xl330_m288.model
1210 xc330_t181.model
1220 xc330_t288.model
1230 xc330_m181.model
1240 xc330_m288.model
1270 xw430_t333.model
1310 xw540_h260.model
4000 ym070_210_m001.model
4020 ym070_210_r051.model
4030 ym070_210_r099.model
Expand Down
8 changes: 4 additions & 4 deletions param/dxl_model/rh_p12_rn.model
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ Address Size Data Name
592 2 Present Input Voltage
594 1 Present Temperature
634 1 Indirect Data 1
168 2 Indirect Address Read
634 1 Indirect Data Read
296 2 Indirect Address Write
698 1 Indirect Data Write
168 2 Indirect Address Write
634 1 Indirect Data Write
296 2 Indirect Address Read
698 1 Indirect Data Read
68 changes: 68 additions & 0 deletions param/dxl_model/xc330_m181.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
[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

[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
44 4 Velocity Limit
48 4 Max Position Limit
52 4 Min Position Limit
62 1 PWM Slope
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
208 1 Indirect Data 1
168 2 Indirect Address Write
208 1 Indirect Data Write
180 2 Indirect Address Read
214 1 Indirect Data Read
68 changes: 68 additions & 0 deletions param/dxl_model/xc330_m288.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
[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

[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
44 4 Velocity Limit
48 4 Max Position Limit
52 4 Min Position Limit
62 1 PWM Slope
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
208 1 Indirect Data 1
168 2 Indirect Address Write
208 1 Indirect Data Write
180 2 Indirect Address Read
214 1 Indirect Data Read
68 changes: 68 additions & 0 deletions param/dxl_model/xc330_t181.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
[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

[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
44 4 Velocity Limit
48 4 Max Position Limit
52 4 Min Position Limit
62 1 PWM Slope
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
208 1 Indirect Data 1
168 2 Indirect Address Write
208 1 Indirect Data Write
180 2 Indirect Address Read
214 1 Indirect Data Read
Loading

0 comments on commit 945fc5c

Please sign in to comment.