Skip to content

Commit 7cc59f3

Browse files
authored
Merge pull request #69 from ROBOTIS-GIT/feature-firmware-based-model
Enhance Dynamixel model file handling with firmware version support
2 parents cc338de + 7811016 commit 7cc59f3

28 files changed

+911
-29
lines changed

CHANGELOG.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,11 @@
22
Changelog for package dynamixel_hardware_interface
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
1.4.11 (2025-07-21)
6+
------------------
7+
* Added support for firmware version-aware model file selection
8+
* Contributors: Woojin Wie
9+
510
1.4.10 (2025-07-18)
611
------------------
712
* Added unit system to model files

include/dynamixel_hardware_interface/dynamixel/dynamixel.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -212,6 +212,8 @@ class Dynamixel
212212
static std::string DxlErrorToString(DxlError error_num);
213213

214214
DxlError ReadDxlModelFile(uint8_t id, uint16_t model_num);
215+
DxlError ReadDxlModelFile(uint8_t id, uint16_t model_num, uint8_t firmware_version);
216+
DxlError ReadFirmwareVersion(uint8_t id, uint8_t & firmware_version);
215217

216218
void SetCommId(uint8_t id, uint8_t comm_id) {comm_id_[id] = comm_id;}
217219

include/dynamixel_hardware_interface/dynamixel/dynamixel_info.hpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <map>
2626
#include <string>
2727
#include <vector>
28+
#include <regex>
2829

2930
#include <boost/algorithm/string.hpp>
3031

@@ -46,6 +47,7 @@ typedef struct
4647
int32_t value_of_max_radian_position;
4748
int32_t value_of_min_radian_position;
4849
uint16_t model_num;
50+
uint8_t firmware_version;
4951

5052
std::vector<ControlItem> item;
5153
std::map<std::string, double> unit_map;
@@ -60,6 +62,12 @@ class DynamixelInfo
6062

6163
std::string dxl_model_file_dir;
6264

65+
// Firmware version-aware model file selection
66+
std::string SelectModelFileByFirmwareVersion(
67+
const std::string & base_model_name,
68+
uint8_t firmware_version);
69+
uint8_t ExtractFirmwareVersionFromFilename(const std::string & filename);
70+
6371
public:
6472
// Id, Control table
6573
std::map<uint8_t, DxlInfo> dxl_info_;
@@ -71,6 +79,7 @@ class DynamixelInfo
7179
void InitDxlModelInfo();
7280

7381
void ReadDxlModelFile(uint8_t id, uint16_t model_num);
82+
void ReadDxlModelFile(uint8_t id, uint16_t model_num, uint8_t firmware_version);
7483
bool GetDxlControlItem(uint8_t id, std::string item_name, uint16_t & addr, uint8_t & size);
7584
bool CheckDxlControlItem(uint8_t id, std::string item_name);
7685

@@ -89,6 +98,8 @@ class DynamixelInfo
8998

9099
int32_t ConvertRadianToValue(uint8_t id, double radian);
91100
double ConvertValueToRadian(uint8_t id, int32_t value);
101+
102+
std::string GetModelName(uint16_t model_number) const;
92103
};
93104

94105
// Template implementations

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>dynamixel_hardware_interface</name>
5-
<version>1.4.10</version>
5+
<version>1.4.11</version>
66
<description>
77
ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework.
88
</description>

