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"
45 #include "dynamixel_sdk/packet_handler.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::EHardwareType;
68 using ::common::model::EndEffectorState;
69 using ::common::model::EStepperCalibrationStatus;
70 using ::common::model::HardwareTypeEnum;
71 using ::common::model::JointState;
72 using ::common::model::StepperMotorState;
73 using ::common::model::ConveyorState;
80 TtlManager::TtlManager(ros::NodeHandle &
nh) : _nh(
nh), _debug_error_message(
"TtlManager - No connection with TTL motors has been made yet")
82 ROS_DEBUG(
"TtlManager - ctor");
87 ROS_WARN(
"TtlManager - TTL Communication Failed");
110 bool use_simu_gripper{
false};
111 bool use_simu_conveyor{
false};
118 nh.getParam(
"simu_gripper", use_simu_gripper);
119 nh.getParam(
"simu_conveyor", use_simu_conveyor);
121 ROS_DEBUG(
"TtlManager::init - Dxl : set port name (%s), baudrate(%d)",
_device_name.c_str(),
_baudrate);
124 ROS_DEBUG(
"TtlManager::init - Simulation mode: %s, simu_gripper: %s, simu_conveyor: %s",
_simulation_mode ?
"True" :
"False", use_simu_gripper ?
"True" :
"False",
125 use_simu_conveyor ?
"True" :
"False");
152 int ret = COMM_NOT_AVAILABLE;
154 ROS_DEBUG(
"TtlManager::setupCommunication - initializing connection...");
175 ros::Duration(0.1).sleep();
184 ROS_ERROR(
"TtlManager::setupCommunication - Failed to set baudrate for Dynamixel bus");
191 ROS_ERROR(
"TtlManager::setupCommunication - Failed to open Uart port for Dynamixel bus");
197 ROS_ERROR(
"TtlManager::setupCommunication - Invalid port handler");
211 return niryo_robot_msgs::CommandStatus::FAILURE;
214 EHardwareType hardware_type = state->getHardwareType();
215 uint8_t
id = state->getId();
217 ROS_DEBUG(
"TtlManager::addHardwareComponent : %s", state->str().c_str());
224 ROS_ERROR(
"TtlManager::addHardwareComponent - No driver found for hardware type %d",
static_cast<int>(hardware_type));
225 return niryo_robot_msgs::CommandStatus::FAILURE;
227 auto driver = driver_it->second;
229 uint16_t model_number = 0;
231 if (state->getStrictModelNumber() && driver->checkModelNumber(
id, model_number) != COMM_SUCCESS)
233 ROS_WARN(
"TtlManager::addHardwareComponent - Model number check failed for hardware id %d",
id);
234 return niryo_robot_msgs::CommandStatus::HARDWARE_NOT_SUPPORTED;
236 else if (driver->getModelNumber(
id, model_number) != COMM_SUCCESS)
238 ROS_WARN(
"TtlManager::addHardwareComponent - Unable to retrieve model number for hardware id %d",
id);
239 return niryo_robot_msgs::CommandStatus::HARDWARE_NOT_SUPPORTED;
242 state->setModelNumber(model_number);
246 int res = COMM_RX_FAIL;
247 for (
int tries = 10; tries > 0; tries--)
249 res = driver->readFirmwareVersion(
id, version);
250 if (COMM_SUCCESS == res)
252 state->setFirmwareVersion(version);
255 ros::Duration(0.1).sleep();
258 if (COMM_SUCCESS != res)
260 ROS_WARN(
"TtlManager::addHardwareComponent : Unable to retrieve firmware version for "
261 "hardware id %d : result = %d",
269 _ids_map[hardware_type].emplace_back(
id);
272 if (common::model::EComponentType::CONVEYOR == state->getComponentType())
279 if (common::model::EComponentType::JOINT == state->getComponentType())
281 if (!(common::model::EHardwareType::FAKE_STEPPER_MOTOR == hardware_type
282 || common::model::EHardwareType::FAKE_DXL_MOTOR == hardware_type))
289 return niryo_robot_msgs::CommandStatus::SUCCESS;
298 ROS_DEBUG(
"TtlManager::removeMotor - Remove motor id: %d",
id);
302 EHardwareType type =
_state_map.at(
id)->getHardwareType();
308 ids.erase(std::remove(ids.begin(), ids.end(),
id), ids.end());
332 return (
static_cast<int>(type) <= 7);
348 int ret = COMM_TX_FAIL;
350 if (old_id == new_id)
356 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(
_driver_map.at(motor_type));
360 ret = driver->changeId(old_id, new_id);
361 if (COMM_SUCCESS == ret)
369 std::swap(
_state_map[new_id], i_state->second);
376 if (common::model::EComponentType::CONVEYOR ==
_state_map.at(new_id)->getComponentType())
390 _ids_map.at(motor_type).emplace_back(new_id);
405 ROS_DEBUG(
"TtlManager::scanAndCheck");
406 int result = COMM_PORT_BUSY;
412 for (
int counter = 0; counter < 50 && COMM_SUCCESS != result; ++counter)
415 ROS_DEBUG_COND(COMM_SUCCESS != result,
"TtlManager::scanAndCheck status: %d (counter: %d)", result, counter);
416 ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
419 if (COMM_SUCCESS == result)
423 std::string error_motors_message;
428 uint8_t
id = istate.first;
434 error_motors_message +=
" " + to_string(
id);
435 istate.second->setConnectionStatus(
true);
439 istate.second->setConnectionStatus(
false);
458 _debug_error_message =
"TtlManager - Failed to scan motors, physical bus is too busy. Will retry...";
459 ROS_WARN_THROTTLE(1,
"TtlManager::scanAndCheck - Failed to scan motors, physical bus is too busy");
492 int return_value = COMM_TX_FAIL;
496 EHardwareType type =
_state_map.at(hw_id)->getHardwareType();
497 ROS_DEBUG(
"TtlManager::rebootHardware - Reboot hardware with ID: %d", hw_id);
500 return_value =
_driver_map.at(type)->reboot(hw_id);
501 if (COMM_SUCCESS == return_value)
504 int res = COMM_RX_FAIL;
505 for (
int tries = 10; tries > 0; tries--)
507 res =
_driver_map.at(type)->readFirmwareVersion(hw_id, version);
508 if (COMM_SUCCESS == res)
510 _state_map.at(hw_id)->setFirmwareVersion(version);
513 ros::Duration(0.1).sleep();
516 if (COMM_SUCCESS != res)
518 ROS_WARN(
"TtlManager::addHardwareComponent : Unable to retrieve firmware version for "
519 "hardware id %d : result = %d",
523 ROS_WARN_COND(COMM_SUCCESS != return_value,
"TtlManager::rebootHardware - Failed to reboot hardware: %d", return_value);
538 auto hw_type = it.first;
539 auto driver = std::dynamic_pointer_cast<ttl_driver::AbstractMotorDriver>(it.second);
544 vector<uint8_t> ids_list =
_ids_map.at(hw_type);
548 for (
size_t i = 0; i < ids_list.size(); ++i)
550 auto jState_it = std::find_if(jStates.begin(), jStates.end(), [i](
const std::shared_ptr<JointState> &jState){
551 return i == jState->getId();
553 if (jState_it == jStates.end())
557 auto jState = *jState_it;
558 ROS_DEBUG(
"TtlManager::resetTorques - Torque ON on stepper ID: %d",
static_cast<int>(ids_list.at(i)));
559 driver->writeTorquePercentage(ids_list.at(i), jState->getTorquePercentage());
576 uint32_t position = 0;
577 EHardwareType hardware_type = motor_state.getHardwareType();
580 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(
_driver_map.at(hardware_type));
585 if (COMM_SUCCESS == driver->readPosition(motor_state.getId(), position))
595 ROS_ERROR_THROTTLE(1,
"TtlManager::getPosition - motor connection problem - Failed to read from bus");
603 ROS_ERROR_THROTTLE(1,
"TtlManager::getPosition - Driver not found for requested motor id");
611 EHardwareType hw_type(EHardwareType::STEPPER);
612 auto driver = std::dynamic_pointer_cast<ttl_driver::StepperDriver<ttl_driver::StepperReg>>(
_driver_map[hw_type]);
616 vector<uint8_t> ids_list =
_ids_map.at(hw_type);
619 vector<uint32_t> homing_abs_position_list;
622 int res = driver->syncReadHomingAbsPosition(ids_list, homing_abs_position_list);
623 if (COMM_SUCCESS == res)
625 if (ids_list.size() == homing_abs_position_list.size())
628 for (
size_t i = 0; i < ids_list.size(); ++i)
630 uint8_t
id = ids_list.at(i);
634 auto state = std::dynamic_pointer_cast<common::model::StepperMotorState>(
_state_map.at(
id));
637 state->setHomingAbsPosition(
static_cast<uint32_t
>(homing_abs_position_list.at(i)));
641 ROS_ERROR(
"TtlManager::readHomingAbsPosition - null pointer");
647 ROS_ERROR(
"TtlManager::readHomingAbsPosition - No hardware state assossiated to ID: %d",
static_cast<int>(
id));
654 ROS_ERROR(
"TtlManager::readHomingAbsPosition - size of requested id %d mismatch size of retrieved homing position %d",
static_cast<int>(ids_list.size()),
655 static_cast<int>(homing_abs_position_list.size()));
661 ROS_ERROR(
"TtlManager::readHomingAbsPosition - communication error: %d",
static_cast<int>(res));
667 ROS_ERROR(
"TtlManager::readHomingAbsPosition - null pointer or no hardware type in map %d or empty vector of ids: %d",
static_cast<int>(
_ids_map.count(hw_type)),
668 static_cast<int>(
_ids_map.at(hw_type).empty()));
681 uint8_t hw_errors_increment = 0;
688 auto hw_type = it.first;
689 auto driver = std::dynamic_pointer_cast<ttl_driver::AbstractMotorDriver>(it.second);
695 auto id_list_it =
_ids_map.find(hw_type);
700 auto ids_list = id_list_it->second;
702 if (ids_list.empty())
712 if (COMM_SUCCESS == res)
717 for (
size_t i = 0; i < ids_list.size(); ++i)
719 uint8_t
id = ids_list.at(i);
723 auto state = std::dynamic_pointer_cast<common::model::AbstractMotorState>(
_state_map.at(
id));
734 ROS_WARN(
"TtlManager::readJointStatus : Fail to sync read joint state - "
735 "vector mismatch (id_list size %d, position_list size %d)",
736 static_cast<int>(ids_list.size()),
static_cast<int>(
_position_list.size()));
737 hw_errors_increment++;
744 ROS_DEBUG(
"TtlManager::readJointStatus : Fail to sync read joint state - "
745 "driver fail to syncReadPosition");
746 hw_errors_increment++;
769 ROS_DEBUG_THROTTLE(2,
"_hw_fail_counter_read, hw_errors_increment: %d, %d",
_hw_fail_counter_read, hw_errors_increment);
772 if (0 == hw_errors_increment)
781 return (0 == hw_errors_increment);
795 EHardwareType ee_type;
798 ee_type = EHardwareType::FAKE_END_EFFECTOR;
799 else if (
_driver_map.count(EHardwareType::END_EFFECTOR))
800 ee_type = EHardwareType::END_EFFECTOR;
801 else if (
_driver_map.count(EHardwareType::NED3PRO_END_EFFECTOR))
802 ee_type = EHardwareType::NED3PRO_END_EFFECTOR;
807 unsigned int hw_errors_increment = 0;
809 auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(
_driver_map.at(ee_type));
814 uint8_t
id =
_ids_map.at(ee_type).front();
819 auto state = std::dynamic_pointer_cast<EndEffectorState>(
_state_map[
id]);
823 vector<common::model::EActionType> action_list;
827 if (COMM_SUCCESS == driver->syncReadButtonsStatus(
id, action_list))
829 for (uint8_t i = 0; i < action_list.size(); i++)
831 state->setButtonStatus(i, action_list.at(i));
834 if (action_list.at(i) != common::model::EActionType::NO_ACTION)
850 hw_errors_increment++;
855 if (COMM_SUCCESS == driver->readDigitalInput(
id, digital_data))
857 state->setDigitalIn(digital_data);
861 hw_errors_increment++;
869 if (0 == hw_errors_increment)
884 ROS_ERROR(
"TtlManager::readEndEffectorStatus - motor connection problem - Failed to read from bus (hw_fail_counter_read : %d)",
_end_effector_fail_counter_read);
905 EHardwareType ee_type;
908 ee_type = EHardwareType::FAKE_END_EFFECTOR;
909 else if (
_driver_map.count(EHardwareType::END_EFFECTOR))
910 ee_type = EHardwareType::END_EFFECTOR;
911 else if (
_driver_map.count(EHardwareType::NED3PRO_END_EFFECTOR))
912 ee_type = EHardwareType::NED3PRO_END_EFFECTOR;
916 unsigned int hw_errors_increment = 0;
918 auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(
_driver_map.at(ee_type));
923 uint8_t
id =
_ids_map.at(ee_type).front();
952 hw_errors_increment++;
963 if (0 == hw_errors_increment)
988 EHardwareType ee_type;
991 ee_type = EHardwareType::FAKE_END_EFFECTOR;
992 else if (
_driver_map.count(EHardwareType::END_EFFECTOR))
993 ee_type = EHardwareType::END_EFFECTOR;
994 else if (
_driver_map.count(EHardwareType::NED3PRO_END_EFFECTOR))
995 ee_type = EHardwareType::NED3PRO_END_EFFECTOR;
999 auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(
_driver_map.at(ee_type));
1005 uint8_t
id =
_ids_map.at(ee_type).front();
1052 unsigned int hw_errors_increment = 0;
1057 auto type = it.first;
1058 auto driver = it.second;
1063 vector<uint8_t> ids_list =
_ids_map.at(type);
1067 vector<std::pair<double, uint8_t>> hw_data_list;
1069 if (COMM_SUCCESS != driver->syncReadHwStatus(ids_list, hw_data_list))
1072 hw_errors_increment++;
1074 else if (ids_list.size() != hw_data_list.size())
1077 ROS_ERROR(
"TtlManager::readHardwareStatusOptimized : syncReadHwStatus failed - "
1078 "vector mistmatch (id_list size %d, hw_data_list size %d)",
1079 static_cast<int>(ids_list.size()),
static_cast<int>(hw_data_list.size()));
1081 hw_errors_increment++;
1085 vector<uint8_t> hw_error_status_list;
1087 if (COMM_SUCCESS != driver->syncReadHwErrorStatus(ids_list, hw_error_status_list))
1089 hw_errors_increment++;
1091 else if (ids_list.size() != hw_error_status_list.size())
1093 ROS_ERROR(
"TtlManager::readHardwareStatus : syncReadTemperature failed - "
1094 "vector mistmatch (id_list size %d, hw_status_list size %d)",
1095 static_cast<int>(ids_list.size()),
static_cast<int>(hw_error_status_list.size()));
1097 hw_errors_increment++;
1101 for (
size_t i = 0; i < ids_list.size(); ++i)
1103 uint8_t
id = ids_list.at(i);
1110 if (hw_data_list.size() > i)
1112 double voltage = (hw_data_list.at(i)).first;
1113 uint8_t temperature = (hw_data_list.at(i)).second;
1115 state->setTemperature(temperature);
1116 state->setRawVoltage(voltage);
1120 if (hw_error_status_list.size() > i)
1122 state->setHardwareError(hw_error_status_list.at(i));
1126 string hardware_message = driver->interpretErrorState(state->getHardwareError());
1127 state->setHardwareError(hardware_message);
1137 if (0 == hw_errors_increment)
1152 ROS_ERROR_THROTTLE(1,
1153 "TtlManager::readHardwareStatus - motor connection problem - "
1154 "Failed to read from bus (hw_fail_counter_read : %d)",
1171 uint8_t hw_errors_increment = 0;
1175 if (stepper_joint_driver)
1177 if (hw_type == EHardwareType::STEPPER || hw_type == EHardwareType::FAKE_STEPPER_MOTOR )
1188 vector<uint8_t> id_list =
_ids_map.at(hw_type);
1189 vector<uint8_t> stepper_id_list;
1190 std::copy_if(id_list.begin(), id_list.end(), std::back_inserter(stepper_id_list),
1191 [
this](uint8_t
id) { return _state_map[id] && _state_map.at(id)->getComponentType() != common::model::EComponentType::CONVEYOR; });
1206 std::vector<uint8_t> homing_status_list;
1207 if (COMM_SUCCESS == stepper_joint_driver->syncReadHomingStatus(stepper_id_list, homing_status_list))
1209 if (stepper_id_list.size() == homing_status_list.size())
1212 int max_status = -1;
1215 std::ostringstream ss_debug;
1216 ss_debug <<
"homing status : ";
1218 bool still_in_progress =
false;
1221 for (
size_t i = 0; i < homing_status_list.size(); ++i)
1223 uint8_t
id = stepper_id_list.at(i);
1224 ss_debug << static_cast<int>(homing_status_list.at(i)) <<
", ";
1228 EStepperCalibrationStatus status = stepper_joint_driver->interpretHomingData(homing_status_list.at(i));
1231 auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(
id));
1232 if (stepperState && !stepperState->isConveyor())
1234 stepperState->setCalibration(status, 1);
1245 if (0 != max_status && homing_status_list.at(i) > max_status)
1246 max_status = homing_status_list.at(i);
1249 if ((0 == homing_status_list.at(i)) || EStepperCalibrationStatus::IN_PROGRESS == status)
1251 still_in_progress =
true;
1257 ss_debug <<
" => max_status: " <<
static_cast<int>(max_status);
1259 ROS_DEBUG_THROTTLE(2.0,
"TtlManager::readCalibrationStatus : %s", ss_debug.str().c_str());
1274 _calibration_status = stepper_joint_driver->interpretHomingData(
static_cast<uint8_t
>(max_status));
1287 ROS_ERROR(
"TtlManager::readCalibrationStatus : syncReadHomingStatus failed - "
1288 "vector mistmatch (id_list size %d, homing_status_list size %d)",
1289 static_cast<int>(stepper_id_list.size()),
static_cast<int>(homing_status_list.size()));
1291 hw_errors_increment++;
1296 hw_errors_increment++;
1300 else if (hw_type == EHardwareType::NED3PRO_STEPPER)
1308 auto conveyor_id = conveyor_state->getId();
1309 auto conveyor_hw_type = conveyor_state->getHardwareType();
1310 auto conveyor_driver = std::dynamic_pointer_cast<ttl_driver::AbstractStepperDriver>(
_driver_map[conveyor_hw_type]);
1311 int32_t conveyor_speed_percent = 0;
1312 int32_t direction = 0;
1313 if (COMM_SUCCESS == conveyor_driver->readConveyorVelocity(conveyor_id, conveyor_speed_percent, direction))
1315 conveyor_state->setGoalDirection(direction);
1316 conveyor_state->setSpeed(conveyor_speed_percent);
1317 conveyor_state->setState(conveyor_speed_percent);
1321 hw_errors_increment++;
1326 ROS_DEBUG_THROTTLE(2.0,
"TtlManager::readCalibrationStatus: _calibration_status: %s", common::model::StepperCalibrationStatusEnum(
_calibration_status).toString().c_str());
1327 ROS_DEBUG_THROTTLE(2.0,
"TtlManager::readCalibrationStatus: _calib_machine_state: %d",
static_cast<int>(
_calib_machine_state.
status()));
1329 return hw_errors_increment;
1334 uint8_t hw_errors_increment = 0;
1336 EHardwareType hw_type = EHardwareType::NED3PRO_STEPPER;
1347 vector<uint8_t> id_list =
_ids_map.at(hw_type);
1348 vector<uint8_t> stepper_id_list;
1349 std::copy_if(id_list.begin(), id_list.end(), std::back_inserter(stepper_id_list), [
this](uint8_t
id) {
1350 return _state_map[id] &&
1351 _state_map.at(id)->getComponentType() != common::model::EComponentType::CONVEYOR;
1356 std::vector<uint8_t> homing_status_list;
1357 if (stepper_joint_driver &&
1358 COMM_SUCCESS == stepper_joint_driver->syncReadHomingStatus(stepper_id_list, homing_status_list))
1360 if (stepper_id_list.size() == homing_status_list.size())
1363 ttl_driver::CalibrationStatus calibration_status_msg;
1365 EStepperCalibrationStatus highest_priority_status = EStepperCalibrationStatus::UNINITIALIZED;
1367 for (
size_t i = 0; i < homing_status_list.size(); ++i)
1369 uint8_t
id = stepper_id_list.at(i);
1374 auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(
id));
1375 if (stepperState && !stepperState->isConveyor())
1377 auto status = stepper_joint_driver->interpretHomingData(homing_status_list.at(i));
1378 stepperState->setCalibration(status, 1);
1380 if (status > highest_priority_status)
1381 highest_priority_status = status;
1383 calibration_status_msg.ids.push_back(
id);
1387 case EStepperCalibrationStatus::IN_PROGRESS:
1388 calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATING);
1390 case EStepperCalibrationStatus::OK:
1391 calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATED);
1393 case EStepperCalibrationStatus::FAIL:
1394 calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATION_ERROR);
1397 calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATION_ERROR);
1409 ROS_ERROR(
"TtlManager::readCalibrationStatus : syncReadHomingStatus failed - "
1410 "vector mistmatch (id_list size %d, homing_status_list size %d)",
1411 static_cast<int>(stepper_id_list.size()),
static_cast<int>(homing_status_list.size()));
1413 hw_errors_increment++;
1418 hw_errors_increment++;
1422 return hw_errors_increment;
1434 int result = COMM_RX_FAIL;
1439 vector<uint8_t> l_idList;
1441 id_list.insert(id_list.end(), l_idList.begin(), l_idList.end());
1444 for (
auto const &
id : l_idList)
1445 ids_str += to_string(
id) +
" ";
1447 ROS_DEBUG_THROTTLE(1,
"TtlManager::getAllIdsOnTtlBus - Found ids (%s) on bus using default driver", ids_str.c_str());
1449 if (COMM_SUCCESS != result)
1451 if (COMM_RX_TIMEOUT != result)
1454 "Make sure that motors are correctly connected and powered on.";
1460 ROS_WARN_THROTTLE(1,
1461 "TtlManager::getAllIdsOnTtlBus - Broadcast ping failed, "
1462 "result : %d (-3001: timeout, -3002: corrupted packet)",
1469 result = COMM_SUCCESS;
1487 int ret = niryo_robot_msgs::CommandStatus::TTL_WRITE_ERROR;
1491 if (mType == EHardwareType::FAKE_DXL_MOTOR)
1492 return niryo_robot_msgs::CommandStatus::SUCCESS;
1495 vector<uint8_t> id_list;
1500 auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(
_driver_map.at(mType));
1504 vector<uint8_t> command_led_value(id_list.size(),
static_cast<uint8_t
>(led));
1505 if (0 <= led && 7 >= led)
1507 int result = COMM_TX_FAIL;
1508 for (
int error_counter = 0; result != COMM_SUCCESS && error_counter < 5; ++error_counter)
1510 ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1511 result = driver->syncWriteLed(id_list, command_led_value);
1514 if (COMM_SUCCESS == result)
1515 ret = niryo_robot_msgs::CommandStatus::SUCCESS;
1517 ROS_WARN(
"TtlManager::setLeds - Failed to write LED");
1522 ROS_DEBUG(
"Set leds failed. Driver is not compatible, check the driver's implementation ");
1523 return niryo_robot_msgs::CommandStatus::FAILURE;
1528 ROS_DEBUG(
"Set leds failed. It is maybe that this service is not support for this product");
1529 ret = niryo_robot_msgs::CommandStatus::SUCCESS;
1545 int result = COMM_TX_FAIL;
1546 ROS_DEBUG(
"TtlManager::sendCustomCommand:\n"
1547 "\t\t ID: %d, Value: %d, Address: %d, Size: %d",
1548 static_cast<int>(
id), value, reg_address, byte_number);
1552 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1554 if (motor_type == EHardwareType::STEPPER || motor_type == EHardwareType::FAKE_STEPPER_MOTOR) {
1555 return niryo_robot_msgs::CommandStatus::SUCCESS;
1560 int32_t value_conv = value;
1561 result =
_driver_map.at(motor_type)->writeCustom(
static_cast<uint16_t
>(reg_address),
static_cast<uint8_t
>(byte_number),
id,
static_cast<uint32_t
>(value_conv));
1562 if (result != COMM_SUCCESS)
1564 ROS_WARN(
"TtlManager::sendCustomCommand - Failed to write custom command: %d", result);
1566 result = niryo_robot_msgs::CommandStatus::TTL_WRITE_ERROR;
1571 ROS_ERROR_THROTTLE(1,
"TtlManager::sendCustomCommand - driver for motor %s not available", HardwareTypeEnum(motor_type).toString().c_str());
1572 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1577 ROS_ERROR_THROTTLE(1,
"TtlManager::sendCustomCommand - driver for motor id %d unknown",
static_cast<int>(
id));
1578 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1581 ros::Duration(0.005).sleep();
1595 int result = COMM_RX_FAIL;
1596 ROS_DEBUG(
"TtlManager::readCustomCommand: ID: %d, Address: %d, Size: %d",
static_cast<int>(
id),
static_cast<int>(reg_address), byte_number);
1600 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1605 result =
_driver_map.at(motor_type)->readCustom(
static_cast<uint16_t
>(reg_address),
static_cast<uint8_t
>(byte_number),
id, data);
1606 auto data_conv =
static_cast<int32_t
>(data);
1609 if (result != COMM_SUCCESS)
1611 ROS_WARN(
"TtlManager::readCustomCommand - Failed to read custom command: %d", result);
1612 result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1617 ROS_ERROR_THROTTLE(1,
"TtlManager::readCustomCommand - driver for motor %s not available", HardwareTypeEnum(motor_type).toString().c_str());
1618 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1623 ROS_ERROR_THROTTLE(1,
"TtlManager::readCustomCommand - driver for motor id %d unknown",
static_cast<int>(
id));
1624 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1627 ros::Duration(0.005).sleep();
1643 int TtlManager::readMotorPID(uint8_t
id, uint16_t &pos_p_gain, uint16_t &pos_i_gain, uint16_t &pos_d_gain, uint16_t &vel_p_gain, uint16_t &vel_i_gain, uint16_t &ff1_gain,
1646 int result = COMM_RX_FAIL;
1650 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1654 auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(
_driver_map.at(motor_type));
1657 std::vector<uint16_t> data;
1658 result = driver->readPID(
id, data);
1660 if (COMM_SUCCESS == result)
1662 pos_p_gain = data.at(0);
1663 pos_i_gain = data.at(1);
1664 pos_d_gain = data.at(2);
1665 vel_p_gain = data.at(3);
1666 vel_i_gain = data.at(4);
1667 ff1_gain = data.at(5);
1668 ff2_gain = data.at(6);
1672 ROS_WARN(
"TtlManager::readMotorPID - Failed to read PID: %d", result);
1673 result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1680 ROS_ERROR_THROTTLE(1,
"TtlManager::readMotorPID - driver for motor %s not available", HardwareTypeEnum(motor_type).toString().c_str());
1681 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1686 ROS_ERROR_THROTTLE(1,
"TtlManager::readMotorPID - driver for motor id %d unknown",
static_cast<int>(
id));
1687 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1690 ros::Duration(0.005).sleep();
1707 int TtlManager::readVelocityProfile(uint8_t
id, uint32_t &v_start, uint32_t &a_1, uint32_t &v_1, uint32_t &a_max, uint32_t &v_max, uint32_t &d_max, uint32_t &d_1, uint32_t &v_stop)
1709 int result = COMM_RX_FAIL;
1713 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1715 if (joint_stepper_driver)
1717 std::vector<uint32_t> data;
1718 result = joint_stepper_driver->readVelocityProfile(
id, data);
1720 if (COMM_SUCCESS == result)
1722 v_start = data.at(0);
1729 v_stop = data.at(7);
1733 ROS_WARN(
"TtlManager::readVelocityProfile - Failed to read velocity profile: %d", result);
1734 result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1740 ROS_ERROR_THROTTLE(1,
"TtlManager::readVelocityProfile - driver for motor %s not available", HardwareTypeEnum(motor_type).toString().c_str());
1741 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1746 ROS_ERROR_THROTTLE(1,
"TtlManager::readVelocityProfile - driver for motor id %d unknown",
static_cast<int>(
id));
1747 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1750 ros::Duration(0.005).sleep();
1762 int result = COMM_RX_FAIL;
1766 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1769 if (
_driver_map.count(motor_type) && (motor_type == EHardwareType::XL330 || motor_type == EHardwareType::XL320|| motor_type == EHardwareType::FAKE_DXL_MOTOR))
1771 auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(
_driver_map.at(motor_type));
1774 result = driver->readMoving(
id, status);
1779 ROS_ERROR_THROTTLE(1,
"TtlManager::readMoving - register MOVING for motor %s not available", HardwareTypeEnum(motor_type).toString().c_str());
1780 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1785 ROS_ERROR_THROTTLE(1,
"TtlManager::readMoving - driver for motor id %d unknown",
static_cast<int>(
id));
1786 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1789 ros::Duration(0.005).sleep();
1801 int result = COMM_RX_FAIL;
1805 EHardwareType motor_type =
_state_map.at(
id)->getHardwareType();
1809 auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(
_driver_map.at(motor_type));
1812 result = driver->readControlMode(
id, control_mode);
1817 ROS_ERROR_THROTTLE(1,
"TtlManager::readControlMode - driver for motor %s not available", HardwareTypeEnum(motor_type).toString().c_str());
1818 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1823 ROS_ERROR_THROTTLE(1,
"TtlManager::readControlMode - driver for motor id %d unknown",
static_cast<int>(
id));
1824 result = niryo_robot_msgs::CommandStatus::WRONG_MOTOR_TYPE;
1827 ros::Duration(0.005).sleep();
1838 int result = COMM_TX_ERROR;
1839 ROS_DEBUG_THROTTLE(0.5,
"TtlManager::writeSynchronizeCommand: %s", cmd->str().c_str());
1843 std::set<EHardwareType> typesToProcess = cmd->getMotorTypes();
1848 ROS_DEBUG_THROTTLE(0.5,
"TtlManager::writeSynchronizeCommand: try to sync write (counter %d)", counter);
1852 if (typesToProcess.count(it.first) != 0)
1854 result = COMM_TX_ERROR;
1857 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it.second);
1860 result = driver->writeSyncCmd(cmd->getCmdType(), cmd->getMotorsId(it.first), cmd->getParams(it.first));
1862 ros::Duration(0.05).sleep();
1866 if (COMM_SUCCESS == result)
1868 typesToProcess.erase(typesToProcess.find(it.first));
1872 ROS_ERROR(
"TtlManager::writeSynchronizeCommand : unable to sync write function : %d", result);
1878 if (typesToProcess.empty())
1880 result = COMM_SUCCESS;
1884 ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1889 ROS_ERROR(
"TtlManager::writeSynchronizeCommand - Invalid command");
1892 if (COMM_SUCCESS != result)
1894 ROS_ERROR_THROTTLE(0.5,
"TtlManager::writeSynchronizeCommand - Failed to write synchronize position");
1908 int result = COMM_TX_ERROR;
1910 uint8_t
id = cmd->getId();
1916 ROS_DEBUG(
"TtlManager::writeSingleCommand: %s", cmd->str().c_str());
1921 while ((COMM_SUCCESS != result) && (counter < 50))
1923 EHardwareType hardware_type = state->getHardwareType();
1924 result = COMM_TX_ERROR;
1928 result =
_driver_map.at(hardware_type)->writeSingleCmd(cmd);
1933 ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1938 ROS_DEBUG(
"TtlManager::writeSingleCommand: command is sent to a removed hardware component. Skipped or write to a unknow device");
1939 result = COMM_TX_ERROR;
1943 if (result != COMM_SUCCESS)
1945 ROS_WARN(
"TtlManager::writeSingleCommand - Fail to write single command : %s", cmd->str().c_str());
1963 for (
auto const &cmd : cmd_vec)
1973 auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it.second);
1978 if (err != COMM_SUCCESS)
1980 ROS_WARN(
"TtlManager::executeJointTrajectoryCmd - Failed to write position");
1996 ROS_DEBUG(
"TtlManager::startCalibration: starting...");
1998 std::vector<uint8_t> stepper_list;
1999 if (
_ids_map.count(EHardwareType::STEPPER))
2003 stepper_list =
_ids_map.at(EHardwareType::STEPPER);
2005 else if (
_ids_map.count(EHardwareType::NED3PRO_STEPPER))
2007 stepper_list =
_ids_map.at(EHardwareType::NED3PRO_STEPPER);
2009 else if (
_ids_map.count(EHardwareType::FAKE_STEPPER_MOTOR))
2013 stepper_list =
_ids_map.at(EHardwareType::FAKE_STEPPER_MOTOR);
2016 for (
auto const &
id : stepper_list)
2020 auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(
id));
2022 if (stepperState && !stepperState->isConveyor())
2024 stepperState->setCalibration(EStepperCalibrationStatus::IN_PROGRESS, 1);
2035 ROS_INFO(
"TtlManager::resetCalibration: reseting...");
2037 std::vector<uint8_t> stepper_list;
2038 if (
_ids_map.count(EHardwareType::STEPPER))
2042 stepper_list =
_ids_map.at(EHardwareType::STEPPER);
2044 else if (
_ids_map.count(EHardwareType::NED3PRO_STEPPER))
2045 stepper_list =
_ids_map.at(EHardwareType::NED3PRO_STEPPER);
2047 for (
auto const id : stepper_list)
2051 auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(
id));
2053 if (stepperState && !stepperState->isConveyor())
2055 stepperState->setCalibration(EStepperCalibrationStatus::UNINITIALIZED, 1);
2069 throw std::out_of_range(
"TtlManager::getMotorsState: Unknown motor id");
2071 return std::dynamic_pointer_cast<StepperMotorState>(
_state_map.at(motor_id))->getCalibrationValue();
2097 std::vector<std::shared_ptr<JointState>> states;
2101 if (it.second && it.second->getComponentType() == common::model::EComponentType::JOINT)
2103 states.emplace_back(std::dynamic_pointer_cast<JointState>(it.second));
2112 std::vector<std::shared_ptr<ConveyorState>> conveyor_states;
2115 if (it.second && it.second->getComponentType() == common::model::EComponentType::CONVEYOR)
2117 conveyor_states.emplace_back(std::dynamic_pointer_cast<ConveyorState>(it.second));
2121 return conveyor_states;
2132 throw std::out_of_range(
"TtlManager::getMotorsState: Unknown motor id");
2150 switch (hardware_type)
2152 case EHardwareType::STEPPER:
2155 case EHardwareType::NED3PRO_STEPPER:
2158 case EHardwareType::FAKE_STEPPER_MOTOR:
2161 case EHardwareType::XL430:
2164 case EHardwareType::XC430:
2167 case EHardwareType::XM430:
2170 case EHardwareType::XL320:
2173 case EHardwareType::XL330:
2176 case EHardwareType::XH430:
2179 case EHardwareType::FAKE_DXL_MOTOR:
2182 case EHardwareType::END_EFFECTOR:
2185 case EHardwareType::NED3PRO_END_EFFECTOR:
2188 case EHardwareType::FAKE_END_EFFECTOR:
2189 _driver_map.insert(std::make_pair(hardware_type, std::make_shared<MockEndEffectorDriver>(
_fake_data)));
2192 ROS_ERROR(
"TtlManager - Unable to instanciate driver, unknown type");
2203 _fake_data = std::make_shared<FakeTtlData>();
2205 if (
_nh.hasParam(
"fake_params"))
2207 std::vector<int> full_id_list;
2208 if (
_nh.hasParam(
"fake_params/id_list"))
2209 _nh.getParam(
"fake_params/id_list", full_id_list);
2210 for (
auto id : full_id_list)
2211 _fake_data->full_id_list.emplace_back(
static_cast<uint8_t
>(
id));
2213 if (
_nh.hasParam(
"fake_params/steppers"))
2215 std::string current_ns =
"fake_params/steppers/";
2219 if (
_nh.hasParam(
"fake_params/dynamixels/"))
2221 std::string current_ns =
"fake_params/dynamixels/";
2225 if (
_nh.hasParam(
"fake_params/end_effector"))
2227 string current_ns =
"fake_params/end_effector/";
2228 vector<int> id_list, temperature_list, voltage_list;
2229 vector<string> firmware_list;
2230 _nh.getParam(current_ns +
"id", id_list);
2231 _nh.getParam(current_ns +
"temperature", temperature_list);
2232 _nh.getParam(current_ns +
"voltage", voltage_list);
2233 _nh.getParam(current_ns +
"firmware", firmware_list);
2235 assert(!id_list.empty());
2236 assert(!temperature_list.empty());
2237 assert(!voltage_list.empty());
2238 assert(!firmware_list.empty());
2240 _fake_data->end_effector.id =
static_cast<uint8_t
>(id_list.at(0));
2241 _fake_data->end_effector.temperature =
static_cast<uint8_t
>(temperature_list.at(0));
2242 _fake_data->end_effector.voltage =
static_cast<double>(voltage_list.at(0));
2244 _fake_data->end_effector.firmware = firmware_list.at(0);
2247 if (use_simu_gripper &&
_nh.hasParam(
"fake_params/tool/"))
2249 std::string current_ns =
"fake_params/tool/";
2253 if (use_simu_conveyor &&
_nh.hasParam(
"fake_params/conveyors/"))
2255 std::string current_ns =
"fake_params/conveyors/";
2270 auto some_joint_state_it = std::find_if(joint_states.begin(), joint_states.end(), [](
const std::shared_ptr<JointState>& joint_state){
2271 return joint_state->isStepper();
2273 if (some_joint_state_it == joint_states.end()){
2276 auto some_joint_state = *some_joint_state_it;
2277 auto hardware_type = some_joint_state->getHardwareType();
2279 .driver = std::dynamic_pointer_cast<AbstractStepperDriver>(
_driver_map.at(hardware_type)),
2280 .hardware_type = hardware_type