Skip to content
Merged
Show file tree
Hide file tree
Changes from all 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
8 changes: 8 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,14 @@
Changelog for package dynamixel_hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.4.0 (2025-03-20)
------------------
* Added Torque Constant Parameter to DXL Model Files
* Enhanced Transmission Command Calculation
* Unified Initialization Structure
* Support for Goal Current Control
* Contributors: Woojin Wie

1.3.0 (2025-02-17)
------------------
* Enhance Error Handling and Timeout Management
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,8 @@ class DynamixelInfo
int32_t & value_of_max_radian_position,
int32_t & value_of_min_radian_position,
double & min_radian,
double & max_radian);
double & max_radian,
double & torque_constant);
int32_t ConvertRadianToValue(uint8_t id, double radian);
double ConvertValueToRadian(uint8_t id, int32_t value);
inline int16_t ConvertEffortToCurrent(uint8_t id, double effort)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,10 @@
#define PRESENT_VELOCITY_INDEX 1
#define PRESENT_EFFORT_INDEX 2

#define GOAL_POSITION_INDEX 0
// #define GOAL_VELOCITY_INDEX 1 // TODO: to be implemented
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

medium

This line is commented out with a TODO. Is the goal velocity control to be implemented in this release? If not, consider removing this line to avoid confusion. If it is to be implemented, please do so before merging.

#define GOAL_CURRENT_INDEX 1

namespace dynamixel_hardware_interface
{

Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version='1.0' encoding='UTF-8'?>
<package format="3">
<name>dynamixel_hardware_interface</name>
<version>1.3.0</version>
<version>1.4.0</version>
<description>
ROS 2 package providing a hardware interface for controlling Dynamixel motors via the ROS 2 control framework.
</description>
Expand Down
1 change: 1 addition & 0 deletions param/dxl_model/xc330_t181.model
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ value_of_max_radian_position 4095
value_of_min_radian_position 0
min_radian -3.14159265
max_radian 3.14159265
torque_constant 0.0006709470296015791

[control table]
Address Size Data Name
Expand Down
1 change: 1 addition & 0 deletions param/dxl_model/xc330_t288.model
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ value_of_max_radian_position 4095
value_of_min_radian_position 0
min_radian -3.14159265
max_radian 3.14159265
torque_constant 0.0009674796739867748

[control table]
Address Size Data Name
Expand Down
1 change: 1 addition & 0 deletions param/dxl_model/xh540_w150.model
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@ value_of_max_radian_position 4095
value_of_min_radian_position 0
min_radian -3.14159265
max_radian 3.14159265
torque_constant 0.0045

[control table]
Address Size Data Name
Expand Down
4 changes: 2 additions & 2 deletions src/dynamixel/dynamixel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -840,7 +840,7 @@ DxlError Dynamixel::GetDxlValueFromSyncRead()
dxl_info_.ConvertValueRPMToVelocityRPS(ID, static_cast<int32_t>(dxl_getdata));
} else if (indirect_info_read_[ID].item_name.at(item_index) == "Present Current") {
*it_read_data.item_data_ptr_vec.at(item_index) =
static_cast<int16_t>(dxl_getdata);
dxl_info_.ConvertCurrentToEffort(ID, static_cast<int16_t>(dxl_getdata));
} else {
*it_read_data.item_data_ptr_vec.at(item_index) =
static_cast<double>(dxl_getdata);
Expand Down Expand Up @@ -962,7 +962,7 @@ DxlError Dynamixel::GetDxlValueFromBulkRead()
dxl_info_.ConvertValueRPMToVelocityRPS(ID, static_cast<int32_t>(dxl_getdata));
} else if (indirect_info_read_[ID].item_name.at(item_index) == "Present Current") {
*it_read_data.item_data_ptr_vec.at(item_index) =
static_cast<int16_t>(dxl_getdata);
dxl_info_.ConvertCurrentToEffort(ID, static_cast<int16_t>(dxl_getdata));
} else {
*it_read_data.item_data_ptr_vec.at(item_index) =
static_cast<double>(dxl_getdata);
Expand Down
4 changes: 3 additions & 1 deletion src/dynamixel/dynamixel_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -149,13 +149,15 @@ bool DynamixelInfo::GetDxlTypeInfo(
int32_t & value_of_max_radian_position,
int32_t & value_of_min_radian_position,
double & min_radian,
double & max_radian)
double & max_radian,
double & torque_constant)
{
value_of_zero_radian_position = dxl_info_[id].value_of_zero_radian_position;
value_of_max_radian_position = dxl_info_[id].value_of_max_radian_position;
value_of_min_radian_position = dxl_info_[id].value_of_min_radian_position;
min_radian = dxl_info_[id].min_radian;
max_radian = dxl_info_[id].max_radian;
torque_constant = dxl_info_[id].torque_constant;
return true;
}