param/dxl_model/xc330_m181.model

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,8 @@ Address Size Data Name
6666
144 2 Present Input Voltage
6767
146 1 Present Temperature
6868
168 2 Indirect Address 1
69-
208 1 Indirect Data 1
69+
224 1 Indirect Data 1
7070
168 2 Indirect Address Write
71-
208 1 Indirect Data Write
71+
224 1 Indirect Data Write
7272
180 2 Indirect Address Read
73-
214 1 Indirect Data Read
73+
230 1 Indirect Data Read
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
[type info]
2+
name value
3+
value_of_zero_radian_position 2048
4+
value_of_max_radian_position 4095
5+
value_of_min_radian_position 0
6+
min_radian -3.14159265
7+
max_radian 3.14159265
8+
9+
[unit info]
10+
Data Name value unit Sign Type
11+
Present Velocity 0.0239691227 rad/s signed
12+
Goal Velocity 0.0239691227 rad/s signed
13+
14+
[control table]
15+
Address Size Data Name
16+
0 2 Model Number
17+
2 4 Model Information
18+
6 1 Firmware Version
19+
7 1 ID
20+
8 1 Baud Rate
21+
9 1 Return Delay Time
22+
10 1 Drive Mode
23+
11 1 Operating Mode
24+
12 1 Secondary(Shadow) ID
25+
13 1 Protocol Type
26+
20 4 Homing Offset
27+
24 4 Moving Threshold
28+
31 1 Temperature Limit
29+
32 2 Max Voltage Limit
30+
34 2 Min Voltage Limit
31+
36 2 PWM Limit
32+
38 2 Current Limit
33+
44 4 Velocity Limit
34+
48 4 Max Position Limit
35+
52 4 Min Position Limit
36+
62 1 PWM Slope
37+
63 1 Shutdown
38+
64 1 Torque Enable
39+
65 1 LED
40+
68 1 Status Return Level
41+
69 1 Registered Instruction
42+
70 1 Hardware Error Status
43+
76 2 Velocity I Gain
44+
78 2 Velocity P Gain
45+
80 2 Position D Gain
46+
82 2 Position I Gain
47+
84 2 Position P Gain
48+
88 2 Feedforward 2nd Gain
49+
90 2 Feedforward 1st Gain
50+
98 1 Bus Watchdog
51+
100 2 Goal PWM
52+
102 2 Goal Current
53+
104 4 Goal Velocity
54+
108 4 Profile Acceleration
55+
112 4 Profile Velocity
56+
116 4 Goal Position
57+
120 2 Realtime Tick
58+
122 1 Moving
59+
123 1 Moving Status
60+
124 2 Present PWM
61+
126 2 Present Current
62+
128 4 Present Velocity
63+
132 4 Present Position
64+
136 4 Velocity Trajectory
65+
140 4 Position Trajectory
66+
144 2 Present Input Voltage
67+
146 1 Present Temperature
68+
168 2 Indirect Address 1
69+
208 1 Indirect Data 1
70+
168 2 Indirect Address Write
71+
208 1 Indirect Data Write
72+
180 2 Indirect Address Read
73+
214 1 Indirect Data Read

param/dxl_model/xc330_m288.model

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -66,8 +66,8 @@ Address Size Data Name
6666
144 2 Present Input Voltage
6767
146 1 Present Temperature
6868
168 2 Indirect Address 1
69-
208 1 Indirect Data 1
69+
224 1 Indirect Data 1
7070
168 2 Indirect Address Write
71-
208 1 Indirect Data Write
71+
224 1 Indirect Data Write
7272
180 2 Indirect Address Read
73-
214 1 Indirect Data Read
73+
230 1 Indirect Data Read
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
[type info]
2+
name value
3+
value_of_zero_radian_position 2048
4+
value_of_max_radian_position 4095
5+
value_of_min_radian_position 0
6+
min_radian -3.14159265
7+
max_radian 3.14159265
8+
9+
[unit info]
10+
Data Name value unit Sign Type
11+
Present Velocity 0.0239691227 rad/s signed
12+
Goal Velocity 0.0239691227 rad/s signed
13+
14+
[control table]
15+
Address Size Data Name
16+
0 2 Model Number
17+
2 4 Model Information
18+
6 1 Firmware Version
19+
7 1 ID
20+
8 1 Baud Rate
21+
9 1 Return Delay Time
22+
10 1 Drive Mode
23+
11 1 Operating Mode
24+
12 1 Secondary(Shadow) ID
25+
13 1 Protocol Type
26+
20 4 Homing Offset
27+
24 4 Moving Threshold
28+
31 1 Temperature Limit
29+
32 2 Max Voltage Limit
30+
34 2 Min Voltage Limit
31+
36 2 PWM Limit
32+
38 2 Current Limit
33+
44 4 Velocity Limit
34+
48 4 Max Position Limit
35+
52 4 Min Position Limit
36+
62 1 PWM Slope
37+
63 1 Shutdown
38+
64 1 Torque Enable
39+
65 1 LED
40+
68 1 Status Return Level
41+
69 1 Registered Instruction
42+
70 1 Hardware Error Status
43+
76 2 Velocity I Gain
44+
78 2 Velocity P Gain
45+
80 2 Position D Gain
46+
82 2 Position I Gain
47+
84 2 Position P Gain
48+
88 2 Feedforward 2nd Gain
49+
90 2 Feedforward 1st Gain
50+
98 1 Bus Watchdog
51+
100 2 Goal PWM
52+
102 2 Goal Current
53+
104 4 Goal Velocity
54+
108 4 Profile Acceleration
55+
112 4 Profile Velocity
56+
116 4 Goal Position
57+
120 2 Realtime Tick
58+
122 1 Moving
59+
123 1 Moving Status
60+
124 2 Present PWM
61+
126 2 Present Current
62+
128 4 Present Velocity
63+
132 4 Present Position
64+
136 4 Velocity Trajectory
65+
140 4 Position Trajectory
66+
144 2 Present Input Voltage
67+
146 1 Present Temperature
68+
168 2 Indirect Address 1
69+
208 1 Indirect Data 1
70+
168 2 Indirect Address Write
71+
208 1 Indirect Data Write
72+
180 2 Indirect Address Read
73+
214 1 Indirect Data Read

