Skip to content
Merged
Show file tree
Hide file tree
Changes from 8 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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.4.11 (2025-07-21)
------------------
* Added support for firmware version-aware model file selection
* Contributors: Woojin Wie

1.4.10 (2025-07-18)
------------------
* Added unit system to model files
Expand Down
2 changes: 2 additions & 0 deletions include/dynamixel_hardware_interface/dynamixel/dynamixel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,6 +212,8 @@ class Dynamixel
static std::string DxlErrorToString(DxlError error_num);

DxlError ReadDxlModelFile(uint8_t id, uint16_t model_num);
DxlError ReadDxlModelFile(uint8_t id, uint16_t model_num, uint8_t firmware_version);
DxlError ReadFirmwareVersion(uint8_t id, uint8_t & firmware_version);

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

Expand Down
11 changes: 11 additions & 0 deletions include/dynamixel_hardware_interface/dynamixel/dynamixel_info.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <map>
#include <string>
#include <vector>
#include <regex>

#include <boost/algorithm/string.hpp>

Expand All @@ -46,6 +47,7 @@ typedef struct
int32_t value_of_max_radian_position;
int32_t value_of_min_radian_position;
uint16_t model_num;
uint8_t firmware_version;

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

std::string dxl_model_file_dir;

// Firmware version-aware model file selection
std::string SelectModelFileByFirmwareVersion(
const std::string & base_model_name,
uint8_t firmware_version);
uint8_t ExtractFirmwareVersionFromFilename(const std::string & filename);

public:
// Id, Control table
std::map<uint8_t, DxlInfo> dxl_info_;
Expand All @@ -71,6 +79,7 @@ class DynamixelInfo
void InitDxlModelInfo();

void ReadDxlModelFile(uint8_t id, uint16_t model_num);
void ReadDxlModelFile(uint8_t id, uint16_t model_num, uint8_t firmware_version);
bool GetDxlControlItem(uint8_t id, std::string item_name, uint16_t & addr, uint8_t & size);
bool CheckDxlControlItem(uint8_t id, std::string item_name);

Expand All @@ -89,6 +98,8 @@ class DynamixelInfo

int32_t ConvertRadianToValue(uint8_t id, double radian);
double ConvertValueToRadian(uint8_t id, int32_t value);

std::string GetModelName(uint16_t model_number) const;
};

// Template implementations
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>dynamixel_hardware_interface</name>
<version>1.4.10</version>
<version>1.4.11</version>
<description>
ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework.
</description>
Expand Down
6 changes: 3 additions & 3 deletions param/dxl_model/xc330_m181.model
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ Address Size Data Name
144 2 Present Input Voltage
146 1 Present Temperature
168 2 Indirect Address 1
208 1 Indirect Data 1
224 1 Indirect Data 1
168 2 Indirect Address Write
208 1 Indirect Data Write
224 1 Indirect Data Write
180 2 Indirect Address Read
214 1 Indirect Data Read
230 1 Indirect Data Read
73 changes: 73 additions & 0 deletions param/dxl_model/xc330_m181_fw52.model
Original file line number Diff line number Diff line change
@@ -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
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
6 changes: 3 additions & 3 deletions param/dxl_model/xc330_m288.model
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ Address Size Data Name
144 2 Present Input Voltage
146 1 Present Temperature
168 2 Indirect Address 1
208 1 Indirect Data 1
224 1 Indirect Data 1
168 2 Indirect Address Write
208 1 Indirect Data Write
224 1 Indirect Data Write
180 2 Indirect Address Read
214 1 Indirect Data Read
230 1 Indirect Data Read
73 changes: 73 additions & 0 deletions param/dxl_model/xc330_m288_fw52.model
Original file line number Diff line number Diff line change
@@ -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
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
6 changes: 3 additions & 3 deletions param/dxl_model/xc330_t181.model
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,8 @@ Address Size Data Name
144 2 Present Input Voltage
146 1 Present Temperature
168 2 Indirect Address 1
208 1 Indirect Data 1
224 1 Indirect Data 1
168 2 Indirect Address Write
208 1 Indirect Data Write
224 1 Indirect Data Write
180 2 Indirect Address Read
214 1 Indirect Data Read
230 1 Indirect Data Read
75 changes: 75 additions & 0 deletions param/dxl_model/xc330_t181_fw52.model
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
[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
Present Current 0.0006709470296015791 N/m signed
Goal Current 0.0006709470296015791 N/m 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
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
6 changes: 3 additions & 3 deletions param/dxl_model/xc330_t288.model
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,8 @@ Address Size Data Name
144 2 Present Input Voltage
146 1 Present Temperature
168 2 Indirect Address 1
208 1 Indirect Data 1
224 1 Indirect Data 1
168 2 Indirect Address Write
208 1 Indirect Data Write
224 1 Indirect Data Write
180 2 Indirect Address Read
214 1 Indirect Data Read
230 1 Indirect Data Read
Loading
Loading