ttl_manager.hpp
Go to the documentation of this file.
1 /*
2 ttl_manager.hpp
3 Copyright (C) 2020 Niryo
4 All rights reserved.
5 
6 This program is free software: you can redistribute it and/or modify
7 it under the terms of the GNU General Public License as published by
8 the Free Software Foundation, either version 3 of the License, or
9 (at your option) any later version.
10 
11 This program is distributed in the hope that it will be useful,
12 but WITHOUT ANY WARRANTY; without even the implied warranty of
13 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 GNU General Public License for more details.
15 
16 You should have received a copy of the GNU General Public License
17 along with this program. If not, see <http:// www.gnu.org/licenses/>.
18 */
19 
20 #ifndef TTL_DRIVER_HPP
21 #define TTL_DRIVER_HPP
22 
23 #include "common/util/util_defs.hpp"
24 #include "common/util/i_bus_manager.hpp"
25 
26 // cpp
27 #include <memory>
28 #include <ros/ros.h>
29 #include <string>
30 #include <thread>
31 #include <queue>
32 #include <functional>
33 #include <algorithm>
34 #include <set>
35 #include <utility>
36 
37 // ros
38 #include "ros/node_handle.h"
39 
40 // niryo
41 #include "dynamixel_sdk/dynamixel_sdk.h"
42 #include "niryo_robot_msgs/MotorHeader.h"
43 #include "niryo_robot_msgs/SetInt.h"
44 #include "niryo_robot_msgs/CommandStatus.h"
45 
49 #include "ttl_driver/MotorCommand.h"
50 
51 #include "common/model/dxl_motor_state.hpp"
52 #include "common/model/synchronize_motor_cmd.hpp"
53 #include "common/model/single_motor_cmd.hpp"
54 #include "common/model/stepper_calibration_status_enum.hpp"
55 #include "common/model/conveyor_state.hpp"
56 
57 namespace ttl_driver
58 {
59 
63 constexpr float TTL_BUS_PROTOCOL_VERSION = 2.0;
64 constexpr int TTL_FAIL_OPEN_PORT = -4500;
65 
66 constexpr int TTL_FAIL_PORT_SET_BAUDRATE = -4501;
67 constexpr int TTL_FAIL_SETUP_GPIO = -4502;
68 
69 constexpr int TTL_SCAN_OK = 0;
70 constexpr int TTL_SCAN_MISSING_MOTOR = -50;
71 constexpr int TTL_SCAN_UNALLOWED_MOTOR = -51;
72 constexpr int TTL_WRONG_TYPE = -52;
73 
84 class TtlManager : public common::util::IBusManager
85 {
86 public:
87  TtlManager() = delete;
88  TtlManager(ros::NodeHandle &nh);
89  ~TtlManager() override;
90  // see
91  // https://github.com/isocpp/CppCoreGuidelines/blob/master/CppCoreGuidelines.md#c21-if-you-define-or-delete-any-copy-move-or-destructor-function-define-or-delete-them-all
92  TtlManager(const TtlManager &) = delete;
93  TtlManager(TtlManager &&) = delete;
94  TtlManager &operator=(TtlManager &&) = delete;
95  TtlManager &operator=(const TtlManager &) = delete;
96 
97  // IBusManager Interface
98  bool init(ros::NodeHandle &nh) override;
99 
100  int addHardwareComponent(std::shared_ptr<common::model::AbstractHardwareState> &&state) override;
101 
102  void removeHardwareComponent(uint8_t id) override;
103  bool isConnectionOk() const override;
104 
105  int scanAndCheck() override;
106  bool ping(uint8_t id) override;
107 
108  size_t getNbMotors() const override;
109  void getBusState(bool &connection_state, std::vector<uint8_t> &motor_id, std::string &debug_msg) const override;
110  std::string getErrorMessage() const override;
111 
112  // commands
113 
114  int changeId(common::model::EHardwareType motor_type, uint8_t old_id, uint8_t new_id);
115 
116  int writeSynchronizeCommand(std::unique_ptr<common::model::AbstractTtlSynchronizeMotorCmd> &&cmd);
117  int writeSingleCommand(std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &&cmd);
118 
119  void executeJointTrajectoryCmd(std::vector<std::pair<uint8_t, uint32_t>> cmd_vec);
120 
121  int rebootHardware(uint8_t id);
122 
123  int setLeds(int led);
124 
125  int sendCustomCommand(uint8_t id, int reg_address, int value, int byte_number);
126  int readCustomCommand(uint8_t id, int32_t reg_address, int &value, int byte_number);
127 
128  void resetTorques();
129 
130  // read status
131  bool readHardwareStatus();
132  bool readEndEffectorStatus();
133  uint8_t readSteppersStatus();
134  uint8_t readNed3ProSteppersStatus();
135  bool readJointsStatus();
136  bool readHomingAbsPosition();
137  bool readCollisionStatus();
138 
139  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,
140  uint16_t &vel_i_gain, uint16_t &ff1_gain, uint16_t &ff2_gain);
141 
142  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,
143  uint32_t &d_max, uint32_t &d_1, uint32_t &v_stop);
144 
145  int readControlMode(uint8_t id, uint8_t &control_mode);
146 
147  int readMoving(uint8_t id, uint8_t &status);
148 
149  // calibration
150  void startCalibration() override;
151  void resetCalibration() override;
152 
153  int32_t getCalibrationResult(uint8_t id) const override;
154  common::model::EStepperCalibrationStatus getCalibrationStatus() const override;
155  bool needCalibration() const;
156  bool isCalibrationInProgress() const;
157 
158  // getters
159  int getAllIdsOnBus(std::vector<uint8_t> &id_list);
160 
161  uint32_t getPosition(const common::model::JointState &motor_state);
162  int getLedState() const;
163 
164  std::vector<std::shared_ptr<common::model::JointState>> getMotorsStates() const;
165  std::vector<std::shared_ptr<common::model::ConveyorState>> getConveyorsStates() const;
166  std::shared_ptr<common::model::AbstractHardwareState> getHardwareState(uint8_t motor_id) const;
167 
168  std::vector<uint8_t> getRemovedMotorList() const override;
169 
170  bool getCollisionStatus() const;
171 
172  bool hasEndEffector() const;
173  bool changeTool(int value, std::string &message, int &status);
174 
175 private:
176  // IBusManager Interface
177  int setupCommunication() override;
178  void addHardwareDriver(common::model::EHardwareType hardware_type) override;
179 
180  // Config params using in fake driver
181  void readFakeConfig(bool use_simu_gripper, bool use_simu_conveyor);
182  template <typename Reg>
183  void retrieveFakeMotorData(const std::string &current_ns, std::map<uint8_t, Reg> &fake_params,
184  std::vector<int> hw_ids = {});
185 
186  // check if hardware is a motor or not
187  // this helps get only one driver to use for all motors to get/set on the same address
188  bool isMotorType(common::model::EHardwareType type);
189 
190  bool checkCollision();
191 
193  {
194  std::shared_ptr<ttl_driver::AbstractStepperDriver> driver;
195  common::model::EHardwareType hardware_type;
196  };
198 
199 private:
200  ros::NodeHandle _nh;
201  std::shared_ptr<dynamixel::PortHandler> _portHandler;
202  std::shared_ptr<dynamixel::PacketHandler> _packetHandler;
203 
204  mutable std::mutex _sync_mutex;
205 
206  std::string _device_name;
207  int _baudrate{ 1000000 };
208 
209  std::vector<uint8_t> _all_ids_connected; // with all ttl motors connected (including the tool)
210  std::vector<uint8_t> _removed_motor_id_list;
211 
212  // state of a component for a given id
213  std::map<uint8_t, std::shared_ptr<common::model::AbstractHardwareState>> _state_map;
214  // map of associated ids for a given hardware type
215  std::map<common::model::EHardwareType, std::vector<uint8_t>> _ids_map;
216  // map of drivers for a given hardware type (dxl, stepper, end effector)
217  std::map<common::model::EHardwareType, std::shared_ptr<ttl_driver::AbstractTtlDriver>> _driver_map;
218 
219  // default ttl driver is always available
220  std::shared_ptr<ttl_driver::AbstractTtlDriver> _default_ttl_driver;
221 
222  // vector of ids of motors and conveyors
223  // Theses vector help remove loop not necessary
224  std::vector<uint8_t> _conveyor_list;
225 
226  // for hardware control
227  bool _is_connection_ok{ false };
228  std::string _debug_error_message;
229 
230  // for simulation
231  uint32_t _current_tool_id{ 0 };
232 
233  uint32_t _hw_fail_counter_read{ 0 };
235 
236  int _led_state = 0;
237  std::string _led_motor_type_cfg;
238 
239  static constexpr uint32_t MAX_HW_FAILURE = 150;
240  static constexpr uint32_t MAX_READ_EE_FAILURE = 150;
241 
242  // at init, no hw, so no calib needed
243  common::model::EStepperCalibrationStatus _calibration_status{ common::model::EStepperCalibrationStatus::OK };
244 
245  // for simulation only
246  std::shared_ptr<FakeTtlData> _fake_data;
247  bool _simulation_mode{ false };
248 
249  // status to track collision status
250  bool _collision_status{ false };
252  bool _isRealCollision{ true };
253  bool _isWrongAction{ false };
254 
256 
257  std::vector<uint32_t> _position_list;
258  std::vector<uint8_t> _position_goal_ids;
259  std::vector<uint32_t> _position_goal_params;
260  std::vector<int> _available_tools;
261  std::vector<int> _current_tool_vector;
262 
264  {
265  public:
266  enum class State
267  {
268  IDLE = 1,
269  STARTING = 2,
270  IN_PROGRESS = 3,
271  UPDATING = 4
272  };
273 
274  void reset()
275  {
276  s = State::IDLE;
277  }
278 
279  void start()
280  {
281  s = State::STARTING;
282  _time = ros::Time::now().toSec(); // keep last date updated
283  }
284 
288  void next()
289  {
290  int newState = static_cast<int>(s);
291  if (State::UPDATING != s)
292  newState++;
293 
294  _time = ros::Time::now().toSec(); // keep last date updated
295  s = static_cast<State>(newState);
296  }
297 
299  {
300  return s;
301  }
302 
303  bool isTimeout()
304  {
305  return (ros::Time::now().toSec() - _time > _calibration_timeout);
306  }
307 
308  private:
310  double _time{};
311  static constexpr double _calibration_timeout{ 5.0 };
312  };
313 
315 };
316 
317 // inline getters
318 
323 inline bool TtlManager::isConnectionOk() const
324 {
325  return _is_connection_ok;
326 }
327 
332 inline size_t TtlManager::getNbMotors() const
333 {
334  return _state_map.size();
335 }
336 
341 inline std::vector<uint8_t> TtlManager::getRemovedMotorList() const
342 {
343  return _removed_motor_id_list;
344 }
345 
350 inline std::string TtlManager::getErrorMessage() const
351 {
352  return _debug_error_message;
353 }
354 
359 inline common::model::EStepperCalibrationStatus TtlManager::getCalibrationStatus() const
360 {
361  return _calibration_status;
362 }
363 
368 inline bool TtlManager::needCalibration() const
369 {
370  return (common::model::EStepperCalibrationStatus::OK != getCalibrationStatus() &&
371  common::model::EStepperCalibrationStatus::IN_PROGRESS != getCalibrationStatus());
372 }
373 
379 {
380  return (common::model::EStepperCalibrationStatus::IN_PROGRESS == getCalibrationStatus());
381 }
382 
387 inline bool TtlManager::hasEndEffector() const
388 {
389  return (_driver_map.count(common::model::EHardwareType::END_EFFECTOR) ||
390  _driver_map.count(common::model::EHardwareType::NED3PRO_END_EFFECTOR) ||
391  _driver_map.count(common::model::EHardwareType::FAKE_END_EFFECTOR));
392 }
393 
399 template <typename Reg>
400 void TtlManager::retrieveFakeMotorData(const std::string &current_ns, std::map<uint8_t, Reg> &fake_params,
401  std::vector<int> hw_ids)
402 {
403  if (hw_ids.size() == 0)
404  {
405  _nh.getParam(current_ns + "id", hw_ids);
406  }
407  std::vector<int> hw_positions;
408  _nh.getParam(current_ns + "position", hw_positions);
409  assert(hw_ids.size() == hw_positions.size());
410 
411  std::vector<int> hw_velocities;
412  _nh.getParam(current_ns + "velocity", hw_velocities);
413  assert(hw_ids.size() == hw_velocities.size());
414 
415  std::vector<int> hw_temperatures;
416  _nh.getParam(current_ns + "temperature", hw_temperatures);
417  assert(hw_positions.size() == hw_temperatures.size());
418 
419  std::vector<double> hw_voltages;
420  _nh.getParam(current_ns + "voltage", hw_voltages);
421  assert(hw_temperatures.size() == hw_voltages.size());
422 
423  std::vector<int> hw_min_positions;
424  _nh.getParam(current_ns + "min_position", hw_min_positions);
425  assert(hw_voltages.size() == hw_min_positions.size());
426 
427  std::vector<int> hw_max_positions;
428  _nh.getParam(current_ns + "max_position", hw_max_positions);
429  assert(hw_min_positions.size() == hw_max_positions.size());
430 
431  std::vector<int> hw_model_numbers;
432  _nh.getParam(current_ns + "model_number", hw_model_numbers);
433  assert(hw_max_positions.size() == hw_model_numbers.size());
434 
435  std::vector<std::string> hw_firmwares;
436  _nh.getParam(current_ns + "firmware", hw_firmwares);
437  assert(hw_firmwares.size() == hw_firmwares.size());
438 
439  for (size_t i = 0; i < hw_ids.size(); i++)
440  {
441  Reg tmp;
442  tmp.id = static_cast<uint8_t>(hw_ids.at(i));
443  tmp.position = static_cast<uint32_t>(hw_positions.at(i));
444  tmp.velocity = static_cast<uint32_t>(hw_velocities.at(i));
445  tmp.temperature = static_cast<uint8_t>(hw_temperatures.at(i));
446  tmp.voltage = hw_voltages.at(i);
447  tmp.model_number = static_cast<uint16_t>(hw_model_numbers.at(i));
448  tmp.firmware = hw_firmwares.at(i);
449  fake_params.insert(std::make_pair(tmp.id, tmp));
450  }
451 }
452 
458 {
459  return _collision_status;
460 }
461 
462 } // namespace ttl_driver
463 
464 #endif // TTLDRIVER_HPP
ttl_driver::TtlManager::startCalibration
void startCalibration() override
TtlManager::startCalibration.
Definition: ttl_manager.cpp:2104
ttl_driver::TtlManager::GetJointsStepperDriverResult::hardware_type
common::model::EHardwareType hardware_type
Definition: ttl_manager.hpp:195
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
ttl_driver::TtlManager::_debug_error_message
std::string _debug_error_message
Definition: ttl_manager.hpp:228
ttl_driver::TtlManager::isCalibrationInProgress
bool isCalibrationInProgress() const
TtlManager::isCalibrationInProgress.
Definition: ttl_manager.hpp:378
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::getCollisionStatus
bool getCollisionStatus() const
TtlManager::getCollisionStatus.
Definition: ttl_manager.hpp:457
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
ttl_driver::TtlManager::getLedState
int getLedState() const
ttl_driver::TtlManager::_position_goal_params
std::vector< uint32_t > _position_goal_params
Definition: ttl_manager.hpp:259
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
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
State
Definition: ttl_manager.hpp:266
abstract_motor_driver.hpp
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::TtlManager::getCalibrationStatus
common::model::EStepperCalibrationStatus getCalibrationStatus() const override
TtlManager::getCalibrationStatus.
Definition: ttl_manager.hpp:359
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
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::_packetHandler
std::shared_ptr< dynamixel::PacketHandler > _packetHandler
Definition: ttl_manager.hpp:202
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::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
abstract_stepper_driver.hpp
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::TtlManager::CalibrationMachineState::s
State s
Definition: ttl_manager.hpp:309
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::getNbMotors
size_t getNbMotors() const override
TtlManager::getNbMotors.
Definition: ttl_manager.hpp:332
ttl_driver::TtlManager::readCollisionStatus
bool readCollisionStatus()
TtlManager::readCollisionStatus.
Definition: ttl_manager.cpp:1064
ttl_driver::TtlManager::GetJointsStepperDriverResult::driver
std::shared_ptr< ttl_driver::AbstractStepperDriver > driver
Definition: ttl_manager.hpp:194
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
The TtlManager class manages the different motor drivers connected on the TTL bus it is used by ttl_i...
Definition: ttl_manager.hpp:84
ttl_driver::TtlManager::CalibrationMachineState::_calibration_timeout
static constexpr double _calibration_timeout
Definition: ttl_manager.hpp:311
ttl_driver::TtlManager::operator=
TtlManager & operator=(TtlManager &&)=delete
ttl_driver::TtlManager::_collision_status
bool _collision_status
Definition: ttl_manager.hpp:250
ttl_driver::TtlManager::ping
bool ping(uint8_t id) override
TtlManager::ping.
Definition: ttl_manager.cpp:542
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
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::getRemovedMotorList
std::vector< uint8_t > getRemovedMotorList() const override
TtlManager::getRemovedMotorList.
Definition: ttl_manager.hpp:341
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::TTL_FAIL_SETUP_GPIO
constexpr int TTL_FAIL_SETUP_GPIO
Definition: ttl_manager.hpp:67
ttl_driver::TtlManager::_led_state
int _led_state
Definition: ttl_manager.hpp:236
ttl_driver::TtlManager::CalibrationMachineState
Definition: ttl_manager.hpp:263
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::CalibrationMachineState::_time
double _time
Definition: ttl_manager.hpp:310
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::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::hasEndEffector
bool hasEndEffector() const
TtlManager::hasEndEffector.
Definition: ttl_manager.hpp:387
ttl_driver::TtlManager::_calibration_status_publisher
ros::Publisher _calibration_status_publisher
Definition: ttl_manager.hpp:255
ttl_driver::TtlManager::getErrorMessage
std::string getErrorMessage() const override
TtlManager::getErrorMessage.
Definition: ttl_manager.hpp:350
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_driver::TTL_SCAN_UNALLOWED_MOTOR
constexpr int TTL_SCAN_UNALLOWED_MOTOR
Definition: ttl_manager.hpp:71
ttl_driver::TTL_WRONG_TYPE
constexpr int TTL_WRONG_TYPE
Definition: ttl_manager.hpp:72
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
ttl_driver::TtlManager::needCalibration
bool needCalibration() const
TtlManager::needCalibration.
Definition: ttl_manager.hpp:368
fake_ttl_data.hpp


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