param/dxl_model/xc330_t181.model

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -68,8 +68,8 @@ Address Size Data Name
6868
144 2 Present Input Voltage
6969
146 1 Present Temperature
7070
168 2 Indirect Address 1
71-
208 1 Indirect Data 1
71+
224 1 Indirect Data 1
7272
168 2 Indirect Address Write
73-
208 1 Indirect Data Write
73+
224 1 Indirect Data Write
7474
180 2 Indirect Address Read
75-
214 1 Indirect Data Read
75+
230 1 Indirect Data Read
Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,75 @@
1+
[type info]
2+
name value
3+
value_of_zero_radian_position 2048
4+
value_of_max_radian_position 4095
5+
value_of_min_radian_position 0
6+
min_radian -3.14159265
7+
max_radian 3.14159265
8+
9+
[unit info]
10+
Data Name value unit Sign Type
11+
Present Velocity 0.0239691227 rad/s signed
12+
Goal Velocity 0.0239691227 rad/s signed
13+
Present Current 0.0006709470296015791 N/m signed
14+
Goal Current 0.0006709470296015791 N/m signed
15+
16+
[control table]
17+
Address Size Data Name
18+
0 2 Model Number
19+
2 4 Model Information
20+
6 1 Firmware Version
21+
7 1 ID
22+
8 1 Baud Rate
23+
9 1 Return Delay Time
24+
10 1 Drive Mode
25+
11 1 Operating Mode
26+
12 1 Secondary(Shadow) ID
27+
13 1 Protocol Type
28+
20 4 Homing Offset
29+
24 4 Moving Threshold
30+
31 1 Temperature Limit
31+
32 2 Max Voltage Limit
32+
34 2 Min Voltage Limit
33+
36 2 PWM Limit
34+
38 2 Current Limit
35+
44 4 Velocity Limit
36+
48 4 Max Position Limit
37+
52 4 Min Position Limit
38+
62 1 PWM Slope
39+
63 1 Shutdown
40+
64 1 Torque Enable
41+
65 1 LED
42+
68 1 Status Return Level
43+
69 1 Registered Instruction
44+
70 1 Hardware Error Status
45+
76 2 Velocity I Gain
46+
78 2 Velocity P Gain
47+
80 2 Position D Gain
48+
82 2 Position I Gain
49+
84 2 Position P Gain
50+
88 2 Feedforward 2nd Gain
51+
90 2 Feedforward 1st Gain
52+
98 1 Bus Watchdog
53+
100 2 Goal PWM
54+
102 2 Goal Current
55+
104 4 Goal Velocity
56+
108 4 Profile Acceleration
57+
112 4 Profile Velocity
58+
116 4 Goal Position
59+
120 2 Realtime Tick
60+
122 1 Moving
61+
123 1 Moving Status
62+
124 2 Present PWM
63+
126 2 Present Current
64+
128 4 Present Velocity
65+
132 4 Present Position
66+
136 4 Velocity Trajectory
67+
140 4 Position Trajectory
68+
144 2 Present Input Voltage
69+
146 1 Present Temperature
70+
168 2 Indirect Address 1
71+
208 1 Indirect Data 1
72+
168 2 Indirect Address Write
73+
208 1 Indirect Data Write
74+
180 2 Indirect Address Read
75+
214 1 Indirect Data Read

0 commit comments

Comments
 (0)