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 
45 #include "dynamixel_sdk/packet_handler.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::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;
74 
75 namespace ttl_driver
76 {
80 TtlManager::TtlManager(ros::NodeHandle &nh) : _nh(nh), _debug_error_message("TtlManager - No connection with TTL motors has been made yet")
81 {
82  ROS_DEBUG("TtlManager - ctor");
83 
84  init(nh);
85 
86  if (COMM_SUCCESS != setupCommunication())
87  ROS_WARN("TtlManager - TTL Communication Failed");
88 }
89 
94 {
95  if (_portHandler)
96  {
97  _portHandler->clearPort();
98  _portHandler->closePort();
99  }
100 }
101 
107 bool TtlManager::init(ros::NodeHandle &nh)
108 {
109  // get params from rosparams
110  bool use_simu_gripper{false};
111  bool use_simu_conveyor{false};
112 
113  nh.getParam("bus_params/uart_device_name", _device_name);
114  nh.getParam("bus_params/baudrate", _baudrate);
115  nh.getParam("led_motor", _led_motor_type_cfg);
116 
117  nh.getParam("simulation_mode", _simulation_mode);
118  nh.getParam("simu_gripper", use_simu_gripper);
119  nh.getParam("simu_conveyor", use_simu_conveyor);
120 
121  ROS_DEBUG("TtlManager::init - Dxl : set port name (%s), baudrate(%d)", _device_name.c_str(), _baudrate);
122  ROS_DEBUG("TtlManager::init - led motor type config : %s", _led_motor_type_cfg.c_str());
123 
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");
126 
127  if (!_simulation_mode)
128  {
129  _portHandler.reset(dynamixel::PortHandler::getPortHandler(_device_name.c_str()));
130  _packetHandler.reset(dynamixel::PacketHandler::getPacketHandler(TTL_BUS_PROTOCOL_VERSION));
131 
132  // init default ttl driver for common operations between drivers
133  _default_ttl_driver = std::make_shared<StepperDriver<StepperReg>>(_portHandler, _packetHandler);
134  }
135  else
136  {
137  readFakeConfig(use_simu_gripper, use_simu_conveyor);
138  _default_ttl_driver = std::make_shared<MockStepperDriver>(_fake_data);
139  }
140 
141  _calibration_status_publisher = nh.advertise<ttl_driver::CalibrationStatus>("calibration_status", 1, true);
142 
143  return true;
144 }
145 
151 {
152  int ret = COMM_NOT_AVAILABLE;
153 
154  ROS_DEBUG("TtlManager::setupCommunication - initializing connection...");
155 
156  // fake drivers will always succeed for the communication
157  if (_simulation_mode)
158  {
159  ret = COMM_SUCCESS;
160  }
161  else
162  {
163  // Ttl bus setup
164  if (_portHandler)
165  {
166  _debug_error_message.clear();
167 
168  // Open port
169  if (_portHandler->openPort())
170  {
171  // Set baudrate
172  if (_portHandler->setBaudRate(_baudrate))
173  {
174  // wait a bit to be sure the connection is established
175  ros::Duration(0.1).sleep();
176 
177  // clear port
178  _portHandler->clearPort();
179 
180  ret = COMM_SUCCESS;
181  }
182  else
183  {
184  ROS_ERROR("TtlManager::setupCommunication - Failed to set baudrate for Dynamixel bus");
185  _debug_error_message = "TtlManager - Failed to set baudrate for Dynamixel bus";
187  }
188  }
189  else
190  {
191  ROS_ERROR("TtlManager::setupCommunication - Failed to open Uart port for Dynamixel bus");
192  _debug_error_message = "TtlManager - Failed to open Uart port for Dynamixel bus";
193  ret = TTL_FAIL_OPEN_PORT;
194  }
195  }
196  else
197  ROS_ERROR("TtlManager::setupCommunication - Invalid port handler");
198  }
199 
200  return ret;
201 }
202 
207 int TtlManager::addHardwareComponent(std::shared_ptr<common::model::AbstractHardwareState> &&state) // NOLINT
208 {
209  if (!state)
210  {
211  return niryo_robot_msgs::CommandStatus::FAILURE;
212  }
213 
214  EHardwareType hardware_type = state->getHardwareType();
215  uint8_t id = state->getId();
216 
217  ROS_DEBUG("TtlManager::addHardwareComponent : %s", state->str().c_str());
218 
219  addHardwareDriver(hardware_type);
220 
221  auto driver_it = _driver_map.find(hardware_type);
222  if (driver_it == _driver_map.end())
223  {
224  ROS_ERROR("TtlManager::addHardwareComponent - No driver found for hardware type %d", static_cast<int>(hardware_type));
225  return niryo_robot_msgs::CommandStatus::FAILURE;
226  }
227  auto driver = driver_it->second;
228 
229  uint16_t model_number = 0;
230  // check if the driver is valid for this hardware
231  if (state->getStrictModelNumber() && driver->checkModelNumber(id, model_number) != COMM_SUCCESS)
232  {
233  ROS_WARN("TtlManager::addHardwareComponent - Model number check failed for hardware id %d", id);
234  return niryo_robot_msgs::CommandStatus::HARDWARE_NOT_SUPPORTED;
235  }
236  else if (driver->getModelNumber(id, model_number) != COMM_SUCCESS)
237  {
238  ROS_WARN("TtlManager::addHardwareComponent - Unable to retrieve model number for hardware id %d", id);
239  return niryo_robot_msgs::CommandStatus::HARDWARE_NOT_SUPPORTED;
240  }
241 
242  state->setModelNumber(model_number);
243 
244  // update firmware version
245  std::string version;
246  int res = COMM_RX_FAIL;
247  for (int tries = 10; tries > 0; tries--)
248  {
249  res = driver->readFirmwareVersion(id, version);
250  if (COMM_SUCCESS == res)
251  {
252  state->setFirmwareVersion(version);
253  break;
254  }
255  ros::Duration(0.1).sleep();
256  }
257 
258  if (COMM_SUCCESS != res)
259  {
260  ROS_WARN("TtlManager::addHardwareComponent : Unable to retrieve firmware version for "
261  "hardware id %d : result = %d",
262  id, res);
263  }
264 
265  // add state to state map
266  _state_map[id] = state;
267 
268  // add id to ids_map
269  _ids_map[hardware_type].emplace_back(id);
270 
271  // add to global lists
272  if (common::model::EComponentType::CONVEYOR == state->getComponentType())
273  {
274  if (std::find(_conveyor_list.begin(), _conveyor_list.end(), id) == _conveyor_list.end())
275  _conveyor_list.emplace_back(id);
276  }
277 
278  // Reset the calibration if we add a new joint and it is not a simulated one
279  if (common::model::EComponentType::JOINT == state->getComponentType())
280  {
281  if (!(common::model::EHardwareType::FAKE_STEPPER_MOTOR == hardware_type
282  || common::model::EHardwareType::FAKE_DXL_MOTOR == hardware_type))
283  {
284  _calibration_status = EStepperCalibrationStatus::UNINITIALIZED;
285  }
286  }
287 
289  return niryo_robot_msgs::CommandStatus::SUCCESS;
290 }
291 
297 {
298  ROS_DEBUG("TtlManager::removeMotor - Remove motor id: %d", id);
299 
300  if (_state_map.count(id) && _state_map.at(id))
301  {
302  EHardwareType type = _state_map.at(id)->getHardwareType();
303 
304  // std::remove to remove hypothetic duplicates too
305  if (_ids_map.count(type))
306  {
307  auto &ids = _ids_map.at(type);
308  ids.erase(std::remove(ids.begin(), ids.end(), id), ids.end());
309  if (ids.empty())
310  {
311  _ids_map.erase(type);
312  }
313  }
314 
315  _state_map.erase(id);
316  }
317  // remove id from conveyor list if they contains id
318  _conveyor_list.erase(std::remove(_conveyor_list.begin(), _conveyor_list.end(), id), _conveyor_list.end());
319 
321 }
322 
329 bool TtlManager::isMotorType(EHardwareType type)
330 {
331  // All motors have value under 7 (check in EHardwareType)
332  return (static_cast<int>(type) <= 7);
333 }
334 
335 // ****************
336 // commands
337 // ****************
338 
346 int TtlManager::changeId(EHardwareType motor_type, uint8_t old_id, uint8_t new_id)
347 {
348  int ret = COMM_TX_FAIL;
349 
350  if (old_id == new_id)
351  {
352  ret = COMM_SUCCESS;
353  }
354  else if (_driver_map.count(motor_type))
355  {
356  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(_driver_map.at(motor_type));
357 
358  if (driver)
359  {
360  ret = driver->changeId(old_id, new_id);
361  if (COMM_SUCCESS == ret)
362  {
363  // update all maps
364  auto i_state = _state_map.find(old_id);
365  // update all maps
366  if (i_state != _state_map.end())
367  {
368  // insert new_id in map, move i_state->second to its new place
369  std::swap(_state_map[new_id], i_state->second);
370  // update all maps
371  _state_map.erase(i_state);
372 
373  assert(_state_map.at(new_id));
374 
375  // update conveyor list if needed
376  if (common::model::EComponentType::CONVEYOR == _state_map.at(new_id)->getComponentType())
377  {
378  // change old id into new id in vector
379  auto iter = std::find(_conveyor_list.begin(), _conveyor_list.end(), old_id);
380  if (iter != _conveyor_list.end())
381  *iter = new_id;
382  }
383  }
384  if (_ids_map.count(motor_type))
385  {
386  // update all maps
387  _ids_map.at(motor_type).erase(std::remove(_ids_map.at(motor_type).begin(), _ids_map.at(motor_type).end(), old_id), _ids_map.at(motor_type).end());
388 
389  // update all maps
390  _ids_map.at(motor_type).emplace_back(new_id);
391  }
392  }
393  }
394  }
395 
396  return ret;
397 }
398 
404 {
405  ROS_DEBUG("TtlManager::scanAndCheck");
406  int result = COMM_PORT_BUSY;
407 
408  _is_connection_ok = false;
409 
410  // 1. retrieve list of connected motors
411  _all_ids_connected.clear();
412  for (int counter = 0; counter < 50 && COMM_SUCCESS != result; ++counter)
413  {
415  ROS_DEBUG_COND(COMM_SUCCESS != result, "TtlManager::scanAndCheck status: %d (counter: %d)", result, counter);
416  ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
417  }
418 
419  if (COMM_SUCCESS == result)
420  {
421  // 2. update list of removed ids and update corresponding states
422  _removed_motor_id_list.clear();
423  std::string error_motors_message;
424  for (auto &istate : _state_map)
425  {
426  if (istate.second)
427  {
428  uint8_t id = istate.first;
429  auto it = find(_all_ids_connected.begin(), _all_ids_connected.end(), id);
430  // not found
431  if (it == _all_ids_connected.end())
432  {
433  _removed_motor_id_list.emplace_back(id);
434  error_motors_message += " " + to_string(id);
435  istate.second->setConnectionStatus(true);
436  }
437  else
438  {
439  istate.second->setConnectionStatus(false);
440  }
441  }
442  }
443 
444  if (_removed_motor_id_list.empty())
445  {
446  _is_connection_ok = true;
447  _debug_error_message.clear();
448  result = TTL_SCAN_OK;
449  }
450  else
451  {
452  _debug_error_message = "Motor(s):" + error_motors_message + " do not seem to be connected";
453  result = TTL_SCAN_MISSING_MOTOR;
454  }
455  }
456  else
457  {
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");
460  }
461 
462  return result;
463 }
464 
472 bool TtlManager::ping(uint8_t id)
473 {
474  int result = false;
475 
477  {
478  if (COMM_SUCCESS == _default_ttl_driver->ping(id))
479  result = true;
480  }
481 
482  return result;
483 }
484 
490 int TtlManager::rebootHardware(uint8_t hw_id)
491 {
492  int return_value = COMM_TX_FAIL;
493 
494  if (_state_map.count(hw_id) != 0 && _state_map.at(hw_id))
495  {
496  EHardwareType type = _state_map.at(hw_id)->getHardwareType();
497  ROS_DEBUG("TtlManager::rebootHardware - Reboot hardware with ID: %d", hw_id);
498  if (_driver_map.count(type) && _driver_map.at(type))
499  {
500  return_value = _driver_map.at(type)->reboot(hw_id);
501  if (COMM_SUCCESS == return_value)
502  {
503  std::string version;
504  int res = COMM_RX_FAIL;
505  for (int tries = 10; tries > 0; tries--)
506  {
507  res = _driver_map.at(type)->readFirmwareVersion(hw_id, version);
508  if (COMM_SUCCESS == res)
509  {
510  _state_map.at(hw_id)->setFirmwareVersion(version);
511  break;
512  }
513  ros::Duration(0.1).sleep();
514  }
515 
516  if (COMM_SUCCESS != res)
517  {
518  ROS_WARN("TtlManager::addHardwareComponent : Unable to retrieve firmware version for "
519  "hardware id %d : result = %d",
520  hw_id, res);
521  }
522  }
523  ROS_WARN_COND(COMM_SUCCESS != return_value, "TtlManager::rebootHardware - Failed to reboot hardware: %d", return_value);
524  }
525  }
526 
527  return return_value;
528 }
529 
535 {
536  for (auto const &it : _driver_map)
537  {
538  auto hw_type = it.first;
539  auto driver = std::dynamic_pointer_cast<ttl_driver::AbstractMotorDriver>(it.second);
540 
541  if (driver && _ids_map.count(hw_type) && !_ids_map.at(hw_type).empty())
542  {
543  // we retrieve all the associated id for the type of the current driver
544  vector<uint8_t> ids_list = _ids_map.at(hw_type);
545 
546  auto jStates = getMotorsStates();
547 
548  for (size_t i = 0; i < ids_list.size(); ++i)
549  {
550  auto jState_it = std::find_if(jStates.begin(), jStates.end(), [i](const std::shared_ptr<JointState> &jState){
551  return i == jState->getId();
552  });
553  if (jState_it == jStates.end())
554  {
555  continue;
556  }
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());
560  } // for ids_list
561  }
562  } // for _driver_map
563 }
564 
565 // ******************
566 // Read operations
567 // ******************
568 
574 uint32_t TtlManager::getPosition(const JointState &motor_state)
575 {
576  uint32_t position = 0;
577  EHardwareType hardware_type = motor_state.getHardwareType();
578  if (_driver_map.count(hardware_type))
579  {
580  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(_driver_map.at(hardware_type));
581  if (driver)
582  {
584  {
585  if (COMM_SUCCESS == driver->readPosition(motor_state.getId(), position))
586  {
588  break;
589  }
590  }
591  }
592 
593  if (0 < _hw_fail_counter_read)
594  {
595  ROS_ERROR_THROTTLE(1, "TtlManager::getPosition - motor connection problem - Failed to read from bus");
596  _debug_error_message = "TtlManager - Connection problem with Bus.";
598  _is_connection_ok = false;
599  }
600  }
601  else
602  {
603  ROS_ERROR_THROTTLE(1, "TtlManager::getPosition - Driver not found for requested motor id");
604  _debug_error_message = "TtlManager::getPosition - Driver not found for requested motor id";
605  }
606  return position;
607 }
608 
610 {
611  EHardwareType hw_type(EHardwareType::STEPPER);
612  auto driver = std::dynamic_pointer_cast<ttl_driver::StepperDriver<ttl_driver::StepperReg>>(_driver_map[hw_type]);
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  // we retrieve all the associated id for the type of the current driver
619  vector<uint32_t> homing_abs_position_list;
620 
621  // retrieve joint status
622  int res = driver->syncReadHomingAbsPosition(ids_list, homing_abs_position_list);
623  if (COMM_SUCCESS == res)
624  {
625  if (ids_list.size() == homing_abs_position_list.size())
626  {
627  // set motors states accordingly
628  for (size_t i = 0; i < ids_list.size(); ++i)
629  {
630  uint8_t id = ids_list.at(i);
631 
632  if (_state_map.count(id))
633  {
634  auto state = std::dynamic_pointer_cast<common::model::StepperMotorState>(_state_map.at(id));
635  if (state)
636  {
637  state->setHomingAbsPosition(static_cast<uint32_t>(homing_abs_position_list.at(i)));
638  }
639  else
640  {
641  ROS_ERROR("TtlManager::readHomingAbsPosition - null pointer");
642  return false;
643  }
644  }
645  else
646  {
647  ROS_ERROR("TtlManager::readHomingAbsPosition - No hardware state assossiated to ID: %d", static_cast<int>(id));
648  return false;
649  }
650  }
651  }
652  else
653  {
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()));
656  return false;
657  }
658  }
659  else
660  {
661  ROS_ERROR("TtlManager::readHomingAbsPosition - communication error: %d", static_cast<int>(res));
662  return false;
663  }
664  }
665  else
666  {
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()));
669  return false;
670  }
671 
672  return true;
673 }
674 
680 {
681  uint8_t hw_errors_increment = 0;
682 
683  // syncread position for all motors.
684  // for ned and one -> we need at least one xl430 and one xl320 drivers as they are different
685 
686  for (auto const &it : _driver_map)
687  {
688  auto hw_type = it.first;
689  auto driver = std::dynamic_pointer_cast<ttl_driver::AbstractMotorDriver>(it.second);
690 
691  if (!driver)
692  {
693  continue;
694  }
695  auto id_list_it = _ids_map.find(hw_type);
696  if (id_list_it == _ids_map.end())
697  {
698  continue;
699  }
700  auto ids_list = id_list_it->second;
701 
702  if (ids_list.empty())
703  {
704  continue;
705  }
706 
707  // we retrieve all the associated id for the type of the current driver
708  _position_list.clear();
709 
710  // retrieve joint status
711  int res = driver->syncReadPosition(ids_list, _position_list);
712  if (COMM_SUCCESS == res)
713  {
714  if (ids_list.size() == _position_list.size())
715  {
716  // set motors states accordingly
717  for (size_t i = 0; i < ids_list.size(); ++i)
718  {
719  uint8_t id = ids_list.at(i);
720 
721  if (_state_map.count(id))
722  {
723  auto state = std::dynamic_pointer_cast<common::model::AbstractMotorState>(_state_map.at(id));
724  if (state)
725  {
726  state->setPosition(static_cast<int>((_position_list.at(i))));
727  }
728  }
729  }
730  }
731  else
732  {
733  // warn to avoid sound and light error on high level (error on ROS_ERROR)
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++;
738  }
739  }
740  else
741  {
742  // debug to avoid sound and light error on high level (error on ROS_ERROR)
743  // also for Ned which has much more errors on XL320 motor
744  ROS_DEBUG("TtlManager::readJointStatus : Fail to sync read joint state - "
745  "driver fail to syncReadPosition");
746  hw_errors_increment++;
747  }
748  } // for driver_map
749 
750  // check collision by END_EFFECTOR
751  if (_isRealCollision)
752  {
754  }
755  else
756  {
757  _collision_status = false;
758  // check collision by END_EFFECTOR
759  if (_isRealCollision)
760  {
761  checkCollision();
762  }
763  else
764  {
765  _collision_status = false;
766  }
767  }
768 
769  ROS_DEBUG_THROTTLE(2, "_hw_fail_counter_read, hw_errors_increment: %d, %d", _hw_fail_counter_read, hw_errors_increment);
770 
771  // we reset the global error variable only if no errors
772  if (0 == hw_errors_increment)
773  {
775  }
776  else
777  {
778  _hw_fail_counter_read += hw_errors_increment;
779  }
780 
781  return (0 == hw_errors_increment);
782 }
783 
789 {
790  bool res = false;
791 
792  // hardware_version is not available within this class to know whether there is a ned2/ned3pro eef
793  // however if hardware_type == ned2 _driver_map will contain EHardwareType::END_EFFECTOR
794  // and if hardware_type == ned3pro _driver_map will contain EHardwareType::NED3PRO_END_EFFECTOR
795  EHardwareType ee_type;
796 
797  if (_simulation_mode)
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;
803 
804 
805  if (_driver_map.count(ee_type))
806  {
807  unsigned int hw_errors_increment = 0;
808 
809  auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(_driver_map.at(ee_type));
810  if (driver)
811  {
812  if (_ids_map.count(ee_type) && !_ids_map.at(ee_type).empty())
813  {
814  uint8_t id = _ids_map.at(ee_type).front();
815 
816  if (_state_map.count(id))
817  {
818  // we retrieve the associated id for the end effector
819  auto state = std::dynamic_pointer_cast<EndEffectorState>(_state_map[id]);
820 
821  if (state)
822  {
823  vector<common::model::EActionType> action_list;
824 
825  // ********** buttons
826  // get action of free driver button, save pos button, custom button
827  if (COMM_SUCCESS == driver->syncReadButtonsStatus(id, action_list))
828  {
829  for (uint8_t i = 0; i < action_list.size(); i++)
830  {
831  state->setButtonStatus(i, action_list.at(i));
832  // In case free driver button, it we hold this button, normally, because of the small threshold of collision detection
833  // this action make EE confuse that it is a collision. That's why when we hold buttons, we need to deactivate the detection of collision.
834  if (action_list.at(i) != common::model::EActionType::NO_ACTION)
835  {
836  _isRealCollision = false;
837  }
838  else if (!_isRealCollision)
839  {
840  // when previous action is not no_action => need to wait a short period to make sure no collision detected
841  // Note, we need to read one time the status of collision just after releasing button to reset the status.
842  _isRealCollision = true;
843  _isWrongAction = true;
844  _last_collision_detection_activating = ros::Time::now().toSec();
845  }
846  }
847  }
848  else
849  {
850  hw_errors_increment++;
851  }
852 
853  // ********** digital data
854  bool digital_data{};
855  if (COMM_SUCCESS == driver->readDigitalInput(id, digital_data))
856  {
857  state->setDigitalIn(digital_data);
858  }
859  else
860  {
861  hw_errors_increment++;
862  }
863  } // if (state)
864  }
865  } // if (_ids_map.count(EHardwareType::END_EFFECTOR))
866  } // if (driver)
867 
868  // we reset the global error variable only if no errors
869  if (0 == hw_errors_increment)
870  {
872  _debug_error_message.clear();
873 
874  res = true;
875  }
876  else
877  {
878  ROS_DEBUG_COND(_end_effector_fail_counter_read > 10, "TtlManager::readEndEffectorStatus: nb error > 10 : %d", _end_effector_fail_counter_read);
879  _end_effector_fail_counter_read += hw_errors_increment;
880  }
881 
883  {
884  ROS_ERROR("TtlManager::readEndEffectorStatus - motor connection problem - Failed to read from bus (hw_fail_counter_read : %d)", _end_effector_fail_counter_read);
886  _debug_error_message = "TtlManager - Connection problem with physical Bus.";
887  }
888  }
889 
890  return res;
891 }
892 
899 {
900  bool res = false;
901 
902  // hardware_version is not available within this class to know whether there is a ned2/ned3pro eef
903  // however if hardware_type == ned2 _driver_map will contain EHardwareType::END_EFFECTOR
904  // and if hardware_type == ned3pro _driver_map will contain EHardwareType::NED3PRO_END_EFFECTOR
905  EHardwareType ee_type;
906 
907  if (_simulation_mode)
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;
913 
914  if (_driver_map.count(ee_type))
915  {
916  unsigned int hw_errors_increment = 0;
917 
918  auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(_driver_map.at(ee_type));
919  if (driver)
920  {
921  if (_ids_map.count(ee_type) && !_ids_map.at(ee_type).empty())
922  {
923  uint8_t id = _ids_map.at(ee_type).front();
924 
925  // ********** collision
926  // not accept other status of collistion in 1 second if it detected a collision
928  {
929  bool last_statut = _collision_status;
930  if (COMM_SUCCESS == driver->readCollisionStatus(id, _collision_status))
931  {
932  if (last_statut == _collision_status && _collision_status)
933  {
934  // if we have a collision, we will publish the statut collision only once
935  // This avoid that the delay in reading statut influent to next movement.
936  _collision_status = false;
937  }
938  else if (_collision_status)
939  {
940  if (_isWrongAction)
941  {
942  // if an action did a wrong detection of collision, we need to read once to reset the status
943  _isWrongAction = false;
944  _collision_status = false;
945  }
946  else
947  _last_collision_detection_activating = ros::Time::now().toSec();
948  }
949  }
950  else
951  {
952  hw_errors_increment++;
953  }
954  }
955  else if (ros::Time::now().toSec() - _last_collision_detection_activating >= 1.0)
956  {
958  }
959  } // if (_ids_map.count(EHardwareType::END_EFFECTOR))
960  } // if (driver)
961 
962  // we reset the global error variable only if no errors
963  if (0 == hw_errors_increment)
964  {
966  res = true;
967  }
968  else
969  {
970  ROS_DEBUG_COND(_end_effector_fail_counter_read > 10, "TtlManager::checkCollision: nb error > 10 : %d", _end_effector_fail_counter_read);
971  _end_effector_fail_counter_read += hw_errors_increment;
972  }
973  }
974  return res;
975 }
976 
982 {
983  bool res = false;
984 
985  // hardware_version is not available within this class to know whether there is a ned2/ned3pro eef
986  // however if hardware_type == ned2 _driver_map will contain EHardwareType::END_EFFECTOR
987  // and if hardware_type == ned3pro _driver_map will contain EHardwareType::NED3PRO_END_EFFECTOR
988  EHardwareType ee_type;
989 
990  if (_simulation_mode)
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;
996 
997  if (_driver_map.count(ee_type))
998  {
999  auto driver = std::dynamic_pointer_cast<AbstractEndEffectorDriver>(_driver_map.at(ee_type));
1000 
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  // don't accept other status of collistion in 1 second if it detected a collision
1010  {
1011  if (COMM_SUCCESS == driver->readCollisionStatus(id, _collision_status))
1012  {
1013  res = true;
1014 
1015  if (_collision_status)
1016  {
1017  if (_isWrongAction)
1018  {
1019  // if an action did a wrong detection of collision, we need to read once to reset the status
1020  _isWrongAction = false;
1021  _collision_status = false;
1022  }
1023  else
1024  {
1025  _last_collision_detection_activating = ros::Time::now().toSec();
1026  }
1027  }
1028  }
1029  else
1030  {
1032  }
1033  }
1034  else if (ros::Time::now().toSec() - _last_collision_detection_activating >= 1.0)
1035  {
1037  }
1038  }
1039  }
1040  }
1041 
1042  return res;
1043 }
1044 
1049 {
1050  bool res = false;
1051 
1052  unsigned int hw_errors_increment = 0;
1053 
1054  // take all hw status dedicated drivers
1055  for (auto const &it : _driver_map)
1056  {
1057  auto type = it.first;
1058  auto driver = it.second;
1059 
1060  if (driver && _ids_map.count(type) && !_ids_map.at(type).empty())
1061  {
1062  // we retrieve all the associated id for the type of the current driver
1063  vector<uint8_t> ids_list = _ids_map.at(type);
1064 
1065  // 1. syncread for all motors
1066  // ********** voltage and Temperature
1067  vector<std::pair<double, uint8_t>> hw_data_list;
1068 
1069  if (COMM_SUCCESS != driver->syncReadHwStatus(ids_list, hw_data_list))
1070  {
1071  // this operation can fail, it is normal, so no error message
1072  hw_errors_increment++;
1073  }
1074  else if (ids_list.size() != hw_data_list.size())
1075  {
1076  // however, if we have a mismatch here, it is not normal
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()));
1080 
1081  hw_errors_increment++;
1082  }
1083 
1084  // ********** error state
1085  vector<uint8_t> hw_error_status_list;
1086 
1087  if (COMM_SUCCESS != driver->syncReadHwErrorStatus(ids_list, hw_error_status_list))
1088  {
1089  hw_errors_increment++;
1090  }
1091  else if (ids_list.size() != hw_error_status_list.size())
1092  {
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()));
1096 
1097  hw_errors_increment++;
1098  }
1099 
1100  // 2. set motors states accordingly
1101  for (size_t i = 0; i < ids_list.size(); ++i)
1102  {
1103  uint8_t id = ids_list.at(i);
1104 
1105  if (_state_map.count(id) && _state_map.at(id))
1106  {
1107  auto state = _state_map.at(id);
1108 
1109  // ************** temperature and voltage
1110  if (hw_data_list.size() > i)
1111  {
1112  double voltage = (hw_data_list.at(i)).first;
1113  uint8_t temperature = (hw_data_list.at(i)).second;
1114 
1115  state->setTemperature(temperature);
1116  state->setRawVoltage(voltage);
1117  }
1118 
1119  // ********** error state
1120  if (hw_error_status_list.size() > i)
1121  {
1122  state->setHardwareError(hw_error_status_list.at(i));
1123  }
1124 
1125  // interpret any error code into message (even if not retrieved now)
1126  string hardware_message = driver->interpretErrorState(state->getHardwareError());
1127  state->setHardwareError(hardware_message);
1128  }
1129  } // for ids_list
1130  } // if driver
1131  } // for (auto it : _hw_status_driver_map)
1132 
1133  // ********** steppers related informations (conveyor and calibration)
1134  hw_errors_increment += readSteppersStatus();
1135 
1136  // we reset the global error variable only if no errors
1137  if (0 == hw_errors_increment)
1138  {
1140  _debug_error_message.clear();
1141 
1142  res = true;
1143  }
1144  else
1145  {
1146  _hw_fail_counter_read += hw_errors_increment;
1147  }
1148 
1149  // if too much errors, disconnect
1151  {
1152  ROS_ERROR_THROTTLE(1,
1153  "TtlManager::readHardwareStatus - motor connection problem - "
1154  "Failed to read from bus (hw_fail_counter_read : %d)",
1157  res = false;
1158  _is_connection_ok = false;
1159  _debug_error_message = "TtlManager - Connection problem with physical Bus.";
1160  }
1161 
1162  return res;
1163 }
1164 
1170 {
1171  uint8_t hw_errors_increment = 0;
1172 
1173  // take all hw status dedicated drivers
1174  auto [stepper_joint_driver, hw_type] = getJointsStepperDriver();
1175  if (stepper_joint_driver)
1176  {
1177  if (hw_type == EHardwareType::STEPPER || hw_type == EHardwareType::FAKE_STEPPER_MOTOR )
1178  {
1179  // 1. read calibration status if needed
1180 
1181  // we want to check calibration (done at startup and when calibration is started)
1183  {
1184  // When calibration is running, sometimes at an unexpected position, calibration make EE thinks that there is a collision
1185  // Have to disable the feature collision detection in this period
1186  _isRealCollision = false;
1187 
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; });
1192 
1193  /* Truth Table
1194  * still_in_progress | state | new state
1195  * 0 | IDLE = IDLE
1196  * 0 | START = START
1197  * 0 | PROG > UPDAT
1198  * 0 | UPDAT R IDLE
1199  * 1 | IDLE = IDLE
1200  * 1 | START > PROG
1201  * 1 | PROG = PROG
1202  * 1 | UPDAT = UPDAT
1203  */
1204 
1205  // *********** calibration status, only if initialized
1206  std::vector<uint8_t> homing_status_list;
1207  if (COMM_SUCCESS == stepper_joint_driver->syncReadHomingStatus(stepper_id_list, homing_status_list))
1208  {
1209  if (stepper_id_list.size() == homing_status_list.size())
1210  {
1211  // max status need to be kept not converted into EStepperCalibrationStatus because max status is "in progress" in the enum
1212  int max_status = -1;
1213 
1214  // debug only
1215  std::ostringstream ss_debug;
1216  ss_debug << "homing status : ";
1217 
1218  bool still_in_progress = false;
1219 
1220  // set states accordingly
1221  for (size_t i = 0; i < homing_status_list.size(); ++i)
1222  {
1223  uint8_t id = stepper_id_list.at(i);
1224  ss_debug << static_cast<int>(homing_status_list.at(i)) << ", ";
1225 
1226  if (_state_map.count(id))
1227  {
1228  EStepperCalibrationStatus status = stepper_joint_driver->interpretHomingData(homing_status_list.at(i));
1229 
1230  // set status in state
1231  auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(id));
1232  if (stepperState && !stepperState->isConveyor())
1233  {
1234  stepperState->setCalibration(status, 1);
1235 
1236  // get max status of all motors (to retrieve potential errors)
1237  // carefull to those possible cases :
1238  // 1, 1, 1
1239  // 1, 2, 1
1240  // 0, 2, 2
1241  // 2, 0, 2
1242 
1243  // if 0, uninitialized, else, take max
1244  // we need to keep the status unconverted to have the correct order
1245  if (0 != max_status && homing_status_list.at(i) > max_status)
1246  max_status = homing_status_list.at(i);
1247 
1248  // if one status is in progress or uinitialized, we are really in progress
1249  if ((0 == homing_status_list.at(i)) || EStepperCalibrationStatus::IN_PROGRESS == status)
1250  {
1251  still_in_progress = true;
1252  }
1253  }
1254  }
1255  } // for homing_status_list
1256 
1257  ss_debug << " => max_status: " << static_cast<int>(max_status);
1258 
1259  ROS_DEBUG_THROTTLE(2.0, "TtlManager::readCalibrationStatus : %s", ss_debug.str().c_str());
1260 
1261  // see truth table above
1262  // timeout is here to prevent being stuck here if retrying calibration when already at the butee (then the system has no time to switch to "in progress"
1263  // before "ok" or "error"
1264  if ((!still_in_progress && CalibrationMachineState::State::IN_PROGRESS == _calib_machine_state.status()) ||
1266  (!still_in_progress && _calib_machine_state.isTimeout()))
1267  {
1269  }
1270 
1271  // see truth table above
1273  {
1274  _calibration_status = stepper_joint_driver->interpretHomingData(static_cast<uint8_t>(max_status));
1276 
1277  // In this CalibrationMachineState, the calibration is considered as finished => can activate collision detection here
1278  // we need to wait a short period to make sure no collision detected
1279  // calibration make a wrong collision, so we have to read the collision status once time to reset it.
1280  _isWrongAction = true;
1281  _isRealCollision = true;
1282  _last_collision_detection_activating = ros::Time::now().toSec();
1283  }
1284  }
1285  else
1286  {
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()));
1290 
1291  hw_errors_increment++;
1292  }
1293  }
1294  else
1295  {
1296  hw_errors_increment++;
1297  }
1298  } // if (_driver_map.count(hw_type) && _driver_map.at(hw_type))
1299  }
1300  else if (hw_type == EHardwareType::NED3PRO_STEPPER)
1301  {
1302  hw_errors_increment = readNed3ProSteppersStatus();
1303  }
1304 
1305  // 2. read conveyors states if has
1306  for (auto &conveyor_state : getConveyorsStates())
1307  {
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))
1314  {
1315  conveyor_state->setGoalDirection(direction);
1316  conveyor_state->setSpeed(conveyor_speed_percent);
1317  conveyor_state->setState(conveyor_speed_percent);
1318  }
1319  else
1320  {
1321  hw_errors_increment++;
1322  }
1323  }
1324  }
1325 
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()));
1328 
1329  return hw_errors_increment;
1330 }
1331 
1333 {
1334  uint8_t hw_errors_increment = 0;
1335 
1336  EHardwareType hw_type = EHardwareType::NED3PRO_STEPPER;
1337 
1338  // 1. read calibration status if needed
1339 
1340  // we want to check calibration (done at startup and when calibration is started)
1342  {
1343  // When calibration is running, sometimes at an unexpected position, calibration make EE thinks that
1344  // there is a collision Have to disable the feature collision detection in this period
1345  _isRealCollision = false;
1346 
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;
1352  });
1353 
1354  // *********** calibration status, only if initialized
1355  auto [stepper_joint_driver, hw_type] = getJointsStepperDriver();
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))
1359  {
1360  if (stepper_id_list.size() == homing_status_list.size())
1361  {
1362  // TODO(i.ambit) publish calibration message
1363  ttl_driver::CalibrationStatus calibration_status_msg;
1364 
1365  EStepperCalibrationStatus highest_priority_status = EStepperCalibrationStatus::UNINITIALIZED;
1366  // set states accordingly
1367  for (size_t i = 0; i < homing_status_list.size(); ++i)
1368  {
1369  uint8_t id = stepper_id_list.at(i);
1370 
1371  if (_state_map.count(id))
1372  {
1373  // set status in state
1374  auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(id));
1375  if (stepperState && !stepperState->isConveyor())
1376  {
1377  auto status = stepper_joint_driver->interpretHomingData(homing_status_list.at(i));
1378  stepperState->setCalibration(status, 1);
1379 
1380  if (status > highest_priority_status)
1381  highest_priority_status = status;
1382 
1383  calibration_status_msg.ids.push_back(id);
1384 
1385  switch (status)
1386  {
1387  case EStepperCalibrationStatus::IN_PROGRESS:
1388  calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATING);
1389  break;
1390  case EStepperCalibrationStatus::OK:
1391  calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATED);
1392  break;
1393  case EStepperCalibrationStatus::FAIL:
1394  calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATION_ERROR);
1395  break;
1396  default:
1397  calibration_status_msg.status.push_back(ttl_driver::CalibrationStatus::CALIBRATION_ERROR);
1398  break;
1399  }
1400 
1401  _calibration_status_publisher.publish(calibration_status_msg);
1402  }
1403  }
1404  } // for homing_status_list
1405  _calibration_status = highest_priority_status;
1406  }
1407  else
1408  {
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()));
1412 
1413  hw_errors_increment++;
1414  }
1415  }
1416  else
1417  {
1418  hw_errors_increment++;
1419  }
1420  } // if (_driver_map.count(hw_type) && _driver_map.at(hw_type))
1421 
1422  return hw_errors_increment;
1423 }
1424 
1432 int TtlManager::getAllIdsOnBus(vector<uint8_t> &id_list)
1433 {
1434  int result = COMM_RX_FAIL;
1435 
1436  // 1. Get all ids from ttl bus. We can use any driver for that
1437  if (_default_ttl_driver)
1438  {
1439  vector<uint8_t> l_idList;
1440  result = _default_ttl_driver->scan(l_idList);
1441  id_list.insert(id_list.end(), l_idList.begin(), l_idList.end());
1442 
1443  string ids_str;
1444  for (auto const &id : l_idList)
1445  ids_str += to_string(id) + " ";
1446 
1447  ROS_DEBUG_THROTTLE(1, "TtlManager::getAllIdsOnTtlBus - Found ids (%s) on bus using default driver", ids_str.c_str());
1448 
1449  if (COMM_SUCCESS != result)
1450  {
1451  if (COMM_RX_TIMEOUT != result)
1452  { // -3001
1453  _debug_error_message = "TtlManager - No motor found. "
1454  "Make sure that motors are correctly connected and powered on.";
1455  }
1456  else
1457  { // -3002 or other
1458  _debug_error_message = "TtlManager - Failed to scan bus.";
1459  }
1460  ROS_WARN_THROTTLE(1,
1461  "TtlManager::getAllIdsOnTtlBus - Broadcast ping failed, "
1462  "result : %d (-3001: timeout, -3002: corrupted packet)",
1463  result);
1464  }
1465  }
1466  else
1467  {
1468  // if no driver, no motors on bus, it is not a failure of scan
1469  result = COMM_SUCCESS;
1470  }
1471 
1472  return result;
1473 }
1474 
1475 // ******************
1476 // Write operations
1477 // ******************
1478 
1485 {
1486  _led_state = led;
1487  int ret = niryo_robot_msgs::CommandStatus::TTL_WRITE_ERROR;
1488 
1489  EHardwareType mType = HardwareTypeEnum(_led_motor_type_cfg.c_str());
1490 
1491  if (mType == EHardwareType::FAKE_DXL_MOTOR)
1492  return niryo_robot_msgs::CommandStatus::SUCCESS;
1493 
1494  // get list of motors of the given type
1495  vector<uint8_t> id_list;
1496  if (_ids_map.count(mType) && _driver_map.count(mType))
1497  {
1498  id_list = _ids_map.at(mType);
1499 
1500  auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(_driver_map.at(mType));
1501  if (driver)
1502  {
1503  // sync write led state
1504  vector<uint8_t> command_led_value(id_list.size(), static_cast<uint8_t>(led));
1505  if (0 <= led && 7 >= led)
1506  {
1507  int result = COMM_TX_FAIL;
1508  for (int error_counter = 0; result != COMM_SUCCESS && error_counter < 5; ++error_counter)
1509  {
1510  ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1511  result = driver->syncWriteLed(id_list, command_led_value);
1512  }
1513 
1514  if (COMM_SUCCESS == result)
1515  ret = niryo_robot_msgs::CommandStatus::SUCCESS;
1516  else
1517  ROS_WARN("TtlManager::setLeds - Failed to write LED");
1518  }
1519  }
1520  else
1521  {
1522  ROS_DEBUG("Set leds failed. Driver is not compatible, check the driver's implementation ");
1523  return niryo_robot_msgs::CommandStatus::FAILURE;
1524  }
1525  }
1526  else
1527  {
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;
1530  }
1531 
1532  return ret;
1533 }
1534 
1543 int TtlManager::sendCustomCommand(uint8_t id, int reg_address, int value, int byte_number)
1544 {
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);
1549 
1550  if (_state_map.count(id) != 0 && _state_map.at(id))
1551  {
1552  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1553 
1554  if (motor_type == EHardwareType::STEPPER || motor_type == EHardwareType::FAKE_STEPPER_MOTOR) {
1555  return niryo_robot_msgs::CommandStatus::SUCCESS;
1556  }
1557 
1558  if (_driver_map.count(motor_type) && _driver_map.at(motor_type))
1559  {
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)
1563  {
1564  ROS_WARN("TtlManager::sendCustomCommand - Failed to write custom command: %d", result);
1565  // TODO(Thuc): change TTL_WRITE_ERROR -> WRITE_ERROR
1566  result = niryo_robot_msgs::CommandStatus::TTL_WRITE_ERROR;
1567  }
1568  }
1569  else
1570  {
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;
1573  }
1574  }
1575  else
1576  {
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;
1579  }
1580 
1581  ros::Duration(0.005).sleep();
1582  return result;
1583 }
1584 
1593 int TtlManager::readCustomCommand(uint8_t id, int32_t reg_address, int &value, int byte_number)
1594 {
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);
1597 
1598  if (_state_map.count(id) != 0 && _state_map.at(id))
1599  {
1600  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1601 
1602  if (_driver_map.count(motor_type) && _driver_map.at(motor_type))
1603  {
1604  uint32_t data = 0;
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);
1607  value = data_conv;
1608 
1609  if (result != COMM_SUCCESS)
1610  {
1611  ROS_WARN("TtlManager::readCustomCommand - Failed to read custom command: %d", result);
1612  result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1613  }
1614  }
1615  else
1616  {
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;
1619  }
1620  }
1621  else
1622  {
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;
1625  }
1626 
1627  ros::Duration(0.005).sleep();
1628  return result;
1629 }
1630 
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,
1644  uint16_t &ff2_gain)
1645 {
1646  int result = COMM_RX_FAIL;
1647 
1648  if (_state_map.count(id) != 0 && _state_map.at(id))
1649  {
1650  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1651 
1652  if (_driver_map.count(motor_type))
1653  {
1654  auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(_driver_map.at(motor_type));
1655  if (driver)
1656  {
1657  std::vector<uint16_t> data;
1658  result = driver->readPID(id, data);
1659 
1660  if (COMM_SUCCESS == result)
1661  {
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);
1669  }
1670  else
1671  {
1672  ROS_WARN("TtlManager::readMotorPID - Failed to read PID: %d", result);
1673  result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1674  return result;
1675  }
1676  }
1677  }
1678  else
1679  {
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;
1682  }
1683  }
1684  else
1685  {
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;
1688  }
1689 
1690  ros::Duration(0.005).sleep();
1691  return result;
1692 }
1693 
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)
1708 {
1709  int result = COMM_RX_FAIL;
1710 
1711  if (_state_map.count(id) != 0 && _state_map.at(id))
1712  {
1713  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1714  auto [joint_stepper_driver, hw_type] = getJointsStepperDriver();
1715  if (joint_stepper_driver)
1716  {
1717  std::vector<uint32_t> data;
1718  result = joint_stepper_driver->readVelocityProfile(id, data);
1719 
1720  if (COMM_SUCCESS == result)
1721  {
1722  v_start = data.at(0);
1723  a_1 = data.at(1);
1724  v_1 = data.at(2);
1725  a_max = data.at(3);
1726  v_max = data.at(4);
1727  d_max = data.at(5);
1728  d_1 = data.at(6);
1729  v_stop = data.at(7);
1730  }
1731  else
1732  {
1733  ROS_WARN("TtlManager::readVelocityProfile - Failed to read velocity profile: %d", result);
1734  result = niryo_robot_msgs::CommandStatus::TTL_READ_ERROR;
1735  return result;
1736  }
1737  }
1738  else
1739  {
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;
1742  }
1743  }
1744  else
1745  {
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;
1748  }
1749 
1750  ros::Duration(0.005).sleep();
1751  return result;
1752 }
1753 
1760 int TtlManager::readMoving(uint8_t id, uint8_t &status)
1761 {
1762  int result = COMM_RX_FAIL;
1763 
1764  if (_state_map.count(id) != 0 && _state_map.at(id))
1765  {
1766  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1767 
1768  // Only used for xl330 and xl320 for now
1769  if (_driver_map.count(motor_type) && (motor_type == EHardwareType::XL330 || motor_type == EHardwareType::XL320|| motor_type == EHardwareType::FAKE_DXL_MOTOR))
1770  {
1771  auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(_driver_map.at(motor_type));
1772  if (driver)
1773  {
1774  result = driver->readMoving(id, status);
1775  }
1776  }
1777  else
1778  {
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;
1781  }
1782  }
1783  else
1784  {
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;
1787  }
1788 
1789  ros::Duration(0.005).sleep();
1790  return result;
1791 }
1792 
1799 int TtlManager::readControlMode(uint8_t id, uint8_t &control_mode)
1800 {
1801  int result = COMM_RX_FAIL;
1802 
1803  if (_state_map.count(id) != 0 && _state_map.at(id))
1804  {
1805  EHardwareType motor_type = _state_map.at(id)->getHardwareType();
1806 
1807  if (_driver_map.count(motor_type))
1808  {
1809  auto driver = std::dynamic_pointer_cast<AbstractDxlDriver>(_driver_map.at(motor_type));
1810  if (driver)
1811  {
1812  result = driver->readControlMode(id, control_mode);
1813  }
1814  }
1815  else
1816  {
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;
1819  }
1820  }
1821  else
1822  {
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;
1825  }
1826 
1827  ros::Duration(0.005).sleep();
1828  return result;
1829 }
1830 
1836 int TtlManager::writeSynchronizeCommand(std::unique_ptr<common::model::AbstractTtlSynchronizeMotorCmd> &&cmd) // NOLINT
1837 {
1838  int result = COMM_TX_ERROR;
1839  ROS_DEBUG_THROTTLE(0.5, "TtlManager::writeSynchronizeCommand: %s", cmd->str().c_str());
1840 
1841  if (cmd->isValid())
1842  {
1843  std::set<EHardwareType> typesToProcess = cmd->getMotorTypes();
1844 
1845  // process all the motors using each successive drivers
1846  for (uint32_t counter = 0; counter < MAX_HW_FAILURE; ++counter)
1847  {
1848  ROS_DEBUG_THROTTLE(0.5, "TtlManager::writeSynchronizeCommand: try to sync write (counter %d)", counter);
1849 
1850  for (auto const &it : _driver_map)
1851  {
1852  if (typesToProcess.count(it.first) != 0)
1853  {
1854  result = COMM_TX_ERROR;
1855 
1856  // syncwrite for this driver. The driver is responsible for sync write only to its associated motors
1857  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it.second);
1858  if (driver)
1859  {
1860  result = driver->writeSyncCmd(cmd->getCmdType(), cmd->getMotorsId(it.first), cmd->getParams(it.first));
1861 
1862  ros::Duration(0.05).sleep();
1863  }
1864 
1865  // if successful, don't process this driver in the next loop
1866  if (COMM_SUCCESS == result)
1867  {
1868  typesToProcess.erase(typesToProcess.find(it.first));
1869  }
1870  else
1871  {
1872  ROS_ERROR("TtlManager::writeSynchronizeCommand : unable to sync write function : %d", result);
1873  }
1874  }
1875  }
1876 
1877  // if all drivers are processed, go out of for loop
1878  if (typesToProcess.empty())
1879  {
1880  result = COMM_SUCCESS;
1881  break;
1882  }
1883 
1884  ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1885  }
1886  }
1887  else
1888  {
1889  ROS_ERROR("TtlManager::writeSynchronizeCommand - Invalid command");
1890  }
1891 
1892  if (COMM_SUCCESS != result)
1893  {
1894  ROS_ERROR_THROTTLE(0.5, "TtlManager::writeSynchronizeCommand - Failed to write synchronize position");
1895  _debug_error_message = "TtlManager - Failed to write synchronize position";
1896  }
1897 
1898  return result;
1899 }
1900 
1906 int TtlManager::writeSingleCommand(std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &&cmd) // NOLINT
1907 {
1908  int result = COMM_TX_ERROR;
1909 
1910  uint8_t id = cmd->getId();
1911 
1912  if (cmd->isValid())
1913  {
1914  int counter = 0;
1915 
1916  ROS_DEBUG("TtlManager::writeSingleCommand: %s", cmd->str().c_str());
1917 
1918  if (_state_map.count(id) && _state_map.at(id))
1919  {
1920  auto state = _state_map.at(id);
1921  while ((COMM_SUCCESS != result) && (counter < 50))
1922  {
1923  EHardwareType hardware_type = state->getHardwareType();
1924  result = COMM_TX_ERROR;
1925  if (_driver_map.count(hardware_type) && _driver_map.at(hardware_type))
1926  {
1927  // writeSingleCmd is in a for loop, we cannot infer that this command will succeed. Thus we cannot move cmd in parameter
1928  result = _driver_map.at(hardware_type)->writeSingleCmd(cmd);
1929  }
1930 
1931  counter += 1;
1932 
1933  ros::Duration(TIME_TO_WAIT_IF_BUSY).sleep();
1934  }
1935  }
1936  else
1937  {
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;
1940  }
1941  }
1942 
1943  if (result != COMM_SUCCESS)
1944  {
1945  ROS_WARN("TtlManager::writeSingleCommand - Fail to write single command : %s", cmd->str().c_str());
1946  _debug_error_message = "TtlManager - Failed to write a single command: " + cmd->str();
1947  }
1948 
1949  return result;
1950 }
1951 
1956 void TtlManager::executeJointTrajectoryCmd(std::vector<std::pair<uint8_t, uint32_t>> cmd_vec)
1957 {
1958  for (auto const &it : _driver_map)
1959  {
1960  // build list of ids and params for this motor
1961  _position_goal_ids.clear();
1962  _position_goal_params.clear();
1963  for (auto const &cmd : cmd_vec)
1964  {
1965  if (_state_map.count(cmd.first) && it.first == _state_map.at(cmd.first)->getHardwareType())
1966  {
1967  _position_goal_ids.emplace_back(cmd.first);
1968  _position_goal_params.emplace_back(cmd.second);
1969  }
1970  }
1971 
1972  // syncwrite for this driver. The driver is responsible for sync write only to its associated motors
1973  auto driver = std::dynamic_pointer_cast<AbstractMotorDriver>(it.second);
1974 
1975  if (driver)
1976  {
1977  int err = driver->syncWritePositionGoal(_position_goal_ids, _position_goal_params);
1978  if (err != COMM_SUCCESS)
1979  {
1980  ROS_WARN("TtlManager::executeJointTrajectoryCmd - Failed to write position");
1981  _debug_error_message = "TtlManager - Failed to write position";
1982  }
1983  }
1984  }
1985 }
1986 
1987 // ******************
1988 // Calibration
1989 // ******************
1990 
1995 {
1996  ROS_DEBUG("TtlManager::startCalibration: starting...");
1997 
1998  std::vector<uint8_t> stepper_list;
1999  if (_ids_map.count(EHardwareType::STEPPER))
2000  {
2001  _calibration_status = EStepperCalibrationStatus::IN_PROGRESS;
2003  stepper_list = _ids_map.at(EHardwareType::STEPPER);
2004  }
2005  else if (_ids_map.count(EHardwareType::NED3PRO_STEPPER))
2006  {
2007  stepper_list = _ids_map.at(EHardwareType::NED3PRO_STEPPER);
2008  }
2009  else if (_ids_map.count(EHardwareType::FAKE_STEPPER_MOTOR))
2010  {
2011  _calibration_status = EStepperCalibrationStatus::IN_PROGRESS;
2013  stepper_list = _ids_map.at(EHardwareType::FAKE_STEPPER_MOTOR);
2014  }
2015 
2016  for (auto const &id : stepper_list)
2017  {
2018  if (_state_map.count(id))
2019  {
2020  auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(id));
2021 
2022  if (stepperState && !stepperState->isConveyor())
2023  {
2024  stepperState->setCalibration(EStepperCalibrationStatus::IN_PROGRESS, 1);
2025  }
2026  }
2027  } // for steppers_list
2028 }
2029 
2034 {
2035  ROS_INFO("TtlManager::resetCalibration: reseting...");
2036 
2037  std::vector<uint8_t> stepper_list;
2038  if (_ids_map.count(EHardwareType::STEPPER))
2039  {
2040  _calibration_status = EStepperCalibrationStatus::UNINITIALIZED;
2042  stepper_list = _ids_map.at(EHardwareType::STEPPER);
2043  }
2044  else if (_ids_map.count(EHardwareType::NED3PRO_STEPPER))
2045  stepper_list = _ids_map.at(EHardwareType::NED3PRO_STEPPER);
2046 
2047  for (auto const id : stepper_list)
2048  {
2049  if (_state_map.count(id))
2050  {
2051  auto stepperState = std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(id));
2052 
2053  if (stepperState && !stepperState->isConveyor())
2054  {
2055  stepperState->setCalibration(EStepperCalibrationStatus::UNINITIALIZED, 1);
2056  }
2057  }
2058  } // for steppers_list
2059 }
2060 
2066 int32_t TtlManager::getCalibrationResult(uint8_t motor_id) const
2067 {
2068  if (!_state_map.count(motor_id) && _state_map.at(motor_id))
2069  throw std::out_of_range("TtlManager::getMotorsState: Unknown motor id");
2070 
2071  return std::dynamic_pointer_cast<StepperMotorState>(_state_map.at(motor_id))->getCalibrationValue();
2072 }
2073 
2074 // ******************
2075 // Getters
2076 // ******************
2077 
2084 void TtlManager::getBusState(bool &connection_state, std::vector<uint8_t> &motor_id, std::string &debug_msg) const
2085 {
2086  debug_msg = _debug_error_message;
2087  motor_id = _all_ids_connected;
2088  connection_state = isConnectionOk();
2089 }
2090 
2095 std::vector<std::shared_ptr<JointState>> TtlManager::getMotorsStates() const
2096 {
2097  std::vector<std::shared_ptr<JointState>> states;
2098 
2099  for (const auto &it : _state_map)
2100  {
2101  if (it.second && it.second->getComponentType() == common::model::EComponentType::JOINT)
2102  {
2103  states.emplace_back(std::dynamic_pointer_cast<JointState>(it.second));
2104  }
2105  }
2106 
2107  return states;
2108 }
2109 
2110 std::vector<std::shared_ptr<ConveyorState>> TtlManager::getConveyorsStates() const
2111 {
2112  std::vector<std::shared_ptr<ConveyorState>> conveyor_states;
2113  for (const auto &it : _state_map)
2114  {
2115  if (it.second && it.second->getComponentType() == common::model::EComponentType::CONVEYOR)
2116  {
2117  conveyor_states.emplace_back(std::dynamic_pointer_cast<ConveyorState>(it.second));
2118  }
2119  }
2120 
2121  return conveyor_states;
2122 }
2123 
2129 std::shared_ptr<common::model::AbstractHardwareState> TtlManager::getHardwareState(uint8_t motor_id) const
2130 {
2131  if (!_state_map.count(motor_id) && _state_map.at(motor_id))
2132  throw std::out_of_range("TtlManager::getMotorsState: Unknown motor id");
2133 
2134  return _state_map.at(motor_id);
2135 }
2136 
2137 // ********************
2138 // Private
2139 // ********************
2140 
2145 void TtlManager::addHardwareDriver(EHardwareType hardware_type)
2146 {
2147  // if not already instanciated
2148  if (!_driver_map.count(hardware_type))
2149  {
2150  switch (hardware_type)
2151  {
2152  case EHardwareType::STEPPER:
2153  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<StepperDriver<StepperReg>>(_portHandler, _packetHandler)));
2154  break;
2155  case EHardwareType::NED3PRO_STEPPER:
2156  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<Ned3ProStepperDriver<Ned3ProStepperReg>>(_portHandler, _packetHandler)));
2157  break;
2158  case EHardwareType::FAKE_STEPPER_MOTOR:
2159  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<MockStepperDriver>(_fake_data)));
2160  break;
2161  case EHardwareType::XL430:
2162  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<DxlDriver<XL430Reg>>(_portHandler, _packetHandler)));
2163  break;
2164  case EHardwareType::XC430:
2165  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<DxlDriver<XC430Reg>>(_portHandler, _packetHandler)));
2166  break;
2167  case EHardwareType::XM430:
2168  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<DxlDriver<XM430Reg>>(_portHandler, _packetHandler)));
2169  break;
2170  case EHardwareType::XL320:
2171  _driver_map.insert(make_pair(hardware_type, std::make_shared<DxlDriver<XL320Reg>>(_portHandler, _packetHandler)));
2172  break;
2173  case EHardwareType::XL330:
2174  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<DxlDriver<XL330Reg>>(_portHandler, _packetHandler)));
2175  break;
2176  case EHardwareType::XH430:
2177  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<DxlDriver<XH430Reg>>(_portHandler, _packetHandler)));
2178  break;
2179  case EHardwareType::FAKE_DXL_MOTOR:
2180  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<MockDxlDriver>(_fake_data)));
2181  break;
2182  case EHardwareType::END_EFFECTOR:
2183  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<EndEffectorDriver<EndEffectorReg>>(_portHandler, _packetHandler)));
2184  break;
2185  case EHardwareType::NED3PRO_END_EFFECTOR:
2186  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<Ned3ProEndEffectorDriver<Ned3ProEndEffectorReg>>(_portHandler, _packetHandler)));
2187  break;
2188  case EHardwareType::FAKE_END_EFFECTOR:
2189  _driver_map.insert(std::make_pair(hardware_type, std::make_shared<MockEndEffectorDriver>(_fake_data)));
2190  break;
2191  default:
2192  ROS_ERROR("TtlManager - Unable to instanciate driver, unknown type");
2193  break;
2194  }
2195  }
2196 }
2197 
2201 void TtlManager::readFakeConfig(bool use_simu_gripper, bool use_simu_conveyor)
2202 {
2203  _fake_data = std::make_shared<FakeTtlData>();
2204 
2205  if (_nh.hasParam("fake_params"))
2206  {
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));
2212 
2213  if (_nh.hasParam("fake_params/steppers"))
2214  {
2215  std::string current_ns = "fake_params/steppers/";
2216  retrieveFakeMotorData(current_ns, _fake_data->stepper_registers);
2217  }
2218 
2219  if (_nh.hasParam("fake_params/dynamixels/"))
2220  {
2221  std::string current_ns = "fake_params/dynamixels/";
2222  retrieveFakeMotorData(current_ns, _fake_data->dxl_registers);
2223  }
2224 
2225  if (_nh.hasParam("fake_params/end_effector"))
2226  {
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);
2234 
2235  assert(!id_list.empty());
2236  assert(!temperature_list.empty());
2237  assert(!voltage_list.empty());
2238  assert(!firmware_list.empty());
2239 
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));
2243 
2244  _fake_data->end_effector.firmware = firmware_list.at(0);
2245  }
2246 
2247  if (use_simu_gripper && _nh.hasParam("fake_params/tool/"))
2248  {
2249  std::string current_ns = "fake_params/tool/";
2250  retrieveFakeMotorData(current_ns, _fake_data->dxl_registers);
2251  }
2252 
2253  if (use_simu_conveyor && _nh.hasParam("fake_params/conveyors/"))
2254  {
2255  std::string current_ns = "fake_params/conveyors/";
2256  retrieveFakeMotorData(current_ns, _fake_data->stepper_registers);
2257  }
2258 
2259  _fake_data->updateFullIdList();
2260  }
2261 }
2262 
2269  auto joint_states = getMotorsStates();
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();
2272  });
2273  if (some_joint_state_it == joint_states.end()){
2274  return {};
2275  }
2276  auto some_joint_state = *some_joint_state_it;
2277  auto hardware_type = some_joint_state->getHardwareType();
2278  return {
2279  .driver = std::dynamic_pointer_cast<AbstractStepperDriver>(_driver_map.at(hardware_type)),
2280  .hardware_type = hardware_type
2281  };
2282 }
2283 
2284 
2285 } // namespace ttl_driver
ttl_driver::TtlManager::retrieveFakeMotorData
void retrieveFakeMotorData(const std::string &current_ns, std::map< uint8_t, Reg > &fake_params)
TtlManager::retrieveFakeMotorData.
Definition: ttl_manager.hpp:406
end_effector_driver.hpp
ttl_driver::TtlManager::startCalibration
void startCalibration() override
TtlManager::startCalibration.
Definition: ttl_manager.cpp:1994
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:207
ttl_driver::TtlManager::CalibrationMachineState::State::IDLE
@ IDLE
ttl_driver::TtlManager::readEndEffectorStatus
bool readEndEffectorStatus()
TtlManager::readEndEffectorStatus.
Definition: ttl_manager.cpp:788
ttl_driver::TtlManager::readCustomCommand
int readCustomCommand(uint8_t id, int32_t reg_address, int &value, int byte_number)
TtlManager::readCustomCommand.
Definition: ttl_manager.cpp:1593
mock_dxl_driver.hpp
ttl_driver::TtlManager::_debug_error_message
std::string _debug_error_message
Definition: ttl_manager.hpp:229
ttl_driver::TtlManager::getJointsStepperDriver
GetJointsStepperDriverResult getJointsStepperDriver()
: Return the driver of the joints
Definition: ttl_manager.cpp:2268
ttl_driver::TtlManager::writeSingleCommand
int writeSingleCommand(std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &&cmd)
TtlManager::writeSingleCommand.
Definition: ttl_manager.cpp:1906
ttl_driver::TTL_SCAN_MISSING_MOTOR
constexpr int TTL_SCAN_MISSING_MOTOR
Definition: ttl_manager.hpp:71
ttl_driver::TtlManager::_state_map
std::map< uint8_t, std::shared_ptr< common::model::AbstractHardwareState > > _state_map
Definition: ttl_manager.hpp:214
ttl_driver::TtlManager::_calib_machine_state
CalibrationMachineState _calib_machine_state
Definition: ttl_manager.hpp:311
ttl_driver::TtlManager::readHardwareStatus
bool readHardwareStatus()
TtlManager::readHardwareStatus.
Definition: ttl_manager.cpp:1048
ttl_driver::TtlManager::getCalibrationResult
int32_t getCalibrationResult(uint8_t id) const override
TtlManager::getCalibrationResult.
Definition: ttl_manager.cpp:2066
ttl_driver::TtlManager::_calibration_status
common::model::EStepperCalibrationStatus _calibration_status
Definition: ttl_manager.hpp:241
ttl_driver::TtlManager::_nh
ros::NodeHandle _nh
Definition: ttl_manager.hpp:201
ttl_driver::TtlManager::scanAndCheck
int scanAndCheck() override
TtlManager::scanAndCheck.
Definition: ttl_manager.cpp:403
ttl_driver::TtlManager::checkCollision
bool checkCollision()
TtlManager::checkCollision.
Definition: ttl_manager.cpp:898
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:231
mock_end_effector_driver.hpp
ttl_driver::TtlManager::executeJointTrajectoryCmd
void executeJointTrajectoryCmd(std::vector< std::pair< uint8_t, uint32_t > > cmd_vec)
TtlManager::executeJointTrajectoryCmd.
Definition: ttl_manager.cpp:1956
ttl_driver::TtlManager::_position_goal_params
std::vector< uint32_t > _position_goal_params
Definition: ttl_manager.hpp:257
stepper_reg.hpp
ttl_driver::TTL_FAIL_OPEN_PORT
constexpr int TTL_FAIL_OPEN_PORT
Definition: ttl_manager.hpp:65
ttl_driver::TtlManager::_position_goal_ids
std::vector< uint8_t > _position_goal_ids
Definition: ttl_manager.hpp:256
ttl_driver::TtlManager::_all_ids_connected
std::vector< uint8_t > _all_ids_connected
Definition: ttl_manager.hpp:210
ttl_driver::TtlManager::_last_collision_detection_activating
double _last_collision_detection_activating
Definition: ttl_manager.hpp:249
ttl_driver::TtlManager::sendCustomCommand
int sendCustomCommand(uint8_t id, int reg_address, int value, int byte_number)
TtlManager::sendCustomCommand.
Definition: ttl_manager.cpp:1543
end_effector_reg.hpp
ttl_driver::TtlManager::readSteppersStatus
uint8_t readSteppersStatus()
TtlManager::readCalibrationStatus : reads specific steppers related information (ned2 only)
Definition: ttl_manager.cpp:1169
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:67
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:346
ttl_driver::TtlManager::getAllIdsOnBus
int getAllIdsOnBus(std::vector< uint8_t > &id_list)
TtlManager::getAllIdsOnDxlBus.
Definition: ttl_manager.cpp:1432
ttl_driver::TtlManager::removeHardwareComponent
void removeHardwareComponent(uint8_t id) override
TtlManager::removeHardwareComponent.
Definition: ttl_manager.cpp:296
ttl_driver::Ned3ProStepperDriver
The Ned3ProStepperDriver class.
Definition: ned3pro_stepper_driver.hpp:40
ttl_driver::TtlManager::readHomingAbsPosition
bool readHomingAbsPosition()
Definition: ttl_manager.cpp:609
ttl_driver::TtlManager::_device_name
std::string _device_name
Definition: ttl_manager.hpp:207
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:2129
ttl_driver::TtlManager::readJointsStatus
bool readJointsStatus()
TtlManager::readJointsStatus.
Definition: ttl_manager.cpp:679
ttl_driver::TtlManager::_packetHandler
std::shared_ptr< dynamixel::PacketHandler > _packetHandler
Definition: ttl_manager.hpp:203
ttl_driver::TtlManager::init
bool init(ros::NodeHandle &nh) override
TtlManager::init.
Definition: ttl_manager.cpp:107
ttl_driver::TtlManager::getConveyorsStates
std::vector< std::shared_ptr< common::model::ConveyorState > > getConveyorsStates() const
Definition: ttl_manager.cpp:2110
ttl_driver::TtlManager::getPosition
uint32_t getPosition(const common::model::JointState &motor_state)
TtlManager::getPosition.
Definition: ttl_manager.cpp:574
ttl_driver::TtlManager::resetCalibration
void resetCalibration() override
TtlManager::resetCalibration.
Definition: ttl_manager.cpp:2033
ttl_driver::TtlManager::CalibrationMachineState::State::STARTING
@ STARTING
ttl_driver::TtlManager::CalibrationMachineState::status
State status()
Definition: ttl_manager.hpp:295
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:2084
ttl_driver::DxlDriver
The DxlDriver class.
Definition: dxl_driver.hpp:44
ttl_driver::TtlManager::resetTorques
void resetTorques()
TtlManager::resetTorques.
Definition: ttl_manager.cpp:534
ttl_driver::TtlManager::isMotorType
bool isMotorType(common::model::EHardwareType type)
TtlManager::isMotorType.
Definition: ttl_manager.cpp:329
ttl_driver::TtlManager::readCollisionStatus
bool readCollisionStatus()
TtlManager::readCollisionStatus.
Definition: ttl_manager.cpp:981
stepper_driver.hpp
ttl_driver::TtlManager::MAX_READ_EE_FAILURE
static constexpr uint32_t MAX_READ_EE_FAILURE
Definition: ttl_manager.hpp:238
ttl_driver::TtlManager::setLeds
int setLeds(int led)
TtlManager::setLeds.
Definition: ttl_manager.cpp:1484
ttl_driver::TtlManager::_isWrongAction
bool _isWrongAction
Definition: ttl_manager.hpp:251
ttl_driver::TtlManager::writeSynchronizeCommand
int writeSynchronizeCommand(std::unique_ptr< common::model::AbstractTtlSynchronizeMotorCmd > &&cmd)
TtlManager::writeSynchronizeCommand.
Definition: ttl_manager.cpp:1836
ttl_driver::TtlManager::_collision_status
bool _collision_status
Definition: ttl_manager.hpp:248
mock_stepper_driver.hpp
ttl_driver::TtlManager::ping
bool ping(uint8_t id) override
TtlManager::ping.
Definition: ttl_manager.cpp:472
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:221
ttl_driver::TtlManager::rebootHardware
int rebootHardware(uint8_t id)
TtlManager::rebootHardware.
Definition: ttl_manager.cpp:490
ttl_driver::TtlManager::_fake_data
std::shared_ptr< FakeTtlData > _fake_data
Definition: ttl_manager.hpp:244
ned3pro_end_effector_driver.hpp
ttl_driver::TtlManager::readNed3ProSteppersStatus
uint8_t readNed3ProSteppersStatus()
Definition: ttl_manager.cpp:1332
ttl_driver::TtlManager::CalibrationMachineState::reset
void reset()
Definition: ttl_manager.hpp:271
ttl_driver::TtlManager::_end_effector_fail_counter_read
uint32_t _end_effector_fail_counter_read
Definition: ttl_manager.hpp:232
ttl_driver::TtlManager::_is_connection_ok
bool _is_connection_ok
Definition: ttl_manager.hpp:228
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:322
ttl_driver::TtlManager::_position_list
std::vector< uint32_t > _position_list
Definition: ttl_manager.hpp:255
ttl_driver::TtlManager::CalibrationMachineState::start
void start()
Definition: ttl_manager.hpp:276
ttl_driver::TtlManager::_led_state
int _led_state
Definition: ttl_manager.hpp:234
ttl_driver::TtlManager::_simulation_mode
bool _simulation_mode
Definition: ttl_manager.hpp:245
ttl_driver::TTL_SCAN_OK
constexpr int TTL_SCAN_OK
Definition: ttl_manager.hpp:70
ttl_driver::TtlManager::readMoving
int readMoving(uint8_t id, uint8_t &status)
TtlManager::readMoving.
Definition: ttl_manager.cpp:1760
ttl_driver::TtlManager::_removed_motor_id_list
std::vector< uint8_t > _removed_motor_id_list
Definition: ttl_manager.hpp:211
ttl_driver::TtlManager::_ids_map
std::map< common::model::EHardwareType, std::vector< uint8_t > > _ids_map
Definition: ttl_manager.hpp:216
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:285
ttl_driver::TtlManager::_portHandler
std::shared_ptr< dynamixel::PortHandler > _portHandler
Definition: ttl_manager.hpp:202
ttl_driver::TtlManager::GetJointsStepperDriverResult
Definition: ttl_manager.hpp:194
ttl_driver::TtlManager::CalibrationMachineState::isTimeout
bool isTimeout()
Definition: ttl_manager.hpp:300
ttl_driver::TtlManager::_driver_map
std::map< common::model::EHardwareType, std::shared_ptr< ttl_driver::AbstractTtlDriver > > _driver_map
Definition: ttl_manager.hpp:218
ttl_driver::TtlManager::setupCommunication
int setupCommunication() override
TtlManager::setupCommunication.
Definition: ttl_manager.cpp:150
ttl_driver::TtlManager::MAX_HW_FAILURE
static constexpr uint32_t MAX_HW_FAILURE
Definition: ttl_manager.hpp:237
ttl_driver::TtlManager::getMotorsStates
std::vector< std::shared_ptr< common::model::JointState > > getMotorsStates() const
TtlManager::getMotorsStates.
Definition: ttl_manager.cpp:2095
ttl_driver::TtlManager::~TtlManager
~TtlManager() override
TtlManager::~TtlManager.
Definition: ttl_manager.cpp:93
ttl_driver::TtlManager::_conveyor_list
std::vector< uint8_t > _conveyor_list
Definition: ttl_manager.hpp:225
ttl_driver::TtlManager::addHardwareDriver
void addHardwareDriver(common::model::EHardwareType hardware_type) override
TtlManager::addHardwareDriver.
Definition: ttl_manager.cpp:2145
ttl_driver::TtlManager::_calibration_status_publisher
ros::Publisher _calibration_status_publisher
Definition: ttl_manager.hpp:253
ttl_driver::TtlManager::_led_motor_type_cfg
std::string _led_motor_type_cfg
Definition: ttl_manager.hpp:235
ttl_driver::TtlManager::readControlMode
int readControlMode(uint8_t id, uint8_t &control_mode)
TtlManager::readControlMode.
Definition: ttl_manager.cpp:1799
ttl_driver::TTL_BUS_PROTOCOL_VERSION
constexpr float TTL_BUS_PROTOCOL_VERSION
Definition: ttl_manager.hpp:64
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:1643
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:1707
ttl_driver::TtlManager::_baudrate
int _baudrate
Definition: ttl_manager.hpp:208
ttl_driver::TtlManager::readFakeConfig
void readFakeConfig(bool use_simu_gripper, bool use_simu_conveyor)
TtlManager::readFakeConfig.
Definition: ttl_manager.cpp:2201
ttl_driver::TtlManager::_isRealCollision
bool _isRealCollision
Definition: ttl_manager.hpp:250
fake_ttl_data.hpp


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Tue Jan 13 2026 12:43:08