28 #include <unordered_map>
33 #include "ros/serialization.h"
37 #include "common/model/dxl_command_type_enum.hpp"
38 #include "common/model/end_effector_state.hpp"
39 #include "common/model/hardware_type_enum.hpp"
40 #include "common/model/stepper_calibration_status_enum.hpp"
41 #include "common/model/stepper_motor_state.hpp"
42 #include "common/model/tool_state.hpp"
44 #include "dynamixel_sdk/packet_handler.h"
45 #include "niryo_robot_msgs/CommandStatus.h"
58 #include "ttl_driver/CalibrationStatus.h"
60 using ::std::ostringstream;
62 using ::std::shared_ptr;
64 using ::std::to_string;
67 using ::common::model::ConveyorState;
68 using ::common::model::EHardwareType;
69 using ::common::model::EndEffectorState;
70 using ::common::model::EStepperCalibrationStatus;
71 using ::common::model::HardwareTypeEnum;
72 using ::common::model::JointState;
73 using ::common::model::StepperMotorState;
81 : _nh(
nh), _debug_error_message(
"TtlManager - No connection with TTL motors has been made yet")
83 ROS_DEBUG(
"TtlManager - ctor");
88 ROS_WARN(
"TtlManager - TTL Communication Failed");
111 bool use_simu_gripper{
false };
112 bool use_simu_conveyor{
false };
121 nh.getParam(
"simu_gripper", use_simu_gripper);
122 nh.getParam(
"simu_conveyor", use_simu_conveyor);
129 ROS_DEBUG(
"TtlManager::init - Dxl : set port name (%s), baudrate(%d)",
_device_name.c_str(),
_baudrate);
132 ROS_DEBUG(
"TtlManager::init - Simulation mode: %s, simu_gripper: %s, simu_conveyor: %s",
134 use_simu_conveyor ?
"True" :
"False");
162 auto it_driver =
_driver_map.find(EHardwareType::FAKE_DXL_MOTOR);
165 status = niryo_robot_msgs::CommandStatus::TOOL_FAILURE;
166 message =
"Tool change failed : Real robot mode";
170 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it_driver->second);
173 status = niryo_robot_msgs::CommandStatus::TOOL_ID_INVALID;
174 message =
"Tool change failed : Driver not found";
184 status = niryo_robot_msgs::CommandStatus::TOOL_ID_INVALID;
185 message =
"Tool change failed: Tool ID is invalid";
198 status = niryo_robot_msgs::CommandStatus::SUCCESS;
199 message =
"Tool change succeeded";
203 status = niryo_robot_msgs::CommandStatus::TOOL_NOT_CONNECTED;
204 message =
"Tool change failed: Communication error";
217 int ret = COMM_NOT_AVAILABLE;
219 ROS_DEBUG(
"TtlManager::setupCommunication - initializing connection...");
240 ros::Duration(0.1).sleep();
249 ROS_ERROR(
"TtlManager::setupCommunication - Failed to set baudrate for Dynamixel bus");
256 ROS_ERROR(
"TtlManager::setupCommunication - Failed to open Uart port for Dynamixel bus");
262 ROS_ERROR(
"TtlManager::setupCommunication - Invalid port handler");
276 return niryo_robot_msgs::CommandStatus::FAILURE;
279 EHardwareType hardware_type = state->getHardwareType();
280 uint8_t
id = state->getId();
282 ROS_DEBUG(
"TtlManager::addHardwareComponent : %s", state->str().c_str());
289 ROS_ERROR(
"TtlManager::addHardwareComponent - No driver found for hardware type %d",
290 static_cast<int>(hardware_type));
291 return niryo_robot_msgs::CommandStatus::FAILURE;
293 auto driver = driver_it->second;
295 uint16_t model_number = 0;
297 if (state->getStrictModelNumber() && driver->checkModelNumber(
id, model_number) != COMM_SUCCESS)
299 ROS_WARN(
"TtlManager::addHardwareComponent - Model number check failed for hardware id %d",
id);
300 return niryo_robot_msgs::CommandStatus::HARDWARE_NOT_SUPPORTED;
302 else if (driver->getModelNumber(
id, model_number) != COMM_SUCCESS)
304 ROS_WARN(
"TtlManager::addHardwareComponent - Unable to retrieve model number for hardware id %d",
id);
305 return niryo_robot_msgs::CommandStatus::HARDWARE_NOT_SUPPORTED;
308 state->setModelNumber(model_number);
312 int res = COMM_RX_FAIL;
313 for (
int tries = 10; tries > 0; tries--)
315 res = driver->readFirmwareVersion(
id, version);
316 if (COMM_SUCCESS == res)
318 state->setFirmwareVersion(version);
321 ros::Duration(0.1).sleep();
324 if (COMM_SUCCESS != res)
327 "TtlManager::addHardwareComponent : Unable to retrieve firmware version for "
328 "hardware id %d : result = %d",
336 _ids_map[hardware_type].emplace_back(
id);
339 if (common::model::EComponentType::CONVEYOR == state->getComponentType())
346 if (common::model::EComponentType::JOINT == state->getComponentType())
348 if (!(common::model::EHardwareType::FAKE_STEPPER_MOTOR == hardware_type ||
349 common::model::EHardwareType::FAKE_DXL_MOTOR == hardware_type))
356 return niryo_robot_msgs::CommandStatus::SUCCESS;
365 ROS_DEBUG(
"TtlManager::removeMotor - Remove motor id: %d",
id);
369 EHardwareType type =
_state_map.at(
id)->getHardwareType();
375 ids.erase(std::remove(ids.begin(), ids.end(),
id), ids.end());
400 return (
static_cast<int>(type) <= 7);
416 int ret = COMM_TX_FAIL;
418 if (old_id == new_id)
424 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(
_driver_map.at(motor_type));
428 ret = driver->changeId(old_id, new_id);
429 if (COMM_SUCCESS == ret)
437 std::swap(
_state_map[new_id], i_state->second);
444 if (common::model::EComponentType::CONVEYOR ==
_state_map.at(new_id)->getComponentType())
456 .erase(std::remove(
_ids_map.at(motor_type).begin(),
_ids_map.at(motor_type).end(), old_id),
460 _ids_map.at(motor_type).emplace_back(new_id);
475 ROS_DEBUG(
"TtlManager::scanAndCheck");
476 int result = COMM_PORT_BUSY;
482 for (
int counter = 0; counter < 50 && COMM_SUCCESS != result; ++counter)
485 ROS_DEBUG_COND(COMM_SUCCESS != result,
"TtlManager::scanAndCheck status: %d (counter: %d)", result, counter);
486 ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
489 if (COMM_SUCCESS == result)
493 std::string error_motors_message;
498 uint8_t
id = istate.first;
504 error_motors_message +=
" " + to_string(
id);
505 istate.second->setConnectionStatus(
true);
509 istate.second->setConnectionStatus(
false);
528 _debug_error_message =
"TtlManager - Failed to scan motors, physical bus is too busy. Will retry...";
529 ROS_WARN_THROTTLE(1,
"TtlManager::scanAndCheck - Failed to scan motors, physical bus is too busy");
562 int return_value = COMM_TX_FAIL;
566 EHardwareType type =
_state_map.at(hw_id)->getHardwareType();
567 ROS_DEBUG(
"TtlManager::rebootHardware - Reboot hardware with ID: %d", hw_id);
570 return_value =
_driver_map.at(type)->reboot(hw_id);
571 if (COMM_SUCCESS == return_value)
574 int res = COMM_RX_FAIL;
575 for (
int tries = 10; tries > 0; tries--)
577 res =
_driver_map.at(type)->readFirmwareVersion(hw_id, version);
578 if (COMM_SUCCESS == res)
580 _state_map.at(hw_id)->setFirmwareVersion(version);
583 ros::Duration(0.1).sleep();
586 if (COMM_SUCCESS != res)
589 "TtlManager::addHardwareComponent : Unable to retrieve firmware version for "
590 "hardware id %d : result = %d",
594 ROS_WARN_COND(COMM_SUCCESS != return_value,
"TtlManager::rebootHardware - Failed to reboot hardware: %d",
610 auto hw_type = it.first;
611 auto driver = std::dynamic_pointer_cast<ttl_driver::AbstractMotorDriver>(it.second);
616 vector<uint8_t> ids_list =
_ids_map.at(hw_type);
620 for (
size_t i = 0; i < ids_list.size(); ++i)
622 auto jState_it = std::find_if(jStates.begin(), jStates.end(),
623 [i](
const std::shared_ptr<JointState> &jState) { return i == jState->getId(); });
624 if (jState_it == jStates.end())
628 auto jState = *jState_it;
629 ROS_DEBUG(
"TtlManager::resetTorques - Torque ON on stepper ID: %d",
static_cast<int>(ids_list.at(i)));
630 driver->writeTorquePercentage(ids_list.at(i), jState->getTorquePercentage());
647 uint32_t position = 0;
648 EHardwareType hardware_type = motor_state.getHardwareType();
651 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(
_driver_map.at(hardware_type));
656 if (COMM_SUCCESS == driver->readPosition(motor_state.getId(), position))
666 ROS_ERROR_THROTTLE(1,
"TtlManager::getPosition - motor connection problem - Failed to read from bus");
674 ROS_ERROR_THROTTLE(1,
"TtlManager::getPosition - Driver not found for requested motor id");
682 EHardwareType hw_type(EHardwareType::STEPPER);
683 auto driver = std::dynamic_pointer_cast<ttl_driver::StepperDriver<ttl_driver::StepperReg>>(
_driver_map[hw_type]);
687 vector<uint8_t> ids_list =
_ids_map.at(hw_type);
690 vector<uint32_t> homing_abs_position_list;
693 int res = driver->syncReadHomingAbsPosition(ids_list, homing_abs_position_list);
694 if (COMM_SUCCESS == res)
696 if (ids_list.size() == homing_abs_position_list.size())
699 for (
size_t i = 0; i < ids_list.size(); ++i)
701 uint8_t
id = ids_list.at(i);
705 auto state = std::dynamic_pointer_cast<common::model::StepperMotorState>(
_state_map.at(
id));
708 state->setHomingAbsPosition(
static_cast<uint32_t
>(homing_abs_position_list.at(i)));
712 ROS_ERROR(
"TtlManager::readHomingAbsPosition - null pointer");
718 ROS_ERROR(
"TtlManager::readHomingAbsPosition - No hardware state assossiated to ID: %d",
719 static_cast<int>(
id));
727 "TtlManager::readHomingAbsPosition - size of requested id %d mismatch size of retrieved homing position %d",
728 static_cast<int>(ids_list.size()),
static_cast<int>(homing_abs_position_list.size()));
734 ROS_ERROR(
"TtlManager::readHomingAbsPosition - communication error: %d",
static_cast<int>(res));
741 "TtlManager::readHomingAbsPosition - null pointer or no hardware type in map %d or empty vector of ids: %d",
742 static_cast<int>(
_ids_map.count(hw_type)),
static_cast<int>(
_ids_map.at(hw_type).empty()));
755 uint8_t hw_errors_increment = 0;
762 auto hw_type = it.first;
763 auto driver = std::dynamic_pointer_cast<ttl_driver::AbstractMotorDriver>(it.second);
769 auto id_list_it =
_ids_map.find(hw_type);
774 auto ids_list = id_list_it->second;
776 if (ids_list.empty())
786 if (COMM_SUCCESS == res)
791 for (
size_t i = 0; i < ids_list.size(); ++i)
793 uint8_t
id = ids_list.at(i);
797 auto state = std::dynamic_pointer_cast<common::model::AbstractMotorState>(
_state_map.at(
id));
809 "TtlManager::readJointStatus : Fail to sync read joint state - "
810 "vector mismatch (id_list size %d, position_list size %d)",
811 static_cast<int>(ids_list.size()),
static_cast<int>(
_position_list.size()));
812 hw_errors_increment++;
820 "TtlManager::readJointStatus : Fail to sync read joint state - "
821 "driver fail to syncReadPosition");
822 hw_errors_increment++;
846 hw_errors_increment);
849 if (0 == hw_errors_increment)
858 return (0 == hw_errors_increment);
872 EHardwareType ee_type;
875 ee_type = EHardwareType::FAKE_END_EFFECTOR;
876 else if (
_driver_map.count(EHardwareType::END_EFFECTOR))
877 ee_type = EHardwareType::END_EFFECTOR;
878 else if (
_driver_map.count(EHardwareType::NED3PRO_END_EFFECTOR))
879 ee_type = EHardwareType::NED3PRO_END_EFFECTOR;
883 unsigned int hw_errors_increment = 0;
885 auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(
_driver_map.at(ee_type));
890 uint8_t
id =
_ids_map.at(ee_type).front();
895 auto state = std::dynamic_pointer_cast<EndEffectorState>(
_state_map[
id]);
899 vector<common::model::EActionType> action_list;
903 if (COMM_SUCCESS == driver->syncReadButtonsStatus(
id, action_list))
905 for (uint8_t i = 0; i < action_list.size(); i++)
907 state->setButtonStatus(i, action_list.at(i));
911 if (action_list.at(i) != common::model::EActionType::NO_ACTION)
928 hw_errors_increment++;
933 if (COMM_SUCCESS == driver->readDigitalInput(
id, digital_data))
935 state->setDigitalIn(digital_data);
939 hw_errors_increment++;
947 if (0 == hw_errors_increment)
964 "TtlManager::readEndEffectorStatus - motor connection problem - Failed to read from bus "
965 "(hw_fail_counter_read : %d)",
987 EHardwareType ee_type;
990 ee_type = EHardwareType::FAKE_END_EFFECTOR;
991 else if (
_driver_map.count(EHardwareType::END_EFFECTOR))
992 ee_type = EHardwareType::END_EFFECTOR;
993 else if (
_driver_map.count(EHardwareType::NED3PRO_END_EFFECTOR))
994 ee_type = EHardwareType::NED3PRO_END_EFFECTOR;
998 unsigned int hw_errors_increment = 0;
1000 auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(
_driver_map.at(ee_type));
1005 uint8_t
id =
_ids_map.at(ee_type).front();
1034 hw_errors_increment++;
1045 if (0 == hw_errors_increment)
1071 EHardwareType ee_type;
1074 ee_type = EHardwareType::FAKE_END_EFFECTOR;
1075 else if (
_driver_map.count(EHardwareType::END_EFFECTOR))
1076 ee_type = EHardwareType::END_EFFECTOR;
1077 else if (
_driver_map.count(EHardwareType::NED3PRO_END_EFFECTOR))
1078 ee_type = EHardwareType::NED3PRO_END_EFFECTOR;
1082 auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(
_driver_map.at(ee_type));
1088 uint8_t
id =
_ids_map.at(ee_type).front();
1135 unsigned int hw_errors_increment = 0;
1140 auto type = it.first;
1141 auto driver = it.second;
1146 vector<uint8_t> ids_list =
_ids_map.at(type);
1150 vector<std::pair<double, uint8_t>> hw_data_list;
1152 if (COMM_SUCCESS != driver->syncReadHwStatus(ids_list, hw_data_list))
1155 hw_errors_increment++;
1157 else if (ids_list.size() != hw_data_list.size())
1161 "TtlManager::readHardwareStatusOptimized : syncReadHwStatus failed - "
1162 "vector mistmatch (id_list size %d, hw_data_list size %d)",
1163 static_cast<int>(ids_list.size()),
static_cast<int>(hw_data_list.size()));
1165 hw_errors_increment++;
1169 vector<uint8_t> hw_error_status_list;
1171 if (COMM_SUCCESS != driver->syncReadHwErrorStatus(ids_list, hw_error_status_list))
1173 hw_errors_increment++;
1175 else if (ids_list.size() != hw_error_status_list.size())
1178 "TtlManager::readHardwareStatus : syncReadTemperature failed - "
1179 "vector mistmatch (id_list size %d, hw_status_list size %d)",
1180 static_cast<int>(ids_list.size()),
static_cast<int>(hw_error_status_list.size()));
1182 hw_errors_increment++;
1186 for (
size_t i = 0; i < ids_list.size(); ++i)
1188 uint8_t
id = ids_list.at(i);
1195 if (hw_data_list.size() > i)
1197 double voltage = (hw_data_list.at(i)).first;
1198 uint8_t temperature = (hw_data_list.at(i)).second;
1200 state->setTemperature(temperature);
1201 state->setRawVoltage(voltage);
1205 if (hw_error_status_list.size() > i)
1207 state->setHardwareError(hw_error_status_list.at(i));
1211 string hardware_message = driver->interpretErrorState(state->getHardwareError());
1212 state->setHardwareError(hardware_message);
1222 if (0 == hw_errors_increment)
1237 ROS_ERROR_THROTTLE(1,
1238 "TtlManager::readHardwareStatus - motor connection problem - "
1239 "Failed to read from bus (hw_fail_counter_read : %d)",
1256 uint8_t hw_errors_increment = 0;
1260 if (stepper_joint_driver)
1262 if (hw_type == EHardwareType::STEPPER || hw_type == EHardwareType::FAKE_STEPPER_MOTOR)
1273 vector<uint8_t> id_list =
_ids_map.at(hw_type);
1274 vector<uint8_t> stepper_id_list;
1275 std::copy_if(id_list.begin(), id_list.end(), std::back_inserter(stepper_id_list), [
this](uint8_t
id) {
1276 return _state_map[id] && _state_map.at(id)->getComponentType() != common::model::EComponentType::CONVEYOR;
1292 std::vector<uint8_t> homing_status_list;
1293 if (COMM_SUCCESS == stepper_joint_driver->syncReadHomingStatus(stepper_id_list, homing_status_list))
1295 if (stepper_id_list.size() == homing_status_list.size())
1299 int max_status = -1;
1302 std::ostringstream ss_debug;
1303 ss_debug <<
"homing status : ";
1305 bool still_in_progress =
false;
1308 for (
size_t i = 0; i < homing_status_list.size(); ++i)
1310 uint8_t
id = stepper_id_list.at(i);
1311 ss_debug << static_cast<int>(homing_status_list.at(i)) <<
", ";
1315 EStepperCalibrationStatus status = stepper_joint_driver->interpretHomingData(homing_status_list.at(i));
1318 auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(
id));
1319 if (stepperState && !stepperState->isConveyor())
1321 stepperState->setCalibration(status, 1);
1332 if (0 != max_status && homing_status_list.at(i) > max_status)
1333 max_status = homing_status_list.at(i);
1336 if ((0 == homing_status_list.at(i)) || EStepperCalibrationStatus::IN_PROGRESS == status)
1338 still_in_progress =
true;
1344 ss_debug <<
" => max_status: " <<
static_cast<int>(max_status);
1346 ROS_DEBUG_THROTTLE(2.0,
"TtlManager::readCalibrationStatus : %s", ss_debug.str().c_str());
1361 _calibration_status = stepper_joint_driver->interpretHomingData(
static_cast<uint8_t
>(max_status));
1375 "TtlManager::readCalibrationStatus : syncReadHomingStatus failed - "
1376 "vector mistmatch (id_list size %d, homing_status_list size %d)",
1377 static_cast<int>(stepper_id_list.size()),
static_cast<int>(homing_status_list.size()));
1379 hw_errors_increment++;
1384 hw_errors_increment++;
1388 else if (hw_type == EHardwareType::NED3PRO_STEPPER)
1396 auto conveyor_id = conveyor_state->getId();
1397 auto conveyor_hw_type = conveyor_state->getHardwareType();
1398 auto conveyor_driver =
1399 std::dynamic_pointer_cast<ttl_driver::AbstractStepperDriver>(
_driver_map[conveyor_hw_type]);
1400 int32_t conveyor_speed_percent = 0;
1401 int32_t direction = 0;
1402 if (COMM_SUCCESS == conveyor_driver->readConveyorVelocity(conveyor_id, conveyor_speed_percent, direction))
1404 conveyor_state->setGoalDirection(direction);
1405 conveyor_state->setSpeed(conveyor_speed_percent);
1406 conveyor_state->setState(conveyor_speed_percent);
1410 hw_errors_increment++;
1415 ROS_DEBUG_THROTTLE(2.0,
"TtlManager::readCalibrationStatus: _calibration_status: %s",
1417 ROS_DEBUG_THROTTLE(2.0,
"TtlManager::readCalibrationStatus: _calib_machine_state: %d",
1420 return hw_errors_increment;
1425 uint8_t hw_errors_increment = 0;
1427 EHardwareType hw_type = EHardwareType::NED3PRO_STEPPER;
1438 vector<uint8_t> id_list =
_ids_map.at(hw_type);
1439 vector<uint8_t> stepper_id_list;
1440 std::copy_if(id_list.begin(), id_list.end(), std::back_inserter(stepper_id_list), [
this](uint8_t
id) {
1441 return _state_map[id] && _state_map.at(id)->getComponentType() != common::model::EComponentType::CONVEYOR;
1446 std::vector<uint8_t> homing_status_list;
1447 if (stepper_joint_driver &&
1448 COMM_SUCCESS == stepper_joint_driver->syncReadHomingStatus(stepper_id_list, homing_status_list))
1450 if (stepper_id_list.size() == homing_status_list.size())
1453 ttl_driver::CalibrationStatus calibration_status_msg;
1455 EStepperCalibrationStatus highest_priority_status = EStepperCalibrationStatus::UNINITIALIZED;
1457 for (
size_t i = 0; i < homing_status_list.size(); ++i)
1459 uint8_t
id = stepper_id_list.at(i);
1464 auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(
id));
1465 if (stepperState && !stepperState->isConveyor())
1467 auto status = stepper_joint_driver->interpretHomingData(homing_status_list.at(i));
1468 stepperState->setCalibration(status, 1);
1470 if (status > highest_priority_status)
1471 highest_priority_status = status;
1473 calibration_status_msg.ids.push_back(
id);
1477 case EStepperCalibrationStatus::IN_PROGRESS:
1478 calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATING);
1480 case EStepperCalibrationStatus::OK:
1481 calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATED);
1483 case EStepperCalibrationStatus::FAIL:
1484 calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATION_ERROR);
1487 calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATION_ERROR);
1500 "TtlManager::readCalibrationStatus : syncReadHomingStatus failed - "
1501 "vector mistmatch (id_list size %d, homing_status_list size %d)",
1502 static_cast<int>(stepper_id_list.size()),
static_cast<int>(homing_status_list.size()));
1504 hw_errors_increment++;
1509 hw_errors_increment++;
1513 return hw_errors_increment;
1525 int result = COMM_RX_FAIL;
1530 vector<uint8_t> l_idList;
1532 id_list.insert(id_list.end(), l_idList.begin(), l_idList.end());
1535 for (
auto const &
id : l_idList)
1536 ids_str += to_string(
id) +
" ";
1538 ROS_DEBUG_THROTTLE(1,
"TtlManager::getAllIdsOnTtlBus - Found ids (%s) on bus using default driver",
1541 if (COMM_SUCCESS != result)
1543 if (COMM_RX_TIMEOUT != result)
1546 "TtlManager - No motor found. "
1547 "Make sure that motors are correctly connected and powered on.";
1553 ROS_WARN_THROTTLE(1,
1554 "TtlManager::getAllIdsOnTtlBus - Broadcast ping failed, "
1555 "result : %d (-3001: timeout, -3002: corrupted packet)",
1562 result = COMM_SUCCESS;
1580 int ret = niryo_robot_msgs::CommandStatus::TTL_WRITE_ERROR;
1584 if (mType == EHardwareType::FAKE_DXL_MOTOR)
1585 return niryo_robot_msgs::CommandStatus::SUCCESS;
1588 vector<uint8_t> id_list;
1593 auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(
_driver_map.at(mType));
1597 vector<uint8_t> command_led_value(id_list.size(),
static_cast<uint8_t
>(led));
1598 if (0 <= led && 7 >= led)
1600 int result = COMM_TX_FAIL;
1601 for (
int error_counter = 0; result != COMM_SUCCESS && error_counter < 5; ++error_counter)
1603 ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1604 result = driver->syncWriteLed(id_list, command_led_value);
1607 if (COMM_SUCCESS == result)
1608 ret = niryo_robot_msgs::CommandStatus::SUCCESS;
1610 ROS_WARN(
"TtlManager::setLeds - Failed to write LED");
1615 ROS_DEBUG(
"Set leds failed. Driver is not compatible, check the driver's implementation ");
1616 return niryo_robot_msgs::CommandStatus::FAILURE;
1621 ROS_DEBUG(
"Set leds failed. It is maybe that this service is not support for this product");
1622 ret = niryo_robot_msgs::CommandStatus::SUCCESS;
1638 int result = COMM_TX_FAIL;
1640 "TtlManager::sendCustomCommand:\n"
1641 "\t\t ID: %d, Value: %d, Address: %d, Size: %d",
1642 static_cast<int>(
id), value, reg_address, byte_number);
1646 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1648 if (motor_type == EHardwareType::STEPPER || motor_type == EHardwareType::FAKE_STEPPER_MOTOR)
1650 return niryo_robot_msgs::CommandStatus::SUCCESS;
1655 int32_t value_conv = value;
1657 ->writeCustom(
static_cast<uint16_t
>(reg_address),
static_cast<uint8_t
>(byte_number),
id,
1658 static_cast<uint32_t
>(value_conv));
1659 if (result != COMM_SUCCESS)
1661 ROS_WARN(
"TtlManager::sendCustomCommand - Failed to write custom command: %d", result);
1663 result = niryo_robot_msgs::CommandStatus::TTL_WRITE_ERROR;
1668 ROS_ERROR_THROTTLE(1,
"TtlManager::sendCustomCommand - driver for motor %s not available",
1669 HardwareTypeEnum(motor_type).toString().c_str());
1670 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1675 ROS_ERROR_THROTTLE(1,
"TtlManager::sendCustomCommand - driver for motor id %d unknown",
static_cast<int>(
id));
1676 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1679 ros::Duration(0.005).sleep();
1693 int result = COMM_RX_FAIL;
1694 ROS_DEBUG(
"TtlManager::readCustomCommand: ID: %d, Address: %d, Size: %d",
static_cast<int>(
id),
1695 static_cast<int>(reg_address), byte_number);
1699 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1705 ->readCustom(
static_cast<uint16_t
>(reg_address),
static_cast<uint8_t
>(byte_number),
id, data);
1706 auto data_conv =
static_cast<int32_t
>(data);
1709 if (result != COMM_SUCCESS)
1711 ROS_WARN(
"TtlManager::readCustomCommand - Failed to read custom command: %d", result);
1712 result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1717 ROS_ERROR_THROTTLE(1,
"TtlManager::readCustomCommand - driver for motor %s not available",
1718 HardwareTypeEnum(motor_type).toString().c_str());
1719 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1724 ROS_ERROR_THROTTLE(1,
"TtlManager::readCustomCommand - driver for motor id %d unknown",
static_cast<int>(
id));
1725 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1728 ros::Duration(0.005).sleep();
1745 uint16_t &vel_p_gain, uint16_t &vel_i_gain, uint16_t &ff1_gain, uint16_t &ff2_gain)
1747 int result = COMM_RX_FAIL;
1751 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1755 auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(
_driver_map.at(motor_type));
1758 std::vector<uint16_t> data;
1759 result = driver->readPID(
id, data);
1761 if (COMM_SUCCESS == result)
1763 pos_p_gain = data.at(0);
1764 pos_i_gain = data.at(1);
1765 pos_d_gain = data.at(2);
1766 vel_p_gain = data.at(3);
1767 vel_i_gain = data.at(4);
1768 ff1_gain = data.at(5);
1769 ff2_gain = data.at(6);
1773 ROS_WARN(
"TtlManager::readMotorPID - Failed to read PID: %d", result);
1774 result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1781 ROS_ERROR_THROTTLE(1,
"TtlManager::readMotorPID - driver for motor %s not available",
1782 HardwareTypeEnum(motor_type).toString().c_str());
1783 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1788 ROS_ERROR_THROTTLE(1,
"TtlManager::readMotorPID - driver for motor id %d unknown",
static_cast<int>(
id));
1789 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1792 ros::Duration(0.005).sleep();
1810 uint32_t &v_max, uint32_t &d_max, uint32_t &d_1, uint32_t &v_stop)
1812 int result = COMM_RX_FAIL;
1816 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1818 if (joint_stepper_driver)
1820 std::vector<uint32_t> data;
1821 result = joint_stepper_driver->readVelocityProfile(
id, data);
1823 if (COMM_SUCCESS == result)
1825 v_start = data.at(0);
1832 v_stop = data.at(7);
1836 ROS_WARN(
"TtlManager::readVelocityProfile - Failed to read velocity profile: %d", result);
1837 result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1843 ROS_ERROR_THROTTLE(1,
"TtlManager::readVelocityProfile - driver for motor %s not available",
1844 HardwareTypeEnum(motor_type).toString().c_str());
1845 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1850 ROS_ERROR_THROTTLE(1,
"TtlManager::readVelocityProfile - driver for motor id %d unknown",
static_cast<int>(
id));
1851 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1854 ros::Duration(0.005).sleep();
1866 int result = COMM_RX_FAIL;
1870 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1873 if (
_driver_map.count(motor_type) && (motor_type == EHardwareType::XL330 || motor_type == EHardwareType::XL320 ||
1874 motor_type == EHardwareType::FAKE_DXL_MOTOR))
1876 auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(
_driver_map.at(motor_type));
1879 result = driver->readMoving(
id, status);
1884 ROS_ERROR_THROTTLE(1,
"TtlManager::readMoving - register MOVING for motor %s not available",
1885 HardwareTypeEnum(motor_type).toString().c_str());
1886 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1891 ROS_ERROR_THROTTLE(1,
"TtlManager::readMoving - driver for motor id %d unknown",
static_cast<int>(
id));
1892 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1895 ros::Duration(0.005).sleep();
1907 int result = COMM_RX_FAIL;
1911 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1915 auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(
_driver_map.at(motor_type));
1918 result = driver->readControlMode(
id, control_mode);
1923 ROS_ERROR_THROTTLE(1,
"TtlManager::readControlMode - driver for motor %s not available",
1924 HardwareTypeEnum(motor_type).toString().c_str());
1925 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1930 ROS_ERROR_THROTTLE(1,
"TtlManager::readControlMode - driver for motor id %d unknown",
static_cast<int>(
id));
1931 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1934 ros::Duration(0.005).sleep();
1945 int result = COMM_TX_ERROR;
1946 ROS_DEBUG_THROTTLE(0.5,
"TtlManager::writeSynchronizeCommand: %s", cmd->str().c_str());
1950 std::set<EHardwareType> typesToProcess = cmd->getMotorTypes();
1955 ROS_DEBUG_THROTTLE(0.5,
"TtlManager::writeSynchronizeCommand: try to sync write (counter %d)", counter);
1959 if (typesToProcess.count(it.first) != 0)
1961 result = COMM_TX_ERROR;
1964 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it.second);
1967 result = driver->writeSyncCmd(cmd->getCmdType(), cmd->getMotorsId(it.first), cmd->getParams(it.first));
1969 ros::Duration(0.05).sleep();
1973 if (COMM_SUCCESS == result)
1975 typesToProcess.erase(typesToProcess.find(it.first));
1979 ROS_ERROR(
"TtlManager::writeSynchronizeCommand : unable to sync write function : %d", result);
1985 if (typesToProcess.empty())
1987 result = COMM_SUCCESS;
1991 ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1996 ROS_ERROR(
"TtlManager::writeSynchronizeCommand - Invalid command");
1999 if (COMM_SUCCESS != result)
2001 ROS_ERROR_THROTTLE(0.5,
"TtlManager::writeSynchronizeCommand - Failed to write synchronize position");
2015 int result = COMM_TX_ERROR;
2017 uint8_t
id = cmd->getId();
2023 ROS_DEBUG(
"TtlManager::writeSingleCommand: %s", cmd->str().c_str());
2028 while ((COMM_SUCCESS != result) && (counter < 50))
2030 EHardwareType hardware_type = state->getHardwareType();
2031 result = COMM_TX_ERROR;
2036 result =
_driver_map.at(hardware_type)->writeSingleCmd(cmd);
2041 ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
2047 "TtlManager::writeSingleCommand: command is sent to a removed hardware component. Skipped or write to a "
2049 result = COMM_TX_ERROR;
2053 if (result != COMM_SUCCESS)
2055 ROS_WARN(
"TtlManager::writeSingleCommand - Fail to write single command : %s", cmd->str().c_str());
2073 for (
auto const &cmd : cmd_vec)
2083 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it.second);
2088 if (err != COMM_SUCCESS)
2090 ROS_WARN(
"TtlManager::executeJointTrajectoryCmd - Failed to write position");
2106 ROS_DEBUG(
"TtlManager::startCalibration: starting...");
2108 std::vector<uint8_t> stepper_list;
2109 if (
_ids_map.count(EHardwareType::STEPPER))
2113 stepper_list =
_ids_map.at(EHardwareType::STEPPER);
2115 else if (
_ids_map.count(EHardwareType::NED3PRO_STEPPER))
2117 stepper_list =
_ids_map.at(EHardwareType::NED3PRO_STEPPER);
2119 else if (
_ids_map.count(EHardwareType::FAKE_STEPPER_MOTOR))
2123 stepper_list =
_ids_map.at(EHardwareType::FAKE_STEPPER_MOTOR);
2126 for (
auto const &
id : stepper_list)
2130 auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(
id));
2132 if (stepperState && !stepperState->isConveyor())
2134 stepperState->setCalibration(EStepperCalibrationStatus::IN_PROGRESS, 1);
2145 ROS_INFO(
"TtlManager::resetCalibration: reseting...");
2147 std::vector<uint8_t> stepper_list;
2148 if (
_ids_map.count(EHardwareType::STEPPER))
2152 stepper_list =
_ids_map.at(EHardwareType::STEPPER);
2154 else if (
_ids_map.count(EHardwareType::NED3PRO_STEPPER))
2155 stepper_list =
_ids_map.at(EHardwareType::NED3PRO_STEPPER);
2157 for (
auto const id : stepper_list)
2161 auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(
id));
2163 if (stepperState && !stepperState->isConveyor())
2165 stepperState->setCalibration(EStepperCalibrationStatus::UNINITIALIZED, 1);
2179 throw std::out_of_range(
"TtlManager::getMotorsState: Unknown motor id");
2181 return std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(motor_id))->getCalibrationValue();
2207 std::vector<std::shared_ptr<JointState>> states;
2211 if (it.second && it.second->getComponentType() == common::model::EComponentType::JOINT)
2213 states.emplace_back(std::dynamic_pointer_cast<JointState>(it.second));
2222 std::vector<std::shared_ptr<ConveyorState>> conveyor_states;
2225 if (it.second && it.second->getComponentType() == common::model::EComponentType::CONVEYOR)
2227 conveyor_states.emplace_back(std::dynamic_pointer_cast<ConveyorState>(it.second));
2231 return conveyor_states;
2242 throw std::out_of_range(
"TtlManager::getMotorsState: Unknown motor id");
2260 switch (hardware_type)
2262 case EHardwareType::STEPPER:
2266 case EHardwareType::NED3PRO_STEPPER:
2270 case EHardwareType::FAKE_STEPPER_MOTOR:
2273 case EHardwareType::XL430:
2277 case EHardwareType::XC430:
2281 case EHardwareType::XM430:
2285 case EHardwareType::XL320:
2289 case EHardwareType::XL330:
2293 case EHardwareType::XH430:
2297 case EHardwareType::FAKE_DXL_MOTOR:
2300 case EHardwareType::END_EFFECTOR:
2304 case EHardwareType::NED3PRO_END_EFFECTOR:
2309 case EHardwareType::FAKE_END_EFFECTOR:
2310 _driver_map.insert(std::make_pair(hardware_type, std::make_shared<MockEndEffectorDriver>(
_fake_data)));
2313 ROS_ERROR(
"TtlManager - Unable to instanciate driver, unknown type");
2324 _fake_data = std::make_shared<FakeTtlData>();
2326 if (
_nh.hasParam(
"fake_params"))
2328 std::vector<int> full_id_list;
2329 if (
_nh.hasParam(
"fake_params/id_list"))
2330 _nh.getParam(
"fake_params/id_list", full_id_list);
2331 for (
auto id : full_id_list)
2332 _fake_data->full_id_list.emplace_back(
static_cast<uint8_t
>(
id));
2334 if (
_nh.hasParam(
"fake_params/steppers"))
2336 std::string current_ns =
"fake_params/steppers/";
2340 if (
_nh.hasParam(
"fake_params/dynamixels/"))
2342 std::string current_ns =
"fake_params/dynamixels/";
2346 if (use_simu_gripper &&
_nh.hasParam(
"fake_params/tool/"))
2348 std::string current_ns =
"fake_params/tool/";
2352 if (
_nh.hasParam(
"fake_params/end_effector"))
2354 string current_ns =
"fake_params/end_effector/";
2355 vector<int> id_list, temperature_list, voltage_list;
2356 vector<string> firmware_list;
2357 _nh.getParam(current_ns +
"id", id_list);
2358 _nh.getParam(current_ns +
"temperature", temperature_list);
2359 _nh.getParam(current_ns +
"voltage", voltage_list);
2360 _nh.getParam(current_ns +
"firmware", firmware_list);
2362 assert(!id_list.empty());
2363 assert(!temperature_list.empty());
2364 assert(!voltage_list.empty());
2365 assert(!firmware_list.empty());
2367 _fake_data->end_effector.id =
static_cast<uint8_t
>(id_list.at(0));
2368 _fake_data->end_effector.temperature =
static_cast<uint8_t
>(temperature_list.at(0));
2369 _fake_data->end_effector.voltage =
static_cast<double>(voltage_list.at(0));
2371 _fake_data->end_effector.firmware = firmware_list.at(0);
2374 if (use_simu_conveyor &&
_nh.hasParam(
"fake_params/conveyors/"))
2376 std::string current_ns =
"fake_params/conveyors/";
2392 auto some_joint_state_it =
2393 std::find_if(joint_states.begin(), joint_states.end(),
2394 [](
const std::shared_ptr<JointState> &joint_state) { return joint_state->isStepper(); });
2395 if (some_joint_state_it == joint_states.end())
2399 auto some_joint_state = *some_joint_state_it;
2400 auto hardware_type = some_joint_state->getHardwareType();
2401 return { .driver = std::dynamic_pointer_cast<AbstractStepperDriver>(
_driver_map.at(hardware_type)),
2402 .hardware_type = hardware_type };