84 #include "yaml-cpp/yaml.h"
96 bool use_group_read,
bool use_group_write)
98 ROS_INFO(
"Device is '%s' with baud rate '%d'", device.c_str(), baud);
99 if (use_legacy_protocol)
105 ROS_INFO(
"Using group read methods");
109 ROS_INFO(
"Using group write methods");
156 ROS_INFO(
"Initialising Dynamixel Port Driver");
161 path +=
"/config/motor_data.yaml";
163 ROS_INFO(
"Loading motor data from file");
166 doc = YAML::LoadFile(path);
168 catch (
const YAML::BadFile &exception)
170 ROS_ERROR(
"Unable to load motor_data.yaml file, expected at %s", path.c_str());
176 for (
int i = 0; i < doc.size(); i++)
181 spec.
name = doc[i][
"name"].as<std::string>();
184 std::string type = doc[i][
"series"].as<std::string>();
189 else if (type ==
"LM")
193 else if (type ==
"X")
197 else if (type ==
"A")
201 else if (type ==
"R")
205 else if (type ==
"D")
209 else if (type ==
"E")
213 else if (type ==
"P")
217 else if (type ==
"LP")
226 spec.
encoder_cpr = doc[i][
"encoder_cpr"].as<uint>();
231 if (doc[i][
"encoder_range_deg"])
240 if (doc[i][
"external_ports"])
263 ROS_ERROR(
"Unable to parse motor_data.yaml file");
285 ROS_ERROR(
"Failed to change the baudrate!");
345 int dxl_comm_result = -1;
356 *error_status = error;
362 error_status, &error);
372 error_status, &error);
395 int dxl_comm_result = -1;
406 reinterpret_cast<uint8_t*
>(max_torque), &error);
479 *torque_enabled = (data > 0);
507 reinterpret_cast<uint16_t*
>(target_torque), &error);
513 reinterpret_cast<uint16_t*
>(target_torque), &error);
518 reinterpret_cast<uint16_t*
>(target_torque), &error);
523 reinterpret_cast<uint16_t*
>(target_torque), &error);
545 std::vector<uint8_t> *response)
const
576 bool success =
false;
577 std::unordered_map<int, SyncData*> read_map;
581 if (state_map.size() == 0)
586 for (
auto &it : state_map)
588 it.second.success =
false;
589 read_map[it.first] =
static_cast<SyncData*
>(&it.second);
608 for (
auto &it : state_map)
612 it.second.success =
true;
616 it.second.success =
false;
621 for (
auto &it : state_map)
623 if (it.second.success)
625 it.second.position = *(
reinterpret_cast<int16_t*
>(&it.second.data[0]));
626 it.second.velocity = *(
reinterpret_cast<int16_t*
>(&it.second.data[2]));
627 it.second.effort = *(
reinterpret_cast<int16_t*
>(&it.second.data[4]));
642 for (
auto &it : state_map)
646 it.second.success =
true;
650 it.second.success =
false;
654 for (
auto &it : state_map)
656 if (it.second.success)
658 it.second.effort = *(
reinterpret_cast<int16_t*
>(&it.second.data[0]));
659 it.second.velocity = *(
reinterpret_cast<int32_t*
>(&it.second.data[2]));
660 it.second.position = *(
reinterpret_cast<int32_t*
>(&it.second.data[6]));
674 for (
auto &it : state_map)
678 it.second.success =
true;
682 it.second.success =
false;
686 for (
auto &it : state_map)
688 if (it.second.success)
690 it.second.effort = *(
reinterpret_cast<int16_t*
>(&it.second.data[0]));
691 it.second.velocity = *(
reinterpret_cast<int32_t*
>(&it.second.data[2]));
692 it.second.position = *(
reinterpret_cast<int32_t*
>(&it.second.data[6]));
706 for (
auto &it : state_map)
710 it.second.success =
true;
714 it.second.success =
false;
718 for (
auto &it : state_map)
720 if (it.second.success)
722 it.second.position = *(
reinterpret_cast<int32_t*
>(&it.second.data[0]));
723 it.second.velocity = *(
reinterpret_cast<int32_t*
>(&it.second.data[4]));
724 it.second.effort = *(
reinterpret_cast<int16_t*
>(&it.second.data[8]));
744 bool success =
false;
745 std::unordered_map<int, SyncData*> read_map;
749 if (data_map.size() == 0)
754 for (
auto &it : data_map)
756 it.second.success =
false;
757 read_map[it.first] =
static_cast<SyncData*
>(&it.second);
772 for (
auto &it : data_map)
776 it.second.success =
true;
780 it.second.success =
false;
784 for (
auto &it : data_map)
786 if (it.second.success)
788 it.second.port_values[0] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[0]));
789 it.second.port_values[1] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[2]));
790 it.second.port_values[2] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[4]));
791 it.second.port_values[4] = 0;
807 for (
auto &it : data_map)
811 it.second.success =
true;
815 it.second.success =
false;
819 for (
auto &it : data_map)
821 if (it.second.success)
823 it.second.port_values[0] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[0]));
824 it.second.port_values[1] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[2]));
825 it.second.port_values[2] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[4]));
826 it.second.port_values[3] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[6]));
841 for (
auto &it : data_map)
845 it.second.success =
true;
849 it.second.success =
false;
853 for (
auto &it : data_map)
855 if (it.second.success)
857 it.second.port_values[0] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[0]));
858 it.second.port_values[1] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[2]));
859 it.second.port_values[2] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[4]));
860 it.second.port_values[3] = *(
reinterpret_cast<uint16_t*
>(&it.second.data[6]));
878 bool success =
false;
879 std::unordered_map<int, SyncData*> read_map;
883 if (diag_map.size() == 0)
888 for (
auto &it : diag_map)
890 it.second.success =
false;
891 read_map[it.first] =
static_cast<SyncData*
>(&it.second);
911 for (
auto &it : diag_map)
915 it.second.success =
true;
919 it.second.success =
false;
923 for (
auto &it : diag_map)
925 if (it.second.success)
927 it.second.voltage = it.second.data[0];
928 it.second.temperature = it.second.data[1];
944 for (
auto &it : diag_map)
948 it.second.success =
true;
952 it.second.success =
false;
956 for (
auto &it : diag_map)
958 if (it.second.success)
960 it.second.voltage = *(
reinterpret_cast<uint16_t*
>(&it.second.data[6]));
961 it.second.temperature = it.second.data[2];
977 for (
auto &it : diag_map)
981 it.second.success =
true;
985 it.second.success =
false;
989 for (
auto &it : diag_map)
991 if (it.second.success)
993 it.second.voltage = *(
reinterpret_cast<uint16_t*
>(&it.second.data[0]));
994 it.second.temperature = it.second.data[2];
1009 for (
auto &it : diag_map)
1013 it.second.success =
true;
1017 it.second.success =
false;
1021 for (
auto &it : diag_map)
1023 if (it.second.success)
1025 it.second.voltage = *(
reinterpret_cast<uint16_t*
>(&it.second.data[0]));
1026 it.second.temperature = it.second.data[2];
1050 uint16_t length)
const
1052 int dxl_comm_result;
1053 bool success =
false;
1059 for (
auto &it : read_data)
1061 GroupBulkRead.
addParam(it.first, address, length);
1063 it.second->data.clear();
1067 dxl_comm_result = GroupBulkRead.
txRxPacket();
1075 for (
auto &it : read_data)
1078 if (GroupBulkRead.
isAvailable(it.first, address, length))
1084 for (
int j = 0; j < length; j++)
1086 it.second->data.push_back(GroupBulkRead.
getData(it.first, address + j, 1));
1088 it.second->success =
true;
1091 GroupBulkRead.
getError(it.first, &(it.second->error));
1112 uint16_t length)
const
1114 int dxl_comm_result;
1115 bool success =
false;
1126 for (
auto &it : read_data)
1130 it.second->data.clear();
1134 dxl_comm_result = GroupSyncRead.
txRxPacket();
1142 for (
auto &it : read_data)
1145 if (GroupSyncRead.
isAvailable(it.first, address, length))
1150 for (
int j = 0; j < length; j++)
1152 it.second->data.push_back(GroupSyncRead.
getData(it.first, address + j, 1));
1154 it.second->success =
true;
1158 it.second->success =
false;
1161 GroupSyncRead.
getError(it.first, &(it.second->error));
1189 int dxl_comm_result = 0;
1191 bool success =
true;
1204 switch (operating_mode)
1230 if (success && (model_num != 30))
1233 operating_mode, &error);
1239 operating_mode, &error);
1254 operating_mode, &error);
1280 int32_t max_angle)
const
1300 int dxl_comm_result;
1349 int dxl_comm_result;
1398 int dxl_comm_result;
1453 int dxl_comm_result;
1501 int dxl_comm_result;
1553 int dxl_comm_result;
1557 if ((model_num == 310) || (model_num == 320))
1560 (uint8_t)(on), &error);
1586 double d_gain)
const
1588 uint16_t p_val, i_val, d_val;
1594 p_val = (uint16_t)(p_gain * 8.0);
1595 i_val = (uint16_t)(i_gain * (1000.0 / 2048.0));
1596 d_val = (uint16_t)(d_gain / (4.0 / 1000.0));
1601 p_val = (uint16_t)(p_gain * 128.0);
1602 i_val = (uint16_t)(i_gain * 65536.0);
1603 d_val = (uint16_t)(d_gain * 16.0);
1607 p_val = (uint16_t)p_gain;
1654 int dxl_comm_result;
1667 (uint8_t)(gain & 0x00FF), &error);
1705 int dxl_comm_result;
1718 (uint8_t)(gain & 0x00FF), &error);
1754 int dxl_comm_result;
1767 (uint8_t)(gain & 0x00FF), &error);
1803 double i_gain)
const
1805 uint16_t p_val, i_val, d_val;
1812 p_val = (uint16_t)(p_gain * 128.0);
1813 i_val = (uint16_t)(i_gain * 65536.0);
1817 p_val = (uint16_t)p_gain;
1818 i_val = (uint16_t)i_gain;
1855 int dxl_comm_result;
1901 int dxl_comm_result;
1948 int dxl_comm_result;
1958 (uint16_t)velocity, &error);
1997 int dxl_comm_result;
2049 int dxl_comm_result;
2072 if (position_data.size() == 0)
2106 if (velocity_data.size() == 0)
2139 if (velocity_data.size() == 0)
2172 if (torque_data.size() == 0)
2212 uint16_t length)
const
2214 uint8_t dxl_comm_result;
2215 bool success =
true;
2223 for (
auto &it : write_data)
2226 if (it.second.data.size() == length)
2228 groupSyncWrite.
addParam(it.first, it.second.data.data());
2233 dxl_comm_result = groupSyncWrite.
txPacket();
2246 for (
auto &it : write_data)
2248 if (!
writeRegisters(it.first, address, length, it.second.data.data()))