90 #define _USE_MATH_DEFINES
106 nh_ = std::make_unique<ros::NodeHandle>();
113 ROS_INFO(
"shutting_down dynamixel_interface_controller");
122 dynamixel_ports_[i].driver->setTorqueEnabled(it.second.id, it.second.model_spec->type, 0);
123 ROS_INFO(
"Torque disabled on %s joint\n", it.first.c_str());
145 ros::param::param<double>(
"~loop_rate",
loop_rate_, 50.0);
154 ros::param::param<std::string>(
"~control_mode", mode,
"Position");
169 ROS_ERROR(
"recv queue size must be >= 1");
179 ROS_WARN(
"Clamping diagnostics rate to loop rate.");
195 ROS_WARN(
"Clamping dataport rate to loop rate.");
206 if (mode ==
"position")
210 else if (mode ==
"velocity")
214 else if (mode ==
"effort")
220 ROS_ERROR(
"Control Mode Not Supported!");
233 ROS_ERROR(
"Unable to parse ports from config!");
240 ROS_ERROR(
"No valid ports found, shutting_down...");
246 ROS_ERROR(
"No port details loaded to param server");
279 ROS_ERROR(
"Invalid/missing device information on the param server");
284 int num_ports = ports.
size();
287 for (
int i = 0; i < ports.
size(); i++)
291 bool use_group_read =
false;
292 bool use_group_write =
false;
300 ROS_ERROR(
"Invalid/Missing info-struct for servo index %d", i);
308 ROS_ERROR(
"Invalid/Missing port name for port %d", i);
313 port.
port_name =
static_cast<std::string
>(ports[i][
"name"]);
320 ROS_ERROR(
"Invalid/Missing device name for port %d", i);
325 port.
device =
static_cast<std::string
>(ports[i][
"device"]);
331 ROS_ERROR(
"Invalid/Missing baudrate for port %d", i);
336 port.
baudrate =
static_cast<int>(ports[i][
"baudrate"]);
342 ROS_ERROR(
"Invalid/Missing use_legacy_protocol option for port %d", i);
353 ROS_ERROR(
"Invalid/Missing group_read_enabled option for port %d", i);
358 use_group_read =
static_cast<bool>(ports[i][
"group_read_enabled"]);
364 ROS_ERROR(
"Invalid/Missing group_write_enabled option for port %d", i);
369 use_group_write =
static_cast<bool>(ports[i][
"group_write_enabled"]);
386 ROS_ERROR(
"Invalid/missing servo information on the param server");
391 servos = ports[i][
"servos"];
401 if (port.
joints.size() > 0)
430 int num_servos = servos.
size();
433 for (
int i = 0; i < servos.
size(); i++)
441 ROS_ERROR(
"Invalid/Missing info-struct for servo index %d", i);
448 ROS_ERROR(
"Invalid/Missing id for servo index %d", i);
454 info.
id =
static_cast<int>(servos[i][
"id"]);
460 ROS_ERROR(
"Invalid/Missing joint name for servo index %d, id: %d", i, info.
id);
466 info.
joint_name =
static_cast<std::string
>(servos[i][
"joint_name"]);
491 ROS_ERROR(
"Invalid/Missing zero position for servo index %d, id: %d", i, info.
id);
497 info.
zero_pos =
static_cast<int>(servos[i][
"zero_pos"]);
503 ROS_ERROR(
"Invalid/Missing min position for servo index %d, id: %d", i, info.
id);
508 info.
min_pos =
static_cast<int>(servos[i][
"min_pos"]);
514 ROS_ERROR(
"Invalid/Missing max position for servo index %d, id: %d", i, info.
id);
519 info.
max_pos =
static_cast<int>(servos[i][
"max_pos"]);
529 info.
max_vel =
static_cast<double>(servos[i][
"max_vel"]);
544 info.
torque_limit =
static_cast<double>(servos[i][
"torque_limit"]);
576 ROS_ERROR(
"Parameters not parsed yet, must be parsed before init");
589 ROS_ERROR(
"Unable to initialised port %s", port.port_name.c_str());
612 ROS_ERROR(
"Parameters not parsed yet, must be parsed before init");
622 bool first_dynamixel =
true;
625 if (!port.
driver->initialise())
627 ROS_ERROR(
"Unable to initialise driver");
632 for (
auto &it : port.
joints)
636 ROS_ERROR(
"Unable to initialised dynamixel %s", it.second.joint_name.c_str());
642 for (
auto &it : port.
joints)
646 type_check = it.second.model_spec->type;
647 first_dynamixel =
false;
660 ROS_ERROR(
"Type mismatch on bus, only dynamixel who share a common register table may share a bus! "
661 "Have both %s and %s.",
662 port.
driver->getSeriesName(type_check).c_str(),
663 port.
driver->getSeriesName(it.second.model_spec->type).c_str());
670 if ((it.second.model_spec->type !=
kSeriesX) && (it.second.model_spec->type !=
kSeriesMX))
672 ROS_ERROR(
"Type mismatch on bus, only dynamixel who share a common register table may share a bus! "
673 "Have both %s and %s.",
674 port.
driver->getSeriesName(type_check).c_str(),
675 port.
driver->getSeriesName(it.second.model_spec->type).c_str());
681 if (it.second.model_spec->type !=
kSeriesP)
683 ROS_ERROR(
"Type mismatch on bus, only dynamixel who share a common register table may share a bus! "
684 "Have both %s and %s.",
685 port.
driver->getSeriesName(type_check).c_str(),
686 port.
driver->getSeriesName(it.second.model_spec->type).c_str());
694 ROS_ERROR(
"Type mismatch on bus, only dynamixel who share a common register table may share a bus! "
695 "Have both %s and %s.",
696 port.
driver->getSeriesName(type_check).c_str(),
697 port.
driver->getSeriesName(it.second.model_spec->type).c_str());
716 ROS_ERROR(
"Parameters not parsed yet, must be parsed before init");
731 bool ping_success =
true;
738 ROS_WARN(
"Failed to ping id: %d, attempt %d, retrying...",
dynamixel.id, ping_count);
753 uint16_t model_number = 0;
760 else if (model_number == 0)
771 ROS_ERROR(
"Model Number: %d", model_number);
778 uint8_t error_status = 0;
783 else if (error_status)
805 ROS_ERROR(
"Effort Control not supported for legacy series dynamixels!");
896 else if ((
write_msg_.position.empty() == joint_commands->position.empty()) &&
897 (
write_msg_.velocity.empty() == joint_commands->velocity.empty()) &&
898 (
write_msg_.effort.empty() == joint_commands->effort.empty()))
901 for (
int i = 0; i < joint_commands->name.size(); i++)
906 for (
int j = 0; j <
write_msg_.name.size(); j++)
908 if (joint_commands->name[i] ==
write_msg_.name[j])
910 if (!
write_msg_.position.empty() && !joint_commands->position.empty())
912 write_msg_.position[j] = joint_commands->position[i];
915 if (!
write_msg_.velocity.empty() && !joint_commands->velocity.empty())
917 write_msg_.velocity[j] = joint_commands->velocity[i];
920 if (!
write_msg_.effort.empty() && !joint_commands->effort.empty())
922 write_msg_.effort[j] = joint_commands->effort[i];
933 write_msg_.name.push_back(joint_commands->name[i]);
935 if (!
write_msg_.position.empty() && !joint_commands->position.empty())
937 write_msg_.position.push_back(joint_commands->position[i]);
940 if (!
write_msg_.velocity.empty() && !joint_commands->velocity.empty())
942 write_msg_.velocity.push_back(joint_commands->velocity[i]);
945 if (!
write_msg_.effort.empty() && !joint_commands->effort.empty())
947 write_msg_.effort.push_back(joint_commands->effort[i]);
968 std::vector<std::thread> threads;
970 sensor_msgs::JointState read_msg;
973 dynamixel_interface::DataPorts dataports_msg;
976 dynamixel_interface::ServoDiags diags_msg;
1007 reads[i] = sensor_msgs::JointState();
1010 std::ref(reads[i]), std::ref(dataports_reads[i]), std::ref(diags_reads[i]),
write_ready_);
1014 reads[0] = sensor_msgs::JointState();
1019 sensor_msgs::JointState temp_msg =
write_msg_;
1029 threads[i - 1].join();
1032 if (reads[i].name.size() == 0)
1039 read_msg.name.insert(read_msg.name.end(), reads[i].name.begin(), reads[i].name.end());
1040 read_msg.position.insert(read_msg.position.end(), reads[i].position.begin(), reads[i].position.end());
1041 read_msg.velocity.insert(read_msg.velocity.end(), reads[i].velocity.begin(), reads[i].velocity.end());
1042 read_msg.effort.insert(read_msg.effort.end(), reads[i].effort.begin(), reads[i].effort.end());
1047 if (dataports_reads[i].states.size() > 0)
1050 dataports_msg.states.insert(dataports_msg.states.end(), dataports_reads[i].states.begin(),
1051 dataports_reads[i].states.end());
1058 if (diags_reads[i].diagnostics.size() > 0)
1060 diags_msg.diagnostics.insert(diags_msg.diagnostics.end(), diags_reads[i].diagnostics.begin(),
1061 diags_reads[i].diagnostics.end());
1079 if (read_msg.name.size() > 0)
1106 dynamixel_interface::DataPorts &dataport_msg,
1107 dynamixel_interface::ServoDiags &diags_msg,
bool perform_write)
const
1126 if (joint_commands.name.size() < 1)
1132 bool has_pos =
false;
1133 bool has_vel =
false;
1134 bool has_eff =
false;
1141 if ((joint_commands.velocity.size() == joint_commands.name.size()) &&
1151 if ((!has_pos) && (!has_vel) && (!has_eff))
1158 std::unordered_map<int, SyncData> velocities, positions, efforts;
1164 for (
int i = 0; i < joint_commands.name.size(); i++)
1167 if (port.
joints.find(joint_commands.name[i]) == port.
joints.end())
1207 double rad_pos = joint_commands.position[i];
1228 if ((pos <= up_lim) && (pos >= dn_lim))
1231 write_data.
id = info->
id;
1235 write_data.
data.resize(2);
1236 *(
reinterpret_cast<uint16_t*
>(write_data.
data.data())) =
static_cast<uint16_t
>(pos);
1240 write_data.
data.resize(4);
1241 *(
reinterpret_cast<uint32_t*
>(write_data.
data.data())) =
static_cast<uint32_t
>(pos);
1244 positions[info->
id] = write_data;
1252 double rad_s_vel = joint_commands.velocity[i];
1255 rad_s_vel = std::min(std::max(rad_s_vel, -info->
max_vel), info->
max_vel);
1272 vel = std::abs(vel) + 1024;
1281 vel = std::abs(vel);
1285 write_data.
id = info->
id;
1289 write_data.
data.resize(2);
1290 *(
reinterpret_cast<uint16_t*
>(write_data.
data.data())) =
static_cast<uint16_t
>(vel);
1294 write_data.
data.resize(4);
1295 *(
reinterpret_cast<uint32_t*
>(write_data.
data.data())) =
static_cast<uint32_t
>(vel);
1298 velocities[info->
id] = write_data;
1303 double input_effort = joint_commands.effort[i];
1311 effort = abs(effort);
1320 write_data.
id = info->
id;
1322 write_data.
data.resize(2);
1323 *(
reinterpret_cast<int16_t*
>(write_data.
data.data())) = effort;
1325 efforts[info->
id] = write_data;
1336 if (!port.
driver->setMultiProfileVelocity(velocities))
1344 if (!port.
driver->setMultiPosition(positions))
1353 if (!port.
driver->setMultiVelocity(velocities))
1361 if (!port.
driver->setMultiTorque(efforts))
1375 dynamixel_interface::DataPorts &dataport_msg,
1376 dynamixel_interface::ServoDiags &diags_msg)
const
1379 std::unordered_map<int, DynamixelState> state_map;
1380 std::unordered_map<int, DynamixelDiagnostic> diag_map;
1381 std::unordered_map<int, DynamixelDataport> data_map;
1384 for (
auto &it : port.
joints)
1388 state_map[it.second.id].id = it.second.id;
1389 state_map[it.second.id].type = it.second.model_spec->type;
1391 diag_map[it.second.id].id = it.second.id;
1392 diag_map[it.second.id].type = it.second.model_spec->type;
1393 if (it.second.model_spec->external_ports)
1396 data_map[it.second.id].id = it.second.id;
1397 data_map[it.second.id].type = it.second.model_spec->type;
1402 if (port.
driver->getBulkState(state_map))
1405 for (
auto &it : port.
joints)
1408 std::string joint_name = it.first;
1411 if (!state_map[it.second.id].success)
1413 ROS_WARN(
"FAILED TO READ DYNAMIXEL %s (id %d)!", joint_name.c_str(), it.second.id);
1418 read_msg.name.push_back(joint_name);
1425 double rad_pos = (state_map[it.second.id].position - it.second.zero_pos) *
1426 (2.0 * M_PI * it.second.model_spec->encoder_range_deg) /
1427 (360.0 * it.second.model_spec->encoder_cpr);
1428 if (it.second.min_pos > it.second.max_pos)
1434 read_msg.position.push_back(rad_pos);
1437 int raw_vel = state_map[it.second.id].velocity;
1445 raw_vel = (raw_vel & 0x3FF);
1447 if ((raw_vel > 1023) && (it.second.max_pos > it.second.min_pos))
1451 else if ((raw_vel < 1023) && (it.second.max_pos < it.second.min_pos))
1456 else if (it.second.min_pos > it.second.max_pos)
1462 double rad_s_vel = (
static_cast<double>(raw_vel)) / it.second.model_spec->velocity_radps_to_reg;
1465 read_msg.velocity.push_back(rad_s_vel);
1475 effort =
static_cast<double>(state_map[it.second.id].effort & 0x3FF) * it.second.model_spec->effort_reg_to_mA;
1477 if (state_map[it.second.id].effort < 1023)
1479 effort = 0.0 - effort;
1484 effort =
static_cast<double>(state_map[it.second.id].effort) * it.second.model_spec->effort_reg_to_mA;
1487 if (it.second.min_pos > it.second.max_pos)
1493 read_msg.effort.push_back(effort);
1504 if (port.
driver->getBulkDataportInfo(data_map))
1507 dataport_msg.header.frame_id = port.
port_name.c_str();
1510 for (
auto &it : port.
joints)
1512 dynamixel_interface::DataPort msg;
1515 if (!data_map[it.second.id].success)
1521 msg.name = it.first;
1522 msg.port_values.push_back(data_map[it.second.id].port_values[0]);
1523 msg.port_values.push_back(data_map[it.second.id].port_values[1]);
1524 msg.port_values.push_back(data_map[it.second.id].port_values[2]);
1525 msg.port_values.push_back(data_map[it.second.id].port_values[3]);
1528 dataport_msg.states.push_back(msg);
1539 if (port.
driver->getBulkDiagnosticInfo(diag_map))
1542 diags_msg.header.frame_id = port.
port_name.c_str();
1545 for (
auto &it : port.
joints)
1547 dynamixel_interface::ServoDiag msg;
1550 if (!diag_map[it.second.id].success)
1556 msg.name = it.first;
1557 msg.id = it.second.id;
1558 msg.model_name = it.second.model_spec->name;
1561 msg.error_code = diag_map[it.second.id].error;
1564 msg.voltage = diag_map[it.second.id].voltage / 10.0;
1567 msg.temperature =
static_cast<double>(diag_map[it.second.id].temperature);
1570 diags_msg.diagnostics.push_back(msg);