Expand Down
43 changes: 34 additions & 9 deletions src/dynamixel_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -711,15 +711,21 @@ bool DynamixelHardware::InitDxlWriteItems()
for (const hardware_interface::ComponentInfo & gpio : info_.gpios) {
if (gpio.command_interfaces.size()) {
uint8_t id = static_cast<uint8_t>(stoi(gpio.parameters.at("ID")));
for (auto it : gpio.command_interfaces) {
HandlerVarType temp_write;
temp_write.id = id;
temp_write.name = gpio.name;
HandlerVarType temp_write;
temp_write.id = id;
temp_write.name = gpio.name;

temp_write.interface_name_vec.push_back("Goal Position");
temp_write.value_ptr_vec.push_back(std::make_shared<double>(0.0));

temp_write.interface_name_vec.push_back(it.name);
temp_write.value_ptr_vec.push_back(std::make_shared<double>(0.0));
hdl_trans_commands_.push_back(temp_write);
for (auto it : gpio.command_interfaces) {
if (it.name == "Goal Current") {
temp_write.interface_name_vec.push_back("Goal Current");
temp_write.value_ptr_vec.push_back(std::make_shared<double>(0.0));
}
}

hdl_trans_commands_.push_back(temp_write);
Comment on lines +714 to +728
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

medium

The logic here could be simplified. Instead of creating a temp_write object and pushing it back, consider directly pushing the necessary interfaces and values into hdl_trans_commands_ within the loop. This might reduce the number of lines and improve readability.

}
}
is_set_hdl = true;
Expand Down Expand Up @@ -853,14 +859,33 @@ void DynamixelHardware::CalcJointToTransmission()
double value = 0.0;
for (size_t j = 0; j < num_of_joints_; j++) {
value += joint_to_transmission_matrix_[i][j] *
(*hdl_joint_commands_.at(j).value_ptr_vec.at(0));
(*hdl_joint_commands_.at(j).value_ptr_vec.at(GOAL_POSITION_INDEX));
}

if (hdl_trans_commands_.at(i).name == conversion_dxl_name_) {
value = prismaticToRevolute(value);
}
*hdl_trans_commands_.at(i).value_ptr_vec.at(GOAL_POSITION_INDEX) = value;
}

*hdl_trans_commands_.at(i).value_ptr_vec.at(0) = value;
for (size_t i = 0; i < num_of_transmissions_; i++) {
if (hdl_trans_commands_.at(i).interface_name_vec.size() > GOAL_CURRENT_INDEX &&
hdl_trans_commands_.at(i).interface_name_vec.at(GOAL_CURRENT_INDEX) == "Goal Current")
{
for (size_t j = 0; j < hdl_joint_commands_.size(); j++) {
if (hdl_joint_commands_.at(j).interface_name_vec.size() > GOAL_CURRENT_INDEX &&
hdl_joint_commands_.at(j).interface_name_vec.at(GOAL_CURRENT_INDEX) ==
hardware_interface::HW_IF_EFFORT)
Comment on lines +875 to +878
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

medium

This nested if statement checks for the same condition twice. Consider refactoring this to avoid redundancy and improve readability. You could extract the condition into a variable and reuse it.

{
double value = 0.0;
for (size_t k = 0; k < num_of_joints_; k++) {
value += joint_to_transmission_matrix_[i][k] *
(*hdl_joint_commands_.at(k).value_ptr_vec.at(GOAL_CURRENT_INDEX));
}
*hdl_trans_commands_.at(i).value_ptr_vec.at(GOAL_CURRENT_INDEX) = value;
}
}
}
}
}

Expand Down
Loading