ttl_manager.cpp
Go to the documentation of this file.
1 /*
2  ttl_driver.cpp
3  Copyright (C) 2020 Niryo
4  All rights reserved.
5  This program is free software: you can redistribute it and/or modify
6  it under the terms of the GNU General Public License as published by
7  the Free Software Foundation, either version 3 of the License, or
8  (at your option) any later version.
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13  You should have received a copy of the GNU General Public License
14  along with this program. If not, see <http:// www.gnu.org/licenses/>.
15 */
16 
18 
19 // cpp
20 #include <algorithm>
21 #include <cassert>
22 #include <cmath>
23 #include <cstdlib>
24 #include <memory>
25 #include <set>
26 #include <sstream>
27 #include <string>
28 #include <unordered_map>
29 #include <utility>
30 #include <vector>
31 
32 // ros
33 #include "ros/serialization.h"
34 #include "ros/time.h"
35 
36 // niryo
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"
43 
44 #include "dynamixel_sdk/packet_handler.h"
45 #include "niryo_robot_msgs/CommandStatus.h"
48 
58 #include "ttl_driver/CalibrationStatus.h"
59 
60 using ::std::ostringstream;
61 using ::std::set;
62 using ::std::shared_ptr;
63 using ::std::string;
64 using ::std::to_string;
65 using ::std::vector;
66 
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;
74 
75 namespace ttl_driver
76 {
80 TtlManager::TtlManager(ros::NodeHandle &nh)
81  : _nh(nh), _debug_error_message("TtlManager - No connection with TTL motors has been made yet")
82 {
83  ROS_DEBUG("TtlManager - ctor");
84 
85  init(nh);
86 
87  if (COMM_SUCCESS != setupCommunication())
88  ROS_WARN("TtlManager - TTL Communication Failed");
89 }
90 
95 {
96  if (_portHandler)
97  {
98  _portHandler->clearPort();
99  _portHandler->closePort();
100  }
101 }
102 
108 bool TtlManager::init(ros::NodeHandle &nh)
109 {
110  // get params from rosparams
111  bool use_simu_gripper{ false };
112  bool use_simu_conveyor{ false };
113 
114  _nh.getParam("fake_params/available_tools/id", _available_tools);
115 
116  nh.getParam("bus_params/uart_device_name", _device_name);
117  nh.getParam("bus_params/baudrate", _baudrate);
118  nh.getParam("led_motor", _led_motor_type_cfg);
119 
120  nh.getParam("simulation_mode", _simulation_mode);
121  nh.getParam("simu_gripper", use_simu_gripper);
122  nh.getParam("simu_conveyor", use_simu_conveyor);
123  nh.getParam("fake_params/tool/id", _current_tool_vector);
124  if (!_current_tool_vector.empty())
125  {
127  }
128 
129  ROS_DEBUG("TtlManager::init - Dxl : set port name (%s), baudrate(%d)", _device_name.c_str(), _baudrate);
130  ROS_DEBUG("TtlManager::init - led motor type config : %s", _led_motor_type_cfg.c_str());
131 
132  ROS_DEBUG("TtlManager::init - Simulation mode: %s, simu_gripper: %s, simu_conveyor: %s",
133  _simulation_mode ? "True" : "False", use_simu_gripper ? "True" : "False",
134  use_simu_conveyor ? "True" : "False");
135 
136  if (!_simulation_mode)
137  {
138  _portHandler.reset(dynamixel::PortHandler::getPortHandler(_device_name.c_str()));
139  _packetHandler.reset(dynamixel::PacketHandler::getPacketHandler(TTL_BUS_PROTOCOL_VERSION));
140 
141  // init default ttl driver for common operations between drivers
142  _default_ttl_driver = std::make_shared<StepperDriver<StepperReg>>(_portHandler, _packetHandler);
143  }
144  else
145  {
146  readFakeConfig(use_simu_gripper, use_simu_conveyor);
147  _default_ttl_driver = std::make_shared<MockStepperDriver>(_fake_data);
148  }
149 
150  _calibration_status_publisher = nh.advertise<ttl_driver::CalibrationStatus>("calibration_status", 1, true);
151 
152  return true;
153 }
154 
159 bool TtlManager::changeTool(int value, string &message, int &status)
160 {
161  std::lock_guard<std::mutex> lck(_sync_mutex);
162  auto it_driver = _driver_map.find(EHardwareType::FAKE_DXL_MOTOR);
163  if (it_driver == _driver_map.end())
164  {
165  status = niryo_robot_msgs::CommandStatus::TOOL_FAILURE;
166  message = "Tool change failed : Real robot mode";
167  return true;
168  }
169 
170  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it_driver->second);
171  if (!driver)
172  {
173  status = niryo_robot_msgs::CommandStatus::TOOL_ID_INVALID;
174  message = "Tool change failed : Driver not found";
175  return true;
176  }
177 
178  if (value != 0)
179  {
180  auto it = std::find(_available_tools.begin(), _available_tools.end(), value);
181 
182  if (it == _available_tools.end())
183  {
184  status = niryo_robot_msgs::CommandStatus::TOOL_ID_INVALID;
185  message = "Tool change failed: Tool ID is invalid";
186  return true;
187  }
188 
189  if (_current_tool_id == 0)
190  {
191  retrieveFakeMotorData("fake_params/tool/", _fake_data->dxl_registers, { value });
192  }
193  }
194 
195  if (driver->changeId(_current_tool_id, value) == COMM_SUCCESS)
196  {
197  _current_tool_id = value;
198  status = niryo_robot_msgs::CommandStatus::SUCCESS;
199  message = "Tool change succeeded";
200  }
201  else
202  {
203  status = niryo_robot_msgs::CommandStatus::TOOL_NOT_CONNECTED;
204  message = "Tool change failed: Communication error";
205  }
206 
207  // return response even request failed
208  return true;
209 }
210 
216 {
217  int ret = COMM_NOT_AVAILABLE;
218 
219  ROS_DEBUG("TtlManager::setupCommunication - initializing connection...");
220 
221  // fake drivers will always succeed for the communication
222  if (_simulation_mode)
223  {
224  ret = COMM_SUCCESS;
225  }
226  else
227  {
228  // Ttl bus setup
229  if (_portHandler)
230  {
231  _debug_error_message.clear();
232 
233  // Open port
234  if (_portHandler->openPort())
235  {
236  // Set baudrate
237  if (_portHandler->setBaudRate(_baudrate))
238  {
239  // wait a bit to be sure the connection is established
240  ros::Duration(0.1).sleep();
241 
242  // clear port
243  _portHandler->clearPort();
244 
245  ret = COMM_SUCCESS;
246  }
247  else
248  {
249  ROS_ERROR("TtlManager::setupCommunication - Failed to set baudrate for Dynamixel bus");
250  _debug_error_message = "TtlManager - Failed to set baudrate for Dynamixel bus";
252  }
253  }
254  else
255  {
256  ROS_ERROR("TtlManager::setupCommunication - Failed to open Uart port for Dynamixel bus");
257  _debug_error_message = "TtlManager - Failed to open Uart port for Dynamixel bus";
258  ret = TTL_FAIL_OPEN_PORT;
259  }
260  }
261  else
262  ROS_ERROR("TtlManager::setupCommunication - Invalid port handler");
263  }
264 
265  return ret;
266 }
267 
272 int TtlManager::addHardwareComponent(std::shared_ptr<common::model::AbstractHardwareState> &&state) // NOLINT
273 {
274  if (!state)
275  {
276  return niryo_robot_msgs::CommandStatus::FAILURE;
277  }
278 
279  EHardwareType hardware_type = state->getHardwareType();
280  uint8_t id = state->getId();
281 
282  ROS_DEBUG("TtlManager::addHardwareComponent : %s", state->str().c_str());
283 
284  addHardwareDriver(hardware_type);
285 
286  auto driver_it = _driver_map.find(hardware_type);
287  if (driver_it == _driver_map.end())
288  {
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;
292  }
293  auto driver = driver_it->second;
294 
295  uint16_t model_number = 0;
296  // check if the driver is valid for this hardware
297  if (state->getStrictModelNumber() && driver->checkModelNumber(id, model_number) != COMM_SUCCESS)
298  {
299  ROS_WARN("TtlManager::addHardwareComponent - Model number check failed for hardware id %d", id);
300  return niryo_robot_msgs::CommandStatus::HARDWARE_NOT_SUPPORTED;
301  }
302  else if (driver->getModelNumber(id, model_number) != COMM_SUCCESS)
303  {
304  ROS_WARN("TtlManager::addHardwareComponent - Unable to retrieve model number for hardware id %d", id);
305  return niryo_robot_msgs::CommandStatus::HARDWARE_NOT_SUPPORTED;
306  }
307 
308  state->setModelNumber(model_number);
309 
310  // update firmware version
311  std::string version;
312  int res = COMM_RX_FAIL;
313  for (int tries = 10; tries > 0; tries--)
314  {
315  res = driver->readFirmwareVersion(id, version);
316  if (COMM_SUCCESS == res)
317  {
318  state->setFirmwareVersion(version);
319  break;
320  }
321  ros::Duration(0.1).sleep();
322  }
323 
324  if (COMM_SUCCESS != res)
325  {
326  ROS_WARN(
327  "TtlManager::addHardwareComponent : Unable to retrieve firmware version for "
328  "hardware id %d : result = %d",
329  id, res);
330  }
331 
332  // add state to state map
333  _state_map[id] = state;
334 
335  // add id to ids_map
336  _ids_map[hardware_type].emplace_back(id);
337 
338  // add to global lists
339  if (common::model::EComponentType::CONVEYOR == state->getComponentType())
340  {
341  if (std::find(_conveyor_list.begin(), _conveyor_list.end(), id) == _conveyor_list.end())
342  _conveyor_list.emplace_back(id);
343  }
344 
345  // Reset the calibration if we add a new joint and it is not a simulated one
346  if (common::model::EComponentType::JOINT == state->getComponentType())
347  {
348  if (!(common::model::EHardwareType::FAKE_STEPPER_MOTOR == hardware_type ||
349  common::model::EHardwareType::FAKE_DXL_MOTOR == hardware_type))
350  {
351  _calibration_status = EStepperCalibrationStatus::UNINITIALIZED;
352  }
353  }
354 
356  return niryo_robot_msgs::CommandStatus::SUCCESS;
357 }
358 
364 {
365  ROS_DEBUG("TtlManager::removeMotor - Remove motor id: %d", id);
366 
367  if (_state_map.count(id) && _state_map.at(id))
368  {
369  EHardwareType type = _state_map.at(id)->getHardwareType();
370 
371  // std::remove to remove hypothetic duplicates too
372  if (_ids_map.count(type))
373  {
374  auto &ids = _ids_map.at(type);
375  ids.erase(std::remove(ids.begin(), ids.end(), id), ids.end());
376  if (ids.empty())
377  {
378  _ids_map.erase(type);
379  }
380  }
381 
382  _state_map.erase(id);
383  }
384  // remove id from conveyor list if they contains id
385  _conveyor_list.erase(std::remove(_conveyor_list.begin(), _conveyor_list.end(), id), _conveyor_list.end());
386 
387  _removed_motor_id_list.erase(std::remove(_removed_motor_id_list.begin(), _removed_motor_id_list.end(), id),
388  _removed_motor_id_list.end());
389 }
390 
397 bool TtlManager::isMotorType(EHardwareType type)
398 {
399  // All motors have value under 7 (check in EHardwareType)
400  return (static_cast<int>(type) <= 7);
401 }
402 
403 // ****************
404 // commands
405 // ****************
406 
414 int TtlManager::changeId(EHardwareType motor_type, uint8_t old_id, uint8_t new_id)
415 {
416  int ret = COMM_TX_FAIL;
417 
418  if (old_id == new_id)
419  {
420  ret = COMM_SUCCESS;
421  }
422  else if (_driver_map.count(motor_type))
423  {
424  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(_driver_map.at(motor_type));
425 
426  if (driver)
427  {
428  ret = driver->changeId(old_id, new_id);
429  if (COMM_SUCCESS == ret)
430  {
431  // update all maps
432  auto i_state = _state_map.find(old_id);
433  // update all maps
434  if (i_state != _state_map.end())
435  {
436  // insert new_id in map, move i_state->second to its new place
437  std::swap(_state_map[new_id], i_state->second);
438  // update all maps
439  _state_map.erase(i_state);
440 
441  assert(_state_map.at(new_id));
442 
443  // update conveyor list if needed
444  if (common::model::EComponentType::CONVEYOR == _state_map.at(new_id)->getComponentType())
445  {
446  // change old id into new id in vector
447  auto iter = std::find(_conveyor_list.begin(), _conveyor_list.end(), old_id);
448  if (iter != _conveyor_list.end())
449  *iter = new_id;
450  }
451  }
452  if (_ids_map.count(motor_type))
453  {
454  // update all maps
455  _ids_map.at(motor_type)
456  .erase(std::remove(_ids_map.at(motor_type).begin(), _ids_map.at(motor_type).end(), old_id),
457  _ids_map.at(motor_type).end());
458 
459  // update all maps
460  _ids_map.at(motor_type).emplace_back(new_id);
461  }
462  }
463  }
464  }
465 
466  return ret;
467 }
468 
474 {
475  ROS_DEBUG("TtlManager::scanAndCheck");
476  int result = COMM_PORT_BUSY;
477 
478  _is_connection_ok = false;
479 
480  // 1. retrieve list of connected motors
481  _all_ids_connected.clear();
482  for (int counter = 0; counter < 50 && COMM_SUCCESS != result; ++counter)
483  {
485  ROS_DEBUG_COND(COMM_SUCCESS != result, "TtlManager::scanAndCheck status: %d (counter: %d)", result, counter);
486  ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
487  }
488 
489  if (COMM_SUCCESS == result)
490  {
491  // 2. update list of removed ids and update corresponding states
492  _removed_motor_id_list.clear();
493  std::string error_motors_message;
494  for (auto &istate : _state_map)
495  {
496  if (istate.second)
497  {
498  uint8_t id = istate.first;
499  auto it = find(_all_ids_connected.begin(), _all_ids_connected.end(), id);
500  // not found
501  if (it == _all_ids_connected.end())
502  {
503  _removed_motor_id_list.emplace_back(id);
504  error_motors_message += " " + to_string(id);
505  istate.second->setConnectionStatus(true);
506  }
507  else
508  {
509  istate.second->setConnectionStatus(false);
510  }
511  }
512  }
513 
514  if (_removed_motor_id_list.empty())
515  {
516  _is_connection_ok = true;
517  _debug_error_message.clear();
518  result = TTL_SCAN_OK;
519  }
520  else
521  {
522  _debug_error_message = "Motor(s):" + error_motors_message + " do not seem to be connected";
523  result = TTL_SCAN_MISSING_MOTOR;
524  }
525  }
526  else
527  {
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");
530  }
531 
532  return result;
533 }
534 
542 bool TtlManager::ping(uint8_t id)
543 {
544  int result = false;
545 
547  {
548  if (COMM_SUCCESS == _default_ttl_driver->ping(id))
549  result = true;
550  }
551 
552  return result;
553 }
554 
560 int TtlManager::rebootHardware(uint8_t hw_id)
561 {
562  int return_value = COMM_TX_FAIL;
563 
564  if (_state_map.count(hw_id) != 0 && _state_map.at(hw_id))
565  {
566  EHardwareType type = _state_map.at(hw_id)->getHardwareType();
567  ROS_DEBUG("TtlManager::rebootHardware - Reboot hardware with ID: %d", hw_id);
568  if (_driver_map.count(type) && _driver_map.at(type))
569  {
570  return_value = _driver_map.at(type)->reboot(hw_id);
571  if (COMM_SUCCESS == return_value)
572  {
573  std::string version;
574  int res = COMM_RX_FAIL;
575  for (int tries = 10; tries > 0; tries--)
576  {
577  res = _driver_map.at(type)->readFirmwareVersion(hw_id, version);
578  if (COMM_SUCCESS == res)
579  {
580  _state_map.at(hw_id)->setFirmwareVersion(version);
581  break;
582  }
583  ros::Duration(0.1).sleep();
584  }
585 
586  if (COMM_SUCCESS != res)
587  {
588  ROS_WARN(
589  "TtlManager::addHardwareComponent : Unable to retrieve firmware version for "
590  "hardware id %d : result = %d",
591  hw_id, res);
592  }
593  }
594  ROS_WARN_COND(COMM_SUCCESS != return_value, "TtlManager::rebootHardware - Failed to reboot hardware: %d",
595  return_value);
596  }
597  }
598 
599  return return_value;
600 }
601 
607 {
608  for (auto const &it : _driver_map)
609  {
610  auto hw_type = it.first;
611  auto driver = std::dynamic_pointer_cast<ttl_driver::AbstractMotorDriver>(it.second);
612 
613  if (driver && _ids_map.count(hw_type) && !_ids_map.at(hw_type).empty())
614  {
615  // we retrieve all the associated id for the type of the current driver
616  vector<uint8_t> ids_list = _ids_map.at(hw_type);
617 
618  auto jStates = getMotorsStates();
619 
620  for (size_t i = 0; i < ids_list.size(); ++i)
621  {
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())
625  {
626  continue;
627  }
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());
631  } // for ids_list
632  }
633  } // for _driver_map
634 }
635 
636 // ******************
637 // Read operations
638 // ******************
639 
645 uint32_t TtlManager::getPosition(const JointState &motor_state)
646 {
647  uint32_t position = 0;
648  EHardwareType hardware_type = motor_state.getHardwareType();
649  if (_driver_map.count(hardware_type))
650  {
651  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(_driver_map.at(hardware_type));
652  if (driver)
653  {
655  {
656  if (COMM_SUCCESS == driver->readPosition(motor_state.getId(), position))
657  {
659  break;
660  }
661  }
662  }
663 
664  if (0 < _hw_fail_counter_read)
665  {
666  ROS_ERROR_THROTTLE(1, "TtlManager::getPosition - motor connection problem - Failed to read from bus");
667  _debug_error_message = "TtlManager - Connection problem with Bus.";
669  _is_connection_ok = false;
670  }
671  }
672  else
673  {
674  ROS_ERROR_THROTTLE(1, "TtlManager::getPosition - Driver not found for requested motor id");
675  _debug_error_message = "TtlManager::getPosition - Driver not found for requested motor id";
676  }
677  return position;
678 }
679 
681 {
682  EHardwareType hw_type(EHardwareType::STEPPER);
683  auto driver = std::dynamic_pointer_cast<ttl_driver::StepperDriver<ttl_driver::StepperReg>>(_driver_map[hw_type]);
684  if (driver && _ids_map.count(hw_type) && !_ids_map.at(hw_type).empty())
685  {
686  // we retrieve all the associated id for the type of the current driver
687  vector<uint8_t> ids_list = _ids_map.at(hw_type);
688 
689  // we retrieve all the associated id for the type of the current driver
690  vector<uint32_t> homing_abs_position_list;
691 
692  // retrieve joint status
693  int res = driver->syncReadHomingAbsPosition(ids_list, homing_abs_position_list);
694  if (COMM_SUCCESS == res)
695  {
696  if (ids_list.size() == homing_abs_position_list.size())
697  {
698  // set motors states accordingly
699  for (size_t i = 0; i < ids_list.size(); ++i)
700  {
701  uint8_t id = ids_list.at(i);
702 
703  if (_state_map.count(id))
704  {
705  auto state = std::dynamic_pointer_cast<common::model::StepperMotorState>(_state_map.at(id));
706  if (state)
707  {
708  state->setHomingAbsPosition(static_cast<uint32_t>(homing_abs_position_list.at(i)));
709  }
710  else
711  {
712  ROS_ERROR("TtlManager::readHomingAbsPosition - null pointer");
713  return false;
714  }
715  }
716  else
717  {
718  ROS_ERROR("TtlManager::readHomingAbsPosition - No hardware state assossiated to ID: %d",
719  static_cast<int>(id));
720  return false;
721  }
722  }
723  }
724  else
725  {
726  ROS_ERROR(
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()));
729  return false;
730  }
731  }
732  else
733  {
734  ROS_ERROR("TtlManager::readHomingAbsPosition - communication error: %d", static_cast<int>(res));
735  return false;
736  }
737  }
738  else
739  {
740  ROS_ERROR(
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()));
743  return false;
744  }
745 
746  return true;
747 }
748 
754 {
755  uint8_t hw_errors_increment = 0;
756 
757  // syncread position for all motors.
758  // for ned and one -> we need at least one xl430 and one xl320 drivers as they are different
759 
760  for (auto const &it : _driver_map)
761  {
762  auto hw_type = it.first;
763  auto driver = std::dynamic_pointer_cast<ttl_driver::AbstractMotorDriver>(it.second);
764 
765  if (!driver)
766  {
767  continue;
768  }
769  auto id_list_it = _ids_map.find(hw_type);
770  if (id_list_it == _ids_map.end())
771  {
772  continue;
773  }
774  auto ids_list = id_list_it->second;
775 
776  if (ids_list.empty())
777  {
778  continue;
779  }
780 
781  // we retrieve all the associated id for the type of the current driver
782  _position_list.clear();
783 
784  // retrieve joint status
785  int res = driver->syncReadPosition(ids_list, _position_list);
786  if (COMM_SUCCESS == res)
787  {
788  if (ids_list.size() == _position_list.size())
789  {
790  // set motors states accordingly
791  for (size_t i = 0; i < ids_list.size(); ++i)
792  {
793  uint8_t id = ids_list.at(i);
794 
795  if (_state_map.count(id))
796  {
797  auto state = std::dynamic_pointer_cast<common::model::AbstractMotorState>(_state_map.at(id));
798  if (state)
799  {
800  state->setPosition(static_cast<int>((_position_list.at(i))));
801  }
802  }
803  }
804  }
805  else
806  {
807  // warn to avoid sound and light error on high level (error on ROS_ERROR)
808  ROS_WARN(
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++;
813  }
814  }
815  else
816  {
817  // debug to avoid sound and light error on high level (error on ROS_ERROR)
818  // also for Ned which has much more errors on XL320 motor
819  ROS_DEBUG(
820  "TtlManager::readJointStatus : Fail to sync read joint state - "
821  "driver fail to syncReadPosition");
822  hw_errors_increment++;
823  }
824  } // for driver_map
825 
826  // check collision by END_EFFECTOR
827  if (_isRealCollision)
828  {
830  }
831  else
832  {
833  _collision_status = false;
834  // check collision by END_EFFECTOR
835  if (_isRealCollision)
836  {
837  checkCollision();
838  }
839  else
840  {
841  _collision_status = false;
842  }
843  }
844 
845  ROS_DEBUG_THROTTLE(2, "_hw_fail_counter_read, hw_errors_increment: %d, %d", _hw_fail_counter_read,
846  hw_errors_increment);
847 
848  // we reset the global error variable only if no errors
849  if (0 == hw_errors_increment)
850  {
852  }
853  else
854  {
855  _hw_fail_counter_read += hw_errors_increment;
856  }
857 
858  return (0 == hw_errors_increment);
859 }
860 
866 {
867  bool res = false;
868 
869  // hardware_version is not available within this class to know whether there is a ned2/ned3pro eef
870  // however if hardware_type == ned2 _driver_map will contain EHardwareType::END_EFFECTOR
871  // and if hardware_type == ned3pro _driver_map will contain EHardwareType::NED3PRO_END_EFFECTOR
872  EHardwareType ee_type;
873 
874  if (_simulation_mode)
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;
880 
881  if (_driver_map.count(ee_type))
882  {
883  unsigned int hw_errors_increment = 0;
884 
885  auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(_driver_map.at(ee_type));
886  if (driver)
887  {
888  if (_ids_map.count(ee_type) && !_ids_map.at(ee_type).empty())
889  {
890  uint8_t id = _ids_map.at(ee_type).front();
891 
892  if (_state_map.count(id))
893  {
894  // we retrieve the associated id for the end effector
895  auto state = std::dynamic_pointer_cast<EndEffectorState>(_state_map[id]);
896 
897  if (state)
898  {
899  vector<common::model::EActionType> action_list;
900 
901  // ********** buttons
902  // get action of free driver button, save pos button, custom button
903  if (COMM_SUCCESS == driver->syncReadButtonsStatus(id, action_list))
904  {
905  for (uint8_t i = 0; i < action_list.size(); i++)
906  {
907  state->setButtonStatus(i, action_list.at(i));
908  // In case free driver button, it we hold this button, normally, because of the small threshold of
909  // collision detection this action make EE confuse that it is a collision. That's why when we hold
910  // buttons, we need to deactivate the detection of collision.
911  if (action_list.at(i) != common::model::EActionType::NO_ACTION)
912  {
913  _isRealCollision = false;
914  }
915  else if (!_isRealCollision)
916  {
917  // when previous action is not no_action => need to wait a short period to make sure no collision
918  // detected Note, we need to read one time the status of collision just after releasing button to
919  // reset the status.
920  _isRealCollision = true;
921  _isWrongAction = true;
922  _last_collision_detection_activating = ros::Time::now().toSec();
923  }
924  }
925  }
926  else
927  {
928  hw_errors_increment++;
929  }
930 
931  // ********** digital data
932  bool digital_data{};
933  if (COMM_SUCCESS == driver->readDigitalInput(id, digital_data))
934  {
935  state->setDigitalIn(digital_data);
936  }
937  else
938  {
939  hw_errors_increment++;
940  }
941  } // if (state)
942  }
943  } // if (_ids_map.count(EHardwareType::END_EFFECTOR))
944  } // if (driver)
945 
946  // we reset the global error variable only if no errors
947  if (0 == hw_errors_increment)
948  {
950  _debug_error_message.clear();
951 
952  res = true;
953  }
954  else
955  {
956  ROS_DEBUG_COND(_end_effector_fail_counter_read > 10, "TtlManager::readEndEffectorStatus: nb error > 10 : %d",
958  _end_effector_fail_counter_read += hw_errors_increment;
959  }
960 
962  {
963  ROS_ERROR(
964  "TtlManager::readEndEffectorStatus - motor connection problem - Failed to read from bus "
965  "(hw_fail_counter_read : %d)",
968  _debug_error_message = "TtlManager - Connection problem with physical Bus.";
969  }
970  }
971 
972  return res;
973 }
974 
981 {
982  bool res = false;
983 
984  // hardware_version is not available within this class to know whether there is a ned2/ned3pro eef
985  // however if hardware_type == ned2 _driver_map will contain EHardwareType::END_EFFECTOR
986  // and if hardware_type == ned3pro _driver_map will contain EHardwareType::NED3PRO_END_EFFECTOR
987  EHardwareType ee_type;
988 
989  if (_simulation_mode)
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;
995 
996  if (_driver_map.count(ee_type))
997  {
998  unsigned int hw_errors_increment = 0;
999 
1000  auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(_driver_map.at(ee_type));
1001  if (driver)
1002  {
1003  if (_ids_map.count(ee_type) && !_ids_map.at(ee_type).empty())
1004  {
1005  uint8_t id = _ids_map.at(ee_type).front();
1006 
1007  // ********** collision
1008  // not accept other status of collistion in 1 second if it detected a collision
1010  {
1011  bool last_statut = _collision_status;
1012  if (COMM_SUCCESS == driver->readCollisionStatus(id, _collision_status))
1013  {
1014  if (last_statut == _collision_status && _collision_status)
1015  {
1016  // if we have a collision, we will publish the statut collision only once
1017  // This avoid that the delay in reading statut influent to next movement.
1018  _collision_status = false;
1019  }
1020  else if (_collision_status)
1021  {
1022  if (_isWrongAction)
1023  {
1024  // if an action did a wrong detection of collision, we need to read once to reset the status
1025  _isWrongAction = false;
1026  _collision_status = false;
1027  }
1028  else
1029  _last_collision_detection_activating = ros::Time::now().toSec();
1030  }
1031  }
1032  else
1033  {
1034  hw_errors_increment++;
1035  }
1036  }
1037  else if (ros::Time::now().toSec() - _last_collision_detection_activating >= 1.0)
1038  {
1040  }
1041  } // if (_ids_map.count(EHardwareType::END_EFFECTOR))
1042  } // if (driver)
1043 
1044  // we reset the global error variable only if no errors
1045  if (0 == hw_errors_increment)
1046  {
1048  res = true;
1049  }
1050  else
1051  {
1052  ROS_DEBUG_COND(_end_effector_fail_counter_read > 10, "TtlManager::checkCollision: nb error > 10 : %d",
1054  _end_effector_fail_counter_read += hw_errors_increment;
1055  }
1056  }
1057  return res;
1058 }
1059 
1065 {
1066  bool res = false;
1067 
1068  // hardware_version is not available within this class to know whether there is a ned2/ned3pro eef
1069  // however if hardware_type == ned2 _driver_map will contain EHardwareType::END_EFFECTOR
1070  // and if hardware_type == ned3pro _driver_map will contain EHardwareType::NED3PRO_END_EFFECTOR
1071  EHardwareType ee_type;
1072 
1073  if (_simulation_mode)
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;
1079 
1080  if (_driver_map.count(ee_type))
1081  {
1082  auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(_driver_map.at(ee_type));
1083 
1084  if (driver)
1085  {
1086  if (_ids_map.count(ee_type) && !_ids_map.at(ee_type).empty())
1087  {
1088  uint8_t id = _ids_map.at(ee_type).front();
1089 
1090  // ********** collision
1091  // don't accept other status of collistion in 1 second if it detected a collision
1093  {
1094  if (COMM_SUCCESS == driver->readCollisionStatus(id, _collision_status))
1095  {
1096  res = true;
1097 
1098  if (_collision_status)
1099  {
1100  if (_isWrongAction)
1101  {
1102  // if an action did a wrong detection of collision, we need to read once to reset the status
1103  _isWrongAction = false;
1104  _collision_status = false;
1105  }
1106  else
1107  {
1108  _last_collision_detection_activating = ros::Time::now().toSec();
1109  }
1110  }
1111  }
1112  else
1113  {
1115  }
1116  }
1117  else if (ros::Time::now().toSec() - _last_collision_detection_activating >= 1.0)
1118  {
1120  }
1121  }
1122  }
1123  }
1124 
1125  return res;
1126 }
1127 
1132 {
1133  bool res = false;
1134 
1135  unsigned int hw_errors_increment = 0;
1136 
1137  // take all hw status dedicated drivers
1138  for (auto const &it : _driver_map)
1139  {
1140  auto type = it.first;
1141  auto driver = it.second;
1142 
1143  if (driver && _ids_map.count(type) && !_ids_map.at(type).empty())
1144  {
1145  // we retrieve all the associated id for the type of the current driver
1146  vector<uint8_t> ids_list = _ids_map.at(type);
1147 
1148  // 1. syncread for all motors
1149  // ********** voltage and Temperature
1150  vector<std::pair<double, uint8_t>> hw_data_list;
1151 
1152  if (COMM_SUCCESS != driver->syncReadHwStatus(ids_list, hw_data_list))
1153  {
1154  // this operation can fail, it is normal, so no error message
1155  hw_errors_increment++;
1156  }
1157  else if (ids_list.size() != hw_data_list.size())
1158  {
1159  // however, if we have a mismatch here, it is not normal
1160  ROS_ERROR(
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()));
1164 
1165  hw_errors_increment++;
1166  }
1167 
1168  // ********** error state
1169  vector<uint8_t> hw_error_status_list;
1170 
1171  if (COMM_SUCCESS != driver->syncReadHwErrorStatus(ids_list, hw_error_status_list))
1172  {
1173  hw_errors_increment++;
1174  }
1175  else if (ids_list.size() != hw_error_status_list.size())
1176  {
1177  ROS_ERROR(
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()));
1181 
1182  hw_errors_increment++;
1183  }
1184 
1185  // 2. set motors states accordingly
1186  for (size_t i = 0; i < ids_list.size(); ++i)
1187  {
1188  uint8_t id = ids_list.at(i);
1189 
1190  if (_state_map.count(id) && _state_map.at(id))
1191  {
1192  auto state = _state_map.at(id);
1193 
1194  // ************** temperature and voltage
1195  if (hw_data_list.size() > i)
1196  {
1197  double voltage = (hw_data_list.at(i)).first;
1198  uint8_t temperature = (hw_data_list.at(i)).second;
1199 
1200  state->setTemperature(temperature);
1201  state->setRawVoltage(voltage);
1202  }
1203 
1204  // ********** error state
1205  if (hw_error_status_list.size() > i)
1206  {
1207  state->setHardwareError(hw_error_status_list.at(i));
1208  }
1209 
1210  // interpret any error code into message (even if not retrieved now)
1211  string hardware_message = driver->interpretErrorState(state->getHardwareError());
1212  state->setHardwareError(hardware_message);
1213  }
1214  } // for ids_list
1215  } // if driver
1216  } // for (auto it : _hw_status_driver_map)
1217 
1218  // ********** steppers related informations (conveyor and calibration)
1219  hw_errors_increment += readSteppersStatus();
1220 
1221  // we reset the global error variable only if no errors
1222  if (0 == hw_errors_increment)
1223  {
1225  _debug_error_message.clear();
1226 
1227  res = true;
1228  }
1229  else
1230  {
1231  _hw_fail_counter_read += hw_errors_increment;
1232  }
1233 
1234  // if too much errors, disconnect
1236  {
1237  ROS_ERROR_THROTTLE(1,
1238  "TtlManager::readHardwareStatus - motor connection problem - "
1239  "Failed to read from bus (hw_fail_counter_read : %d)",
1242  res = false;
1243  _is_connection_ok = false;
1244  _debug_error_message = "TtlManager - Connection problem with physical Bus.";
1245  }
1246 
1247  return res;
1248 }
1249 
1255 {
1256  uint8_t hw_errors_increment = 0;
1257 
1258  // take all hw status dedicated drivers
1259  auto [stepper_joint_driver, hw_type] = getJointsStepperDriver();
1260  if (stepper_joint_driver)
1261  {
1262  if (hw_type == EHardwareType::STEPPER || hw_type == EHardwareType::FAKE_STEPPER_MOTOR)
1263  {
1264  // 1. read calibration status if needed
1265 
1266  // we want to check calibration (done at startup and when calibration is started)
1268  {
1269  // When calibration is running, sometimes at an unexpected position, calibration make EE thinks that there is a
1270  // collision Have to disable the feature collision detection in this period
1271  _isRealCollision = false;
1272 
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;
1277  });
1278 
1279  /* Truth Table
1280  * still_in_progress | state | new state
1281  * 0 | IDLE = IDLE
1282  * 0 | START = START
1283  * 0 | PROG > UPDAT
1284  * 0 | UPDAT R IDLE
1285  * 1 | IDLE = IDLE
1286  * 1 | START > PROG
1287  * 1 | PROG = PROG
1288  * 1 | UPDAT = UPDAT
1289  */
1290 
1291  // *********** calibration status, only if initialized
1292  std::vector<uint8_t> homing_status_list;
1293  if (COMM_SUCCESS == stepper_joint_driver->syncReadHomingStatus(stepper_id_list, homing_status_list))
1294  {
1295  if (stepper_id_list.size() == homing_status_list.size())
1296  {
1297  // max status need to be kept not converted into EStepperCalibrationStatus because max status is "in
1298  // progress" in the enum
1299  int max_status = -1;
1300 
1301  // debug only
1302  std::ostringstream ss_debug;
1303  ss_debug << "homing status : ";
1304 
1305  bool still_in_progress = false;
1306 
1307  // set states accordingly
1308  for (size_t i = 0; i < homing_status_list.size(); ++i)
1309  {
1310  uint8_t id = stepper_id_list.at(i);
1311  ss_debug << static_cast<int>(homing_status_list.at(i)) << ", ";
1312 
1313  if (_state_map.count(id))
1314  {
1315  EStepperCalibrationStatus status = stepper_joint_driver->interpretHomingData(homing_status_list.at(i));
1316 
1317  // set status in state
1318  auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(id));
1319  if (stepperState && !stepperState->isConveyor())
1320  {
1321  stepperState->setCalibration(status, 1);
1322 
1323  // get max status of all motors (to retrieve potential errors)
1324  // carefull to those possible cases :
1325  // 1, 1, 1
1326  // 1, 2, 1
1327  // 0, 2, 2
1328  // 2, 0, 2
1329 
1330  // if 0, uninitialized, else, take max
1331  // we need to keep the status unconverted to have the correct order
1332  if (0 != max_status && homing_status_list.at(i) > max_status)
1333  max_status = homing_status_list.at(i);
1334 
1335  // if one status is in progress or uinitialized, we are really in progress
1336  if ((0 == homing_status_list.at(i)) || EStepperCalibrationStatus::IN_PROGRESS == status)
1337  {
1338  still_in_progress = true;
1339  }
1340  }
1341  }
1342  } // for homing_status_list
1343 
1344  ss_debug << " => max_status: " << static_cast<int>(max_status);
1345 
1346  ROS_DEBUG_THROTTLE(2.0, "TtlManager::readCalibrationStatus : %s", ss_debug.str().c_str());
1347 
1348  // see truth table above
1349  // timeout is here to prevent being stuck here if retrying calibration when already at the butee (then the
1350  // system has no time to switch to "in progress" before "ok" or "error"
1351  if ((!still_in_progress && CalibrationMachineState::State::IN_PROGRESS == _calib_machine_state.status()) ||
1353  (!still_in_progress && _calib_machine_state.isTimeout()))
1354  {
1356  }
1357 
1358  // see truth table above
1360  {
1361  _calibration_status = stepper_joint_driver->interpretHomingData(static_cast<uint8_t>(max_status));
1363 
1364  // In this CalibrationMachineState, the calibration is considered as finished => can activate collision
1365  // detection here we need to wait a short period to make sure no collision detected calibration make a
1366  // wrong collision, so we have to read the collision status once time to reset it.
1367  _isWrongAction = true;
1368  _isRealCollision = true;
1369  _last_collision_detection_activating = ros::Time::now().toSec();
1370  }
1371  }
1372  else
1373  {
1374  ROS_ERROR(
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()));
1378 
1379  hw_errors_increment++;
1380  }
1381  }
1382  else
1383  {
1384  hw_errors_increment++;
1385  }
1386  } // if (_driver_map.count(hw_type) && _driver_map.at(hw_type))
1387  }
1388  else if (hw_type == EHardwareType::NED3PRO_STEPPER)
1389  {
1390  hw_errors_increment = readNed3ProSteppersStatus();
1391  }
1392 
1393  // 2. read conveyors states if has
1394  for (auto &conveyor_state : getConveyorsStates())
1395  {
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))
1403  {
1404  conveyor_state->setGoalDirection(direction);
1405  conveyor_state->setSpeed(conveyor_speed_percent);
1406  conveyor_state->setState(conveyor_speed_percent);
1407  }
1408  else
1409  {
1410  hw_errors_increment++;
1411  }
1412  }
1413  }
1414 
1415  ROS_DEBUG_THROTTLE(2.0, "TtlManager::readCalibrationStatus: _calibration_status: %s",
1416  common::model::StepperCalibrationStatusEnum(_calibration_status).toString().c_str());
1417  ROS_DEBUG_THROTTLE(2.0, "TtlManager::readCalibrationStatus: _calib_machine_state: %d",
1418  static_cast<int>(_calib_machine_state.status()));
1419 
1420  return hw_errors_increment;
1421 }
1422 
1424 {
1425  uint8_t hw_errors_increment = 0;
1426 
1427  EHardwareType hw_type = EHardwareType::NED3PRO_STEPPER;
1428 
1429  // 1. read calibration status if needed
1430 
1431  // we want to check calibration (done at startup and when calibration is started)
1433  {
1434  // When calibration is running, sometimes at an unexpected position, calibration make EE thinks that
1435  // there is a collision Have to disable the feature collision detection in this period
1436  _isRealCollision = false;
1437 
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;
1442  });
1443 
1444  // *********** calibration status, only if initialized
1445  auto [stepper_joint_driver, hw_type] = getJointsStepperDriver();
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))
1449  {
1450  if (stepper_id_list.size() == homing_status_list.size())
1451  {
1452  // TODO(i.ambit) publish calibration message
1453  ttl_driver::CalibrationStatus calibration_status_msg;
1454 
1455  EStepperCalibrationStatus highest_priority_status = EStepperCalibrationStatus::UNINITIALIZED;
1456  // set states accordingly
1457  for (size_t i = 0; i < homing_status_list.size(); ++i)
1458  {
1459  uint8_t id = stepper_id_list.at(i);
1460 
1461  if (_state_map.count(id))
1462  {
1463  // set status in state
1464  auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(id));
1465  if (stepperState && !stepperState->isConveyor())
1466  {
1467  auto status = stepper_joint_driver->interpretHomingData(homing_status_list.at(i));
1468  stepperState->setCalibration(status, 1);
1469 
1470  if (status > highest_priority_status)
1471  highest_priority_status = status;
1472 
1473  calibration_status_msg.ids.push_back(id);
1474 
1475  switch (status)
1476  {
1477  case EStepperCalibrationStatus::IN_PROGRESS:
1478  calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATING);
1479  break;
1480  case EStepperCalibrationStatus::OK:
1481  calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATED);
1482  break;
1483  case EStepperCalibrationStatus::FAIL:
1484  calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATION_ERROR);
1485  break;
1486  default:
1487  calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATION_ERROR);
1488  break;
1489  }
1490 
1491  _calibration_status_publisher.publish(calibration_status_msg);
1492  }
1493  }
1494  } // for homing_status_list
1495  _calibration_status = highest_priority_status;
1496  }
1497  else
1498  {
1499  ROS_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()));
1503 
1504  hw_errors_increment++;
1505  }
1506  }
1507  else
1508  {
1509  hw_errors_increment++;
1510  }
1511  } // if (_driver_map.count(hw_type) && _driver_map.at(hw_type))
1512 
1513  return hw_errors_increment;
1514 }
1515 
1523 int TtlManager::getAllIdsOnBus(vector<uint8_t> &id_list)
1524 {
1525  int result = COMM_RX_FAIL;
1526 
1527  // 1. Get all ids from ttl bus. We can use any driver for that
1528  if (_default_ttl_driver)
1529  {
1530  vector<uint8_t> l_idList;
1531  result = _default_ttl_driver->scan(l_idList);
1532  id_list.insert(id_list.end(), l_idList.begin(), l_idList.end());
1533 
1534  string ids_str;
1535  for (auto const &id : l_idList)
1536  ids_str += to_string(id) + " ";
1537 
1538  ROS_DEBUG_THROTTLE(1, "TtlManager::getAllIdsOnTtlBus - Found ids (%s) on bus using default driver",
1539  ids_str.c_str());
1540 
1541  if (COMM_SUCCESS != result)
1542  {
1543  if (COMM_RX_TIMEOUT != result)
1544  { // -3001
1546  "TtlManager - No motor found. "
1547  "Make sure that motors are correctly connected and powered on.";
1548  }
1549  else
1550  { // -3002 or other
1551  _debug_error_message = "TtlManager - Failed to scan bus.";
1552  }
1553  ROS_WARN_THROTTLE(1,
1554  "TtlManager::getAllIdsOnTtlBus - Broadcast ping failed, "
1555  "result : %d (-3001: timeout, -3002: corrupted packet)",
1556  result);
1557  }
1558  }
1559  else
1560  {
1561  // if no driver, no motors on bus, it is not a failure of scan
1562  result = COMM_SUCCESS;
1563  }
1564 
1565  return result;
1566 }
1567 
1568 // ******************
1569 // Write operations
1570 // ******************
1571 
1578 {
1579  _led_state = led;
1580  int ret = niryo_robot_msgs::CommandStatus::TTL_WRITE_ERROR;
1581 
1582  EHardwareType mType = HardwareTypeEnum(_led_motor_type_cfg.c_str());
1583 
1584  if (mType == EHardwareType::FAKE_DXL_MOTOR)
1585  return niryo_robot_msgs::CommandStatus::SUCCESS;
1586 
1587  // get list of motors of the given type
1588  vector<uint8_t> id_list;
1589  if (_ids_map.count(mType) && _driver_map.count(mType))
1590  {
1591  id_list = _ids_map.at(mType);
1592 
1593  auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(_driver_map.at(mType));
1594  if (driver)
1595  {
1596  // sync write led state
1597  vector<uint8_t> command_led_value(id_list.size(), static_cast<uint8_t>(led));
1598  if (0 <= led && 7 >= led)
1599  {
1600  int result = COMM_TX_FAIL;
1601  for (int error_counter = 0; result != COMM_SUCCESS && error_counter < 5; ++error_counter)
1602  {
1603  ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1604  result = driver->syncWriteLed(id_list, command_led_value);
1605  }
1606 
1607  if (COMM_SUCCESS == result)
1608  ret = niryo_robot_msgs::CommandStatus::SUCCESS;
1609  else
1610  ROS_WARN("TtlManager::setLeds - Failed to write LED");
1611  }
1612  }
1613  else
1614  {
1615  ROS_DEBUG("Set leds failed. Driver is not compatible, check the driver's implementation ");
1616  return niryo_robot_msgs::CommandStatus::FAILURE;
1617  }
1618  }
1619  else
1620  {
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;
1623  }
1624 
1625  return ret;
1626 }
1627 
1636 int TtlManager::sendCustomCommand(uint8_t id, int reg_address, int value, int byte_number)
1637 {
1638  int result = COMM_TX_FAIL;
1639  ROS_DEBUG(
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);
1643 
1644  if (_state_map.count(id) != 0 && _state_map.at(id))
1645  {
1646  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1647 
1648  if (motor_type == EHardwareType::STEPPER || motor_type == EHardwareType::FAKE_STEPPER_MOTOR)
1649  {
1650  return niryo_robot_msgs::CommandStatus::SUCCESS;
1651  }
1652 
1653  if (_driver_map.count(motor_type) && _driver_map.at(motor_type))
1654  {
1655  int32_t value_conv = value;
1656  result = _driver_map.at(motor_type)
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)
1660  {
1661  ROS_WARN("TtlManager::sendCustomCommand - Failed to write custom command: %d", result);
1662  // TODO(Thuc): change TTL_WRITE_ERROR -> WRITE_ERROR
1663  result = niryo_robot_msgs::CommandStatus::TTL_WRITE_ERROR;
1664  }
1665  }
1666  else
1667  {
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;
1671  }
1672  }
1673  else
1674  {
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;
1677  }
1678 
1679  ros::Duration(0.005).sleep();
1680  return result;
1681 }
1682 
1691 int TtlManager::readCustomCommand(uint8_t id, int32_t reg_address, int &value, int byte_number)
1692 {
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);
1696 
1697  if (_state_map.count(id) != 0 && _state_map.at(id))
1698  {
1699  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1700 
1701  if (_driver_map.count(motor_type) && _driver_map.at(motor_type))
1702  {
1703  uint32_t data = 0;
1704  result = _driver_map.at(motor_type)
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);
1707  value = data_conv;
1708 
1709  if (result != COMM_SUCCESS)
1710  {
1711  ROS_WARN("TtlManager::readCustomCommand - Failed to read custom command: %d", result);
1712  result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1713  }
1714  }
1715  else
1716  {
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;
1720  }
1721  }
1722  else
1723  {
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;
1726  }
1727 
1728  ros::Duration(0.005).sleep();
1729  return result;
1730 }
1731 
1744 int TtlManager::readMotorPID(uint8_t id, uint16_t &pos_p_gain, uint16_t &pos_i_gain, uint16_t &pos_d_gain,
1745  uint16_t &vel_p_gain, uint16_t &vel_i_gain, uint16_t &ff1_gain, uint16_t &ff2_gain)
1746 {
1747  int result = COMM_RX_FAIL;
1748 
1749  if (_state_map.count(id) != 0 && _state_map.at(id))
1750  {
1751  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1752 
1753  if (_driver_map.count(motor_type))
1754  {
1755  auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(_driver_map.at(motor_type));
1756  if (driver)
1757  {
1758  std::vector<uint16_t> data;
1759  result = driver->readPID(id, data);
1760 
1761  if (COMM_SUCCESS == result)
1762  {
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);
1770  }
1771  else
1772  {
1773  ROS_WARN("TtlManager::readMotorPID - Failed to read PID: %d", result);
1774  result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1775  return result;
1776  }
1777  }
1778  }
1779  else
1780  {
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;
1784  }
1785  }
1786  else
1787  {
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;
1790  }
1791 
1792  ros::Duration(0.005).sleep();
1793  return result;
1794 }
1795 
1809 int TtlManager::readVelocityProfile(uint8_t id, uint32_t &v_start, uint32_t &a_1, uint32_t &v_1, uint32_t &a_max,
1810  uint32_t &v_max, uint32_t &d_max, uint32_t &d_1, uint32_t &v_stop)
1811 {
1812  int result = COMM_RX_FAIL;
1813 
1814  if (_state_map.count(id) != 0 && _state_map.at(id))
1815  {
1816  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1817  auto [joint_stepper_driver, hw_type] = getJointsStepperDriver();
1818  if (joint_stepper_driver)
1819  {
1820  std::vector<uint32_t> data;
1821  result = joint_stepper_driver->readVelocityProfile(id, data);
1822 
1823  if (COMM_SUCCESS == result)
1824  {
1825  v_start = data.at(0);
1826  a_1 = data.at(1);
1827  v_1 = data.at(2);
1828  a_max = data.at(3);
1829  v_max = data.at(4);
1830  d_max = data.at(5);
1831  d_1 = data.at(6);
1832  v_stop = data.at(7);
1833  }
1834  else
1835  {
1836  ROS_WARN("TtlManager::readVelocityProfile - Failed to read velocity profile: %d", result);
1837  result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1838  return result;
1839  }
1840  }
1841  else
1842  {
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;
1846  }
1847  }
1848  else
1849  {
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;
1852  }
1853 
1854  ros::Duration(0.005).sleep();
1855  return result;
1856 }
1857 
1864 int TtlManager::readMoving(uint8_t id, uint8_t &status)
1865 {
1866  int result = COMM_RX_FAIL;
1867 
1868  if (_state_map.count(id) != 0 && _state_map.at(id))
1869  {
1870  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1871 
1872  // Only used for xl330 and xl320 for now
1873  if (_driver_map.count(motor_type) && (motor_type == EHardwareType::XL330 || motor_type == EHardwareType::XL320 ||
1874  motor_type == EHardwareType::FAKE_DXL_MOTOR))
1875  {
1876  auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(_driver_map.at(motor_type));
1877  if (driver)
1878  {
1879  result = driver->readMoving(id, status);
1880  }
1881  }
1882  else
1883  {
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;
1887  }
1888  }
1889  else
1890  {
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;
1893  }
1894 
1895  ros::Duration(0.005).sleep();
1896  return result;
1897 }
1898 
1905 int TtlManager::readControlMode(uint8_t id, uint8_t &control_mode)
1906 {
1907  int result = COMM_RX_FAIL;
1908 
1909  if (_state_map.count(id) != 0 && _state_map.at(id))
1910  {
1911  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1912 
1913  if (_driver_map.count(motor_type))
1914  {
1915  auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(_driver_map.at(motor_type));
1916  if (driver)
1917  {
1918  result = driver->readControlMode(id, control_mode);
1919  }
1920  }
1921  else
1922  {
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;
1926  }
1927  }
1928  else
1929  {
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;
1932  }
1933 
1934  ros::Duration(0.005).sleep();
1935  return result;
1936 }
1937 
1943 int TtlManager::writeSynchronizeCommand(std::unique_ptr<common::model::AbstractTtlSynchronizeMotorCmd> &&cmd) // NOLINT
1944 {
1945  int result = COMM_TX_ERROR;
1946  ROS_DEBUG_THROTTLE(0.5, "TtlManager::writeSynchronizeCommand: %s", cmd->str().c_str());
1947 
1948  if (cmd->isValid())
1949  {
1950  std::set<EHardwareType> typesToProcess = cmd->getMotorTypes();
1951 
1952  // process all the motors using each successive drivers
1953  for (uint32_t counter = 0; counter < MAX_HW_FAILURE; ++counter)
1954  {
1955  ROS_DEBUG_THROTTLE(0.5, "TtlManager::writeSynchronizeCommand: try to sync write (counter %d)", counter);
1956 
1957  for (auto const &it : _driver_map)
1958  {
1959  if (typesToProcess.count(it.first) != 0)
1960  {
1961  result = COMM_TX_ERROR;
1962 
1963  // syncwrite for this driver. The driver is responsible for sync write only to its associated motors
1964  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it.second);
1965  if (driver)
1966  {
1967  result = driver->writeSyncCmd(cmd->getCmdType(), cmd->getMotorsId(it.first), cmd->getParams(it.first));
1968 
1969  ros::Duration(0.05).sleep();
1970  }
1971 
1972  // if successful, don't process this driver in the next loop
1973  if (COMM_SUCCESS == result)
1974  {
1975  typesToProcess.erase(typesToProcess.find(it.first));
1976  }
1977  else
1978  {
1979  ROS_ERROR("TtlManager::writeSynchronizeCommand : unable to sync write function : %d", result);
1980  }
1981  }
1982  }
1983 
1984  // if all drivers are processed, go out of for loop
1985  if (typesToProcess.empty())
1986  {
1987  result = COMM_SUCCESS;
1988  break;
1989  }
1990 
1991  ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1992  }
1993  }
1994  else
1995  {
1996  ROS_ERROR("TtlManager::writeSynchronizeCommand - Invalid command");
1997  }
1998 
1999  if (COMM_SUCCESS != result)
2000  {
2001  ROS_ERROR_THROTTLE(0.5, "TtlManager::writeSynchronizeCommand - Failed to write synchronize position");
2002  _debug_error_message = "TtlManager - Failed to write synchronize position";
2003  }
2004 
2005  return result;
2006 }
2007 
2013 int TtlManager::writeSingleCommand(std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &&cmd) // NOLINT
2014 {
2015  int result = COMM_TX_ERROR;
2016 
2017  uint8_t id = cmd->getId();
2018 
2019  if (cmd->isValid())
2020  {
2021  int counter = 0;
2022 
2023  ROS_DEBUG("TtlManager::writeSingleCommand: %s", cmd->str().c_str());
2024 
2025  if (_state_map.count(id) && _state_map.at(id))
2026  {
2027  auto state = _state_map.at(id);
2028  while ((COMM_SUCCESS != result) && (counter < 50))
2029  {
2030  EHardwareType hardware_type = state->getHardwareType();
2031  result = COMM_TX_ERROR;
2032  if (_driver_map.count(hardware_type) && _driver_map.at(hardware_type))
2033  {
2034  // writeSingleCmd is in a for loop, we cannot infer that this command will succeed. Thus we cannot move cmd in
2035  // parameter
2036  result = _driver_map.at(hardware_type)->writeSingleCmd(cmd);
2037  }
2038 
2039  counter += 1;
2040 
2041  ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
2042  }
2043  }
2044  else
2045  {
2046  ROS_DEBUG(
2047  "TtlManager::writeSingleCommand: command is sent to a removed hardware component. Skipped or write to a "
2048  "unknow device");
2049  result = COMM_TX_ERROR;
2050  }
2051  }
2052 
2053  if (result != COMM_SUCCESS)
2054  {
2055  ROS_WARN("TtlManager::writeSingleCommand - Fail to write single command : %s", cmd->str().c_str());
2056  _debug_error_message = "TtlManager - Failed to write a single command: " + cmd->str();
2057  }
2058 
2059  return result;
2060 }
2061 
2066 void TtlManager::executeJointTrajectoryCmd(std::vector<std::pair<uint8_t, uint32_t>> cmd_vec)
2067 {
2068  for (auto const &it : _driver_map)
2069  {
2070  // build list of ids and params for this motor
2071  _position_goal_ids.clear();
2072  _position_goal_params.clear();
2073  for (auto const &cmd : cmd_vec)
2074  {
2075  if (_state_map.count(cmd.first) && it.first == _state_map.at(cmd.first)->getHardwareType())
2076  {
2077  _position_goal_ids.emplace_back(cmd.first);
2078  _position_goal_params.emplace_back(cmd.second);
2079  }
2080  }
2081 
2082  // syncwrite for this driver. The driver is responsible for sync write only to its associated motors
2083  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it.second);
2084 
2085  if (driver)
2086  {
2087  int err = driver->syncWritePositionGoal(_position_goal_ids, _position_goal_params);
2088  if (err != COMM_SUCCESS)
2089  {
2090  ROS_WARN("TtlManager::executeJointTrajectoryCmd - Failed to write position");
2091  _debug_error_message = "TtlManager - Failed to write position";
2092  }
2093  }
2094  }
2095 }
2096 
2097 // ******************
2098 // Calibration
2099 // ******************
2100 
2105 {
2106  ROS_DEBUG("TtlManager::startCalibration: starting...");
2107 
2108  std::vector<uint8_t> stepper_list;
2109  if (_ids_map.count(EHardwareType::STEPPER))
2110  {
2111  _calibration_status = EStepperCalibrationStatus::IN_PROGRESS;
2113  stepper_list = _ids_map.at(EHardwareType::STEPPER);
2114  }
2115  else if (_ids_map.count(EHardwareType::NED3PRO_STEPPER))
2116  {
2117  stepper_list = _ids_map.at(EHardwareType::NED3PRO_STEPPER);
2118  }
2119  else if (_ids_map.count(EHardwareType::FAKE_STEPPER_MOTOR))
2120  {
2121  _calibration_status = EStepperCalibrationStatus::IN_PROGRESS;
2123  stepper_list = _ids_map.at(EHardwareType::FAKE_STEPPER_MOTOR);
2124  }
2125 
2126  for (auto const &id : stepper_list)
2127  {
2128  if (_state_map.count(id))
2129  {
2130  auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(id));
2131 
2132  if (stepperState && !stepperState->isConveyor())
2133  {
2134  stepperState->setCalibration(EStepperCalibrationStatus::IN_PROGRESS, 1);
2135  }
2136  }
2137  } // for steppers_list
2138 }
2139 
2144 {
2145  ROS_INFO("TtlManager::resetCalibration: reseting...");
2146 
2147  std::vector<uint8_t> stepper_list;
2148  if (_ids_map.count(EHardwareType::STEPPER))
2149  {
2150  _calibration_status = EStepperCalibrationStatus::UNINITIALIZED;
2152  stepper_list = _ids_map.at(EHardwareType::STEPPER);
2153  }
2154  else if (_ids_map.count(EHardwareType::NED3PRO_STEPPER))
2155  stepper_list = _ids_map.at(EHardwareType::NED3PRO_STEPPER);
2156 
2157  for (auto const id : stepper_list)
2158  {
2159  if (_state_map.count(id))
2160  {
2161  auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(id));
2162 
2163  if (stepperState && !stepperState->isConveyor())
2164  {
2165  stepperState->setCalibration(EStepperCalibrationStatus::UNINITIALIZED, 1);
2166  }
2167  }
2168  } // for steppers_list
2169 }
2170 
2176 int32_t TtlManager::getCalibrationResult(uint8_t motor_id) const
2177 {
2178  if (!_state_map.count(motor_id) && _state_map.at(motor_id))
2179  throw std::out_of_range("TtlManager::getMotorsState: Unknown motor id");
2180 
2181  return std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(motor_id))->getCalibrationValue();
2182 }
2183 
2184 // ******************
2185 // Getters
2186 // ******************
2187 
2194 void TtlManager::getBusState(bool &connection_state, std::vector<uint8_t> &motor_id, std::string &debug_msg) const
2195 {
2196  debug_msg = _debug_error_message;
2197  motor_id = _all_ids_connected;
2198  connection_state = isConnectionOk();
2199 }
2200 
2205 std::vector<std::shared_ptr<JointState>> TtlManager::getMotorsStates() const
2206 {
2207  std::vector<std::shared_ptr<JointState>> states;
2208 
2209  for (const auto &it : _state_map)
2210  {
2211  if (it.second && it.second->getComponentType() == common::model::EComponentType::JOINT)
2212  {
2213  states.emplace_back(std::dynamic_pointer_cast<JointState>(it.second));
2214  }
2215  }
2216 
2217  return states;
2218 }
2219 
2220 std::vector<std::shared_ptr<ConveyorState>> TtlManager::getConveyorsStates() const
2221 {
2222  std::vector<std::shared_ptr<ConveyorState>> conveyor_states;
2223  for (const auto &it : _state_map)
2224  {
2225  if (it.second && it.second->getComponentType() == common::model::EComponentType::CONVEYOR)
2226  {
2227  conveyor_states.emplace_back(std::dynamic_pointer_cast<ConveyorState>(it.second));
2228  }
2229  }
2230 
2231  return conveyor_states;
2232 }
2233 
2239 std::shared_ptr<common::model::AbstractHardwareState> TtlManager::getHardwareState(uint8_t motor_id) const
2240 {
2241  if (!_state_map.count(motor_id) && _state_map.at(motor_id))
2242  throw std::out_of_range("TtlManager::getMotorsState: Unknown motor id");
2243 
2244  return _state_map.at(motor_id);
2245 }
2246 
2247 // ********************
2248 // Private
2249 // ********************
2250 
2255 void TtlManager::addHardwareDriver(EHardwareType hardware_type)
2256 {
2257  // if not already instanciated
2258  if (!_driver_map.count(hardware_type))
2259  {
2260  switch (hardware_type)
2261  {
2262  case EHardwareType::STEPPER:
2263  _driver_map.insert(
2264  std::make_pair(hardware_type, std::make_shared<StepperDriver<StepperReg>>(_portHandler, _packetHandler)));
2265  break;
2266  case EHardwareType::NED3PRO_STEPPER:
2267  _driver_map.insert(std::make_pair(
2268  hardware_type, std::make_shared<Ned3ProStepperDriver<Ned3ProStepperReg>>(_portHandler, _packetHandler)));
2269  break;
2270  case EHardwareType::FAKE_STEPPER_MOTOR:
2271  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<MockStepperDriver>(_fake_data)));
2272  break;
2273  case EHardwareType::XL430:
2274  _driver_map.insert(
2275  std::make_pair(hardware_type, std::make_shared<DxlDriver<XL430Reg>>(_portHandler, _packetHandler)));
2276  break;
2277  case EHardwareType::XC430:
2278  _driver_map.insert(
2279  std::make_pair(hardware_type, std::make_shared<DxlDriver<XC430Reg>>(_portHandler, _packetHandler)));
2280  break;
2281  case EHardwareType::XM430:
2282  _driver_map.insert(
2283  std::make_pair(hardware_type, std::make_shared<DxlDriver<XM430Reg>>(_portHandler, _packetHandler)));
2284  break;
2285  case EHardwareType::XL320:
2286  _driver_map.insert(
2287  make_pair(hardware_type, std::make_shared<DxlDriver<XL320Reg>>(_portHandler, _packetHandler)));
2288  break;
2289  case EHardwareType::XL330:
2290  _driver_map.insert(
2291  std::make_pair(hardware_type, std::make_shared<DxlDriver<XL330Reg>>(_portHandler, _packetHandler)));
2292  break;
2293  case EHardwareType::XH430:
2294  _driver_map.insert(
2295  std::make_pair(hardware_type, std::make_shared<DxlDriver<XH430Reg>>(_portHandler, _packetHandler)));
2296  break;
2297  case EHardwareType::FAKE_DXL_MOTOR:
2298  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<MockDxlDriver>(_fake_data)));
2299  break;
2300  case EHardwareType::END_EFFECTOR:
2301  _driver_map.insert(std::make_pair(
2302  hardware_type, std::make_shared<EndEffectorDriver<EndEffectorReg>>(_portHandler, _packetHandler)));
2303  break;
2304  case EHardwareType::NED3PRO_END_EFFECTOR:
2305  _driver_map.insert(std::make_pair(
2306  hardware_type,
2308  break;
2309  case EHardwareType::FAKE_END_EFFECTOR:
2310  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<MockEndEffectorDriver>(_fake_data)));
2311  break;
2312  default:
2313  ROS_ERROR("TtlManager - Unable to instanciate driver, unknown type");
2314  break;
2315  }
2316  }
2317 }
2318 
2322 void TtlManager::readFakeConfig(bool use_simu_gripper, bool use_simu_conveyor)
2323 {
2324  _fake_data = std::make_shared<FakeTtlData>();
2325 
2326  if (_nh.hasParam("fake_params"))
2327  {
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));
2333 
2334  if (_nh.hasParam("fake_params/steppers"))
2335  {
2336  std::string current_ns = "fake_params/steppers/";
2337  retrieveFakeMotorData(current_ns, _fake_data->stepper_registers);
2338  }
2339 
2340  if (_nh.hasParam("fake_params/dynamixels/"))
2341  {
2342  std::string current_ns = "fake_params/dynamixels/";
2343  retrieveFakeMotorData(current_ns, _fake_data->dxl_registers);
2344  }
2345 
2346  if (use_simu_gripper && _nh.hasParam("fake_params/tool/"))
2347  {
2348  std::string current_ns = "fake_params/tool/";
2349  retrieveFakeMotorData(current_ns, _fake_data->dxl_registers);
2350  }
2351 
2352  if (_nh.hasParam("fake_params/end_effector"))
2353  {
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);
2361 
2362  assert(!id_list.empty());
2363  assert(!temperature_list.empty());
2364  assert(!voltage_list.empty());
2365  assert(!firmware_list.empty());
2366 
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));
2370 
2371  _fake_data->end_effector.firmware = firmware_list.at(0);
2372  }
2373 
2374  if (use_simu_conveyor && _nh.hasParam("fake_params/conveyors/"))
2375  {
2376  std::string current_ns = "fake_params/conveyors/";
2377  retrieveFakeMotorData(current_ns, _fake_data->stepper_registers);
2378  }
2379 
2380  _fake_data->updateFullIdList();
2381  }
2382 }
2383 
2390 {
2391  auto joint_states = getMotorsStates();
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())
2396  {
2397  return {};
2398  }
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 };
2403 }
2404 
2405 } // namespace ttl_driver
end_effector_driver.hpp
ttl_driver::TtlManager::startCalibration
void startCalibration() override
TtlManager::startCalibration.
Definition: ttl_manager.cpp:2104
ttl_driver::StepperDriver
The StepperDriver class.
Definition: stepper_driver.hpp:38
ttl_driver::TtlManager::addHardwareComponent
int addHardwareComponent(std::shared_ptr< common::model::AbstractHardwareState > &&state) override
TtlManager::addHardwareComponent add hardware component like joint, ee, tool... to ttl manager.
Definition: ttl_manager.cpp:272
ttl_driver::TtlManager::CalibrationMachineState::State::IDLE
@ IDLE
ttl_driver::TtlManager::readEndEffectorStatus
bool readEndEffectorStatus()
TtlManager::readEndEffectorStatus.
Definition: ttl_manager.cpp:865
ttl_driver::TtlManager::readCustomCommand
int readCustomCommand(uint8_t id, int32_t reg_address, int &value, int byte_number)
TtlManager::readCustomCommand.
Definition: ttl_manager.cpp:1691
mock_dxl_driver.hpp
ttl_driver::TtlManager::_debug_error_message
std::string _debug_error_message
Definition: ttl_manager.hpp:228
ttl_driver::TtlManager::_current_tool_vector
std::vector< int > _current_tool_vector
Definition: ttl_manager.hpp:261
ttl_driver::TtlManager::getJointsStepperDriver
GetJointsStepperDriverResult getJointsStepperDriver()
: Return the driver of the joints
Definition: ttl_manager.cpp:2389
ttl_driver::TtlManager::writeSingleCommand
int writeSingleCommand(std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &&cmd)
TtlManager::writeSingleCommand.
Definition: ttl_manager.cpp:2013
ttl_driver::TTL_SCAN_MISSING_MOTOR
constexpr int TTL_SCAN_MISSING_MOTOR
Definition: ttl_manager.hpp:70
ttl_driver::TtlManager::_state_map
std::map< uint8_t, std::shared_ptr< common::model::AbstractHardwareState > > _state_map
Definition: ttl_manager.hpp:213
ttl_driver::TtlManager::_calib_machine_state
CalibrationMachineState _calib_machine_state
Definition: ttl_manager.hpp:314
ttl_driver::TtlManager::readHardwareStatus
bool readHardwareStatus()
TtlManager::readHardwareStatus.
Definition: ttl_manager.cpp:1131
ttl_driver::TtlManager::getCalibrationResult
int32_t getCalibrationResult(uint8_t id) const override
TtlManager::getCalibrationResult.
Definition: ttl_manager.cpp:2176
ttl_driver::TtlManager::retrieveFakeMotorData
void retrieveFakeMotorData(const std::string &current_ns, std::map< uint8_t, Reg > &fake_params, std::vector< int > hw_ids={})
TtlManager::retrieveFakeMotorData.
Definition: ttl_manager.hpp:400
ttl_driver::TtlManager::_calibration_status
common::model::EStepperCalibrationStatus _calibration_status
Definition: ttl_manager.hpp:243
ttl_driver::TtlManager::_nh
ros::NodeHandle _nh
Definition: ttl_manager.hpp:200
ttl_driver::TtlManager::scanAndCheck
int scanAndCheck() override
TtlManager::scanAndCheck.
Definition: ttl_manager.cpp:473
ttl_driver::TtlManager::checkCollision
bool checkCollision()
TtlManager::checkCollision.
Definition: ttl_manager.cpp:980
ttl_driver::TtlManager::CalibrationMachineState::State::IN_PROGRESS
@ IN_PROGRESS
ttl_driver::TtlManager::_hw_fail_counter_read
uint32_t _hw_fail_counter_read
Definition: ttl_manager.hpp:233
mock_end_effector_driver.hpp
ttl_driver::TtlManager::_position_goal_params
std::vector< uint32_t > _position_goal_params
Definition: ttl_manager.hpp:259
stepper_reg.hpp
ttl_driver::TTL_FAIL_OPEN_PORT
constexpr int TTL_FAIL_OPEN_PORT
Definition: ttl_manager.hpp:64
ttl_driver::TtlManager::_position_goal_ids
std::vector< uint8_t > _position_goal_ids
Definition: ttl_manager.hpp:258
ttl_driver::TtlManager::_all_ids_connected
std::vector< uint8_t > _all_ids_connected
Definition: ttl_manager.hpp:209
ttl_driver::TtlManager::_last_collision_detection_activating
double _last_collision_detection_activating
Definition: ttl_manager.hpp:251
ttl_driver::TtlManager::sendCustomCommand
int sendCustomCommand(uint8_t id, int reg_address, int value, int byte_number)
TtlManager::sendCustomCommand.
Definition: ttl_manager.cpp:1636
end_effector_reg.hpp
ttl_driver::TtlManager::readSteppersStatus
uint8_t readSteppersStatus()
TtlManager::readCalibrationStatus : reads specific steppers related information (ned2 only)
Definition: ttl_manager.cpp:1254
ttl_driver::TtlManager::TtlManager
TtlManager()=delete
ttl_driver::TtlManager::CalibrationMachineState::State::UPDATING
@ UPDATING
ttl_driver::TTL_FAIL_PORT_SET_BAUDRATE
constexpr int TTL_FAIL_PORT_SET_BAUDRATE
Definition: ttl_manager.hpp:66
ttl_driver::TtlManager::changeId
int changeId(common::model::EHardwareType motor_type, uint8_t old_id, uint8_t new_id)
TtlManager::changeId.
Definition: ttl_manager.cpp:414
ttl_driver::TtlManager::getAllIdsOnBus
int getAllIdsOnBus(std::vector< uint8_t > &id_list)
TtlManager::getAllIdsOnDxlBus.
Definition: ttl_manager.cpp:1523
ttl_driver::TtlManager::removeHardwareComponent
void removeHardwareComponent(uint8_t id) override
TtlManager::removeHardwareComponent.
Definition: ttl_manager.cpp:363
ttl_driver::Ned3ProStepperDriver
The Ned3ProStepperDriver class.
Definition: ned3pro_stepper_driver.hpp:40
ttl_driver::TtlManager::readHomingAbsPosition
bool readHomingAbsPosition()
Definition: ttl_manager.cpp:680
ttl_driver::TtlManager::_device_name
std::string _device_name
Definition: ttl_manager.hpp:206
ned3pro_stepper_driver.hpp
ttl_driver::TtlManager::getHardwareState
std::shared_ptr< common::model::AbstractHardwareState > getHardwareState(uint8_t motor_id) const
TtlManager::getHardwareState.
Definition: ttl_manager.cpp:2239
ttl_driver::TtlManager::readJointsStatus
bool readJointsStatus()
TtlManager::readJointsStatus.
Definition: ttl_manager.cpp:753
ttl_driver::TtlManager::executeJointTrajectoryCmd
void executeJointTrajectoryCmd(std::vector< std::pair< uint8_t, uint32_t >> cmd_vec)
TtlManager::executeJointTrajectoryCmd.
Definition: ttl_manager.cpp:2066
ttl_driver::TtlManager::_packetHandler
std::shared_ptr< dynamixel::PacketHandler > _packetHandler
Definition: ttl_manager.hpp:202
ttl_driver::TtlManager::init
bool init(ros::NodeHandle &nh) override
TtlManager::init.
Definition: ttl_manager.cpp:108
ttl_driver::TtlManager::getConveyorsStates
std::vector< std::shared_ptr< common::model::ConveyorState > > getConveyorsStates() const
Definition: ttl_manager.cpp:2220
ttl_driver::TtlManager::getPosition
uint32_t getPosition(const common::model::JointState &motor_state)
TtlManager::getPosition.
Definition: ttl_manager.cpp:645
ttl_driver::TtlManager::resetCalibration
void resetCalibration() override
TtlManager::resetCalibration.
Definition: ttl_manager.cpp:2143
ttl_driver::TtlManager::CalibrationMachineState::State::STARTING
@ STARTING
ttl_driver::TtlManager::CalibrationMachineState::status
State status()
Definition: ttl_manager.hpp:298
ttl_driver::TtlManager::getBusState
void getBusState(bool &connection_state, std::vector< uint8_t > &motor_id, std::string &debug_msg) const override
TtlManager::getBusState.
Definition: ttl_manager.cpp:2194
ttl_driver::DxlDriver
The DxlDriver class.
Definition: dxl_driver.hpp:44
ttl_driver::TtlManager::changeTool
bool changeTool(int value, std::string &message, int &status)
TtlManager::changeTool.
Definition: ttl_manager.cpp:159
ttl_driver::TtlManager::resetTorques
void resetTorques()
TtlManager::resetTorques.
Definition: ttl_manager.cpp:606
ttl_driver::TtlManager::isMotorType
bool isMotorType(common::model::EHardwareType type)
TtlManager::isMotorType.
Definition: ttl_manager.cpp:397
ttl_driver::TtlManager::_available_tools
std::vector< int > _available_tools
Definition: ttl_manager.hpp:260
ttl_driver::TtlManager::readCollisionStatus
bool readCollisionStatus()
TtlManager::readCollisionStatus.
Definition: ttl_manager.cpp:1064
stepper_driver.hpp
ttl_driver::TtlManager::MAX_READ_EE_FAILURE
static constexpr uint32_t MAX_READ_EE_FAILURE
Definition: ttl_manager.hpp:240
ttl_driver::TtlManager::setLeds
int setLeds(int led)
TtlManager::setLeds.
Definition: ttl_manager.cpp:1577
ttl_driver::TtlManager::_isWrongAction
bool _isWrongAction
Definition: ttl_manager.hpp:253
ttl_driver::TtlManager::writeSynchronizeCommand
int writeSynchronizeCommand(std::unique_ptr< common::model::AbstractTtlSynchronizeMotorCmd > &&cmd)
TtlManager::writeSynchronizeCommand.
Definition: ttl_manager.cpp:1943
ttl_driver::TtlManager::_collision_status
bool _collision_status
Definition: ttl_manager.hpp:250
mock_stepper_driver.hpp
ttl_driver::TtlManager::ping
bool ping(uint8_t id) override
TtlManager::ping.
Definition: ttl_manager.cpp:542
ttl_driver::EndEffectorDriver
The EndEffectorDriver class.
Definition: end_effector_driver.hpp:42
dxl_driver.hpp
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::TtlManager::_default_ttl_driver
std::shared_ptr< ttl_driver::AbstractTtlDriver > _default_ttl_driver
Definition: ttl_manager.hpp:220
ttl_driver::TtlManager::rebootHardware
int rebootHardware(uint8_t id)
TtlManager::rebootHardware.
Definition: ttl_manager.cpp:560
ttl_driver::TtlManager::_fake_data
std::shared_ptr< FakeTtlData > _fake_data
Definition: ttl_manager.hpp:246
ned3pro_end_effector_driver.hpp
ttl_driver::TtlManager::readNed3ProSteppersStatus
uint8_t readNed3ProSteppersStatus()
Definition: ttl_manager.cpp:1423
ttl_driver::TtlManager::CalibrationMachineState::reset
void reset()
Definition: ttl_manager.hpp:274
ttl_driver::TtlManager::_end_effector_fail_counter_read
uint32_t _end_effector_fail_counter_read
Definition: ttl_manager.hpp:234
ttl_driver::TtlManager::_is_connection_ok
bool _is_connection_ok
Definition: ttl_manager.hpp:227
nh
static std::unique_ptr< ros::NodeHandle > nh
Definition: service_client_ned2.cpp:31
ttl_driver::TtlManager::isConnectionOk
bool isConnectionOk() const override
TtlManager::isConnectionOk.
Definition: ttl_manager.hpp:323
ttl_driver::TtlManager::_position_list
std::vector< uint32_t > _position_list
Definition: ttl_manager.hpp:257
ttl_driver::TtlManager::CalibrationMachineState::start
void start()
Definition: ttl_manager.hpp:279
ttl_driver::TtlManager::_led_state
int _led_state
Definition: ttl_manager.hpp:236
ttl_driver::TtlManager::_simulation_mode
bool _simulation_mode
Definition: ttl_manager.hpp:247
ttl_driver::TTL_SCAN_OK
constexpr int TTL_SCAN_OK
Definition: ttl_manager.hpp:69
ttl_driver::TtlManager::readMoving
int readMoving(uint8_t id, uint8_t &status)
TtlManager::readMoving.
Definition: ttl_manager.cpp:1864
ttl_driver::TtlManager::_removed_motor_id_list
std::vector< uint8_t > _removed_motor_id_list
Definition: ttl_manager.hpp:210
ttl_driver::TtlManager::_current_tool_id
uint32_t _current_tool_id
Definition: ttl_manager.hpp:231
ttl_driver::TtlManager::_sync_mutex
std::mutex _sync_mutex
Definition: ttl_manager.hpp:204
ttl_driver::TtlManager::_ids_map
std::map< common::model::EHardwareType, std::vector< uint8_t > > _ids_map
Definition: ttl_manager.hpp:215
ttl_driver::Ned3ProEndEffectorDriver
The Ned3ProEndEffectorDriver class.
Definition: ned3pro_end_effector_driver.hpp:42
ttl_driver::TtlManager::CalibrationMachineState::next
void next()
next : next state, stops at updating (dont circle)
Definition: ttl_manager.hpp:288
ttl_driver::TtlManager::_portHandler
std::shared_ptr< dynamixel::PortHandler > _portHandler
Definition: ttl_manager.hpp:201
ttl_driver::TtlManager::GetJointsStepperDriverResult
Definition: ttl_manager.hpp:192
ttl_driver::TtlManager::CalibrationMachineState::isTimeout
bool isTimeout()
Definition: ttl_manager.hpp:303
ttl_driver::TtlManager::_driver_map
std::map< common::model::EHardwareType, std::shared_ptr< ttl_driver::AbstractTtlDriver > > _driver_map
Definition: ttl_manager.hpp:217
ttl_driver::TtlManager::setupCommunication
int setupCommunication() override
TtlManager::setupCommunication.
Definition: ttl_manager.cpp:215
ttl_driver::TtlManager::MAX_HW_FAILURE
static constexpr uint32_t MAX_HW_FAILURE
Definition: ttl_manager.hpp:239
ttl_driver::TtlManager::getMotorsStates
std::vector< std::shared_ptr< common::model::JointState > > getMotorsStates() const
TtlManager::getMotorsStates.
Definition: ttl_manager.cpp:2205
ttl_driver::TtlManager::~TtlManager
~TtlManager() override
TtlManager::~TtlManager.
Definition: ttl_manager.cpp:94
ttl_driver::TtlManager::_conveyor_list
std::vector< uint8_t > _conveyor_list
Definition: ttl_manager.hpp:224
ttl_driver::TtlManager::addHardwareDriver
void addHardwareDriver(common::model::EHardwareType hardware_type) override
TtlManager::addHardwareDriver.
Definition: ttl_manager.cpp:2255
ttl_driver::TtlManager::_calibration_status_publisher
ros::Publisher _calibration_status_publisher
Definition: ttl_manager.hpp:255
ttl_driver::TtlManager::_led_motor_type_cfg
std::string _led_motor_type_cfg
Definition: ttl_manager.hpp:237
ttl_driver::TtlManager::readControlMode
int readControlMode(uint8_t id, uint8_t &control_mode)
TtlManager::readControlMode.
Definition: ttl_manager.cpp:1905
ttl_driver::TTL_BUS_PROTOCOL_VERSION
constexpr float TTL_BUS_PROTOCOL_VERSION
Definition: ttl_manager.hpp:63
ttl_manager.hpp
ttl_driver::TtlManager::readMotorPID
int 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, uint16_t &ff2_gain)
TtlManager::readMotorPID.
Definition: ttl_manager.cpp:1744
ttl_driver::TtlManager::readVelocityProfile
int 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)
TtlManager::readVelocityProfile.
Definition: ttl_manager.cpp:1809
ttl_driver::TtlManager::_baudrate
int _baudrate
Definition: ttl_manager.hpp:207
ttl_driver::TtlManager::readFakeConfig
void readFakeConfig(bool use_simu_gripper, bool use_simu_conveyor)
TtlManager::readFakeConfig.
Definition: ttl_manager.cpp:2322
ttl_driver::TtlManager::_isRealCollision
bool _isRealCollision
Definition: ttl_manager.hpp:252
fake_ttl_data.hpp


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Fri Mar 6 2026 15:24:15