Skip to content

Commit a2dcf76

Browse files
authored
Merge pull request #18 from ROBOTIS-GIT/feature-om-y-top-support
Support Current Control
2 parents ab7956c + 196cd79 commit a2dcf76

File tree

8 files changed

+48
-13
lines changed

8 files changed

+48
-13
lines changed

include/dynamixel_hardware_interface/dynamixel/dynamixel_info.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,8 @@ class DynamixelInfo
7878
int32_t & value_of_max_radian_position,
7979
int32_t & value_of_min_radian_position,
8080
double & min_radian,
81-
double & max_radian);
81+
double & max_radian,
82+
double & torque_constant);
8283
int32_t ConvertRadianToValue(uint8_t id, double radian);
8384
double ConvertValueToRadian(uint8_t id, int32_t value);
8485
inline int16_t ConvertEffortToCurrent(uint8_t id, double effort)

include/dynamixel_hardware_interface/dynamixel_hardware_interface.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,10 @@
4747
#define PRESENT_VELOCITY_INDEX 1
4848
#define PRESENT_EFFORT_INDEX 2
4949

50+
#define GOAL_POSITION_INDEX 0
51+
// #define GOAL_VELOCITY_INDEX 1 // TODO: to be implemented
52+
#define GOAL_CURRENT_INDEX 1
53+
5054
namespace dynamixel_hardware_interface
5155
{
5256

param/dxl_model/xc330_t181.model

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@ value_of_max_radian_position 4095
55
value_of_min_radian_position 0
66
min_radian -3.14159265
77
max_radian 3.14159265
8+
torque_constant 0.0006709470296015791
89

910
[control table]
1011
Address Size Data Name

param/dxl_model/xc330_t288.model

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@ value_of_max_radian_position 4095
55
value_of_min_radian_position 0
66
min_radian -3.14159265
77
max_radian 3.14159265
8+
torque_constant 0.0009674796739867748
89

910
[control table]
1011
Address Size Data Name

param/dxl_model/xh540_w150.model

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@ value_of_max_radian_position 4095
55
value_of_min_radian_position 0
66
min_radian -3.14159265
77
max_radian 3.14159265
8+
torque_constant 0.0045
89

910
[control table]
1011
Address Size Data Name

src/dynamixel/dynamixel.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -840,7 +840,7 @@ DxlError Dynamixel::GetDxlValueFromSyncRead()
840840
dxl_info_.ConvertValueRPMToVelocityRPS(ID, static_cast<int32_t>(dxl_getdata));
841841
} else if (indirect_info_read_[ID].item_name.at(item_index) == "Present Current") {
842842
*it_read_data.item_data_ptr_vec.at(item_index) =
843-
static_cast<int16_t>(dxl_getdata);
843+
dxl_info_.ConvertCurrentToEffort(ID, static_cast<int16_t>(dxl_getdata));
844844
} else {
845845
*it_read_data.item_data_ptr_vec.at(item_index) =
846846
static_cast<double>(dxl_getdata);
@@ -962,7 +962,7 @@ DxlError Dynamixel::GetDxlValueFromBulkRead()
962962
dxl_info_.ConvertValueRPMToVelocityRPS(ID, static_cast<int32_t>(dxl_getdata));
963963
} else if (indirect_info_read_[ID].item_name.at(item_index) == "Present Current") {
964964
*it_read_data.item_data_ptr_vec.at(item_index) =
965-
static_cast<int16_t>(dxl_getdata);
965+
dxl_info_.ConvertCurrentToEffort(ID, static_cast<int16_t>(dxl_getdata));
966966
} else {
967967
*it_read_data.item_data_ptr_vec.at(item_index) =
968968
static_cast<double>(dxl_getdata);

src/dynamixel/dynamixel_info.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -149,13 +149,15 @@ bool DynamixelInfo::GetDxlTypeInfo(
149149
int32_t & value_of_max_radian_position,
150150
int32_t & value_of_min_radian_position,
151151
double & min_radian,
152-
double & max_radian)
152+
double & max_radian,
153+
double & torque_constant)
153154
{
154155
value_of_zero_radian_position = dxl_info_[id].value_of_zero_radian_position;
155156
value_of_max_radian_position = dxl_info_[id].value_of_max_radian_position;
156157
value_of_min_radian_position = dxl_info_[id].value_of_min_radian_position;
157158
min_radian = dxl_info_[id].min_radian;
158159
max_radian = dxl_info_[id].max_radian;
160+
torque_constant = dxl_info_[id].torque_constant;
159161
return true;
160162
}
161163

src/dynamixel_hardware_interface.cpp

Lines changed: 34 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -711,15 +711,21 @@ bool DynamixelHardware::InitDxlWriteItems()
711711
for (const hardware_interface::ComponentInfo & gpio : info_.gpios) {
712712
if (gpio.command_interfaces.size()) {
713713
uint8_t id = static_cast<uint8_t>(stoi(gpio.parameters.at("ID")));
714-
for (auto it : gpio.command_interfaces) {
715-
HandlerVarType temp_write;
716-
temp_write.id = id;
717-
temp_write.name = gpio.name;
714+
HandlerVarType temp_write;
715+
temp_write.id = id;
716+
temp_write.name = gpio.name;
717+
718+
temp_write.interface_name_vec.push_back("Goal Position");
719+
temp_write.value_ptr_vec.push_back(std::make_shared<double>(0.0));
718720

719-
temp_write.interface_name_vec.push_back(it.name);
720-
temp_write.value_ptr_vec.push_back(std::make_shared<double>(0.0));
721-
hdl_trans_commands_.push_back(temp_write);
721+
for (auto it : gpio.command_interfaces) {
722+
if (it.name == "Goal Current") {
723+
temp_write.interface_name_vec.push_back("Goal Current");
724+
temp_write.value_ptr_vec.push_back(std::make_shared<double>(0.0));
725+
}
722726
}
727+
728+
hdl_trans_commands_.push_back(temp_write);
723729
}
724730
}
725731
is_set_hdl = true;
@@ -853,14 +859,33 @@ void DynamixelHardware::CalcJointToTransmission()
853859
double value = 0.0;
854860
for (size_t j = 0; j < num_of_joints_; j++) {
855861
value += joint_to_transmission_matrix_[i][j] *
856-
(*hdl_joint_commands_.at(j).value_ptr_vec.at(0));
862+
(*hdl_joint_commands_.at(j).value_ptr_vec.at(GOAL_POSITION_INDEX));
857863
}
858864

859865
if (hdl_trans_commands_.at(i).name == conversion_dxl_name_) {
860866
value = prismaticToRevolute(value);
861867
}
868+
*hdl_trans_commands_.at(i).value_ptr_vec.at(GOAL_POSITION_INDEX) = value;
869+
}
862870

863-
*hdl_trans_commands_.at(i).value_ptr_vec.at(0) = value;
871+
for (size_t i = 0; i < num_of_transmissions_; i++) {
872+
if (hdl_trans_commands_.at(i).interface_name_vec.size() > GOAL_CURRENT_INDEX &&
873+
hdl_trans_commands_.at(i).interface_name_vec.at(GOAL_CURRENT_INDEX) == "Goal Current")
874+
{
875+
for (size_t j = 0; j < hdl_joint_commands_.size(); j++) {
876+
if (hdl_joint_commands_.at(j).interface_name_vec.size() > GOAL_CURRENT_INDEX &&
877+
hdl_joint_commands_.at(j).interface_name_vec.at(GOAL_CURRENT_INDEX) ==
878+
hardware_interface::HW_IF_EFFORT)
879+
{
880+
double value = 0.0;
881+
for (size_t k = 0; k < num_of_joints_; k++) {
882+
value += joint_to_transmission_matrix_[i][k] *
883+
(*hdl_joint_commands_.at(k).value_ptr_vec.at(GOAL_CURRENT_INDEX));
884+
}
885+
*hdl_trans_commands_.at(i).value_ptr_vec.at(GOAL_CURRENT_INDEX) = value;
886+
}
887+
}
888+
}
864889
}
865890
}
866891

0 commit comments

Comments
 (0)