end_effector_driver.hpp
Go to the documentation of this file.
1 /*
2 end_effector_driver.hpp
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 
17 #ifndef END_EFFECTOR_DRIVER_HPP
18 #define END_EFFECTOR_DRIVER_HPP
19 
20 #include <memory>
21 #include <vector>
22 #include <string>
23 #include <iostream>
24 #include <sstream>
25 #include <cassert>
26 
28 
29 #include "end_effector_reg.hpp"
30 #include "common/model/end_effector_command_type_enum.hpp"
31 #include "common/model/end_effector_state.hpp"
32 
33 using ::common::model::EEndEffectorCommandType;
34 
35 namespace ttl_driver
36 {
37 
41 template <typename reg_type = EndEffectorReg>
43 {
44 public:
45  EndEffectorDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
46  std::shared_ptr<dynamixel::PacketHandler> packetHandler);
47 
48 public:
49  // AbstractTtlDriver interface : we cannot define them globally in AbstractTtlDriver
50  // as it is needed here for polymorphism (AbstractTtlDriver cannot be a template class and does not
51  // have access to reg_type). So it seems like a duplicate of StepperDriver
52  std::string str() const override;
53 
54  int checkModelNumber(uint8_t id, uint16_t &model_number) override;
55  int readFirmwareVersion(uint8_t id, std::string &version) override;
56 
57  int readTemperature(uint8_t id, uint8_t &temperature) override;
58  int readVoltage(uint8_t id, double &voltage) override;
59  int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override;
60 
61  int syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list) override;
62  int syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list) override;
63  int syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
64  int syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
65  int syncReadHwStatus(const std::vector<uint8_t> &id_list,
66  std::vector<std::pair<double, uint8_t> > &data_list) override;
67 
68  int syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list) override;
69 
70 public:
71  // AbstractEndEffectorDriver
72 
73  int readButton0Status(uint8_t id, common::model::EActionType &action) override;
74  int readButton1Status(uint8_t id, common::model::EActionType &action) override;
75  int readButton2Status(uint8_t id, common::model::EActionType &action) override;
76  int syncReadButtonsStatus(const uint8_t &id, std::vector<common::model::EActionType> &action_list) override;
77 
78  int readAccelerometerXValue(uint8_t id, uint32_t &x_value) override;
79  int readAccelerometerYValue(uint8_t id, uint32_t &y_value) override;
80  int readAccelerometerZValue(uint8_t id, uint32_t &z_value) override;
81 
82  int readCollisionStatus(uint8_t id, bool &status) override;
83 
84  int readDigitalInput(uint8_t id, bool &in) override;
85  int writeDigitalInput(uint8_t id, bool in) override;
86  int writeDigitalOutput(uint8_t id, bool out) override;
87 
88  int writeCollisionThresh(uint8_t id, int thresh) override;
89  int writeCollisionThreshAlgo2(uint8_t id, int thresh) override;
90 };
91 
92 // definition of methods
93 
97 template <typename reg_type>
98 EndEffectorDriver<reg_type>::EndEffectorDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
99  std::shared_ptr<dynamixel::PacketHandler> packetHandler)
100  : AbstractEndEffectorDriver(std::move(portHandler), std::move(packetHandler))
101 {
102 }
103 
104 //*****************************
105 // AbstractTtlDriver interface
106 //*****************************
107 
112 template <typename reg_type>
114 {
115  return common::model::HardwareTypeEnum(reg_type::motor_type).toString() + " : " +
117 }
118 
124 template <typename reg_type>
125 int EndEffectorDriver<reg_type>::checkModelNumber(uint8_t id, uint16_t &model_number)
126 {
127  int ping_result = getModelNumber(id, model_number);
128 
129  if (ping_result == COMM_SUCCESS)
130  {
131  if (model_number && model_number != reg_type::MODEL_NUMBER)
132  {
133  return PING_WRONG_MODEL_NUMBER;
134  }
135  }
136 
137  return ping_result;
138 }
139 
146 template <typename reg_type>
147 int EndEffectorDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
148 {
149  int res = COMM_RX_FAIL;
150  uint32_t data{};
151  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
152  version = interpretFirmwareVersion(data);
153  return res;
154 }
155 
156 // ram read
157 
164 template <typename reg_type>
165 int EndEffectorDriver<reg_type>::readTemperature(uint8_t id, uint8_t &temperature)
166 {
167  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
168 }
169 
176 template <typename reg_type>
177 int EndEffectorDriver<reg_type>::readVoltage(uint8_t id, double &voltage)
178 {
179  uint16_t voltage_mV = 0;
180  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
181  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
182  return res;
183 }
184 
191 template <typename reg_type>
192 int EndEffectorDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
193 {
194  hardware_error_status = 0;
195  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
196 }
197 
204 template <typename reg_type>
205 int EndEffectorDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list,
206  std::vector<std::string> &firmware_list)
207 {
208  int res = 0;
209  firmware_list.clear();
210  std::vector<uint32_t> data_list{};
211  res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
212  for (auto const &data : data_list)
213  firmware_list.emplace_back(interpretFirmwareVersion(data));
214  return res;
215 }
216 
223 template <typename reg_type>
224 int EndEffectorDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list,
225  std::vector<uint8_t> &temperature_list)
226 {
227  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list,
228  temperature_list);
229 }
230 
237 template <typename reg_type>
238 int EndEffectorDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
239 {
240  voltage_list.clear();
241  std::vector<uint16_t> v_read;
242  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
243  for (auto const &v : v_read)
244  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
245  return res;
246 }
247 
254 template <typename reg_type>
255 int EndEffectorDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list,
256  std::vector<double> &voltage_list)
257 {
258  voltage_list.clear();
259  std::vector<uint16_t> v_read;
260  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
261  for (auto const &v : v_read)
262  voltage_list.emplace_back(static_cast<double>(v));
263  return res;
264 }
265 
272 template <typename reg_type>
273 int EndEffectorDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
274  std::vector<std::pair<double, uint8_t> > &data_list)
275 {
276  data_list.clear();
277 
278  std::vector<std::array<uint8_t, 3> > raw_data;
279  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
280 
281  for (auto const &data : raw_data)
282  {
283  // Voltage is first reg, uint16
284  auto voltage = static_cast<double>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0));
285 
286  // Temperature is second reg, uint8
287  uint8_t temperature = data.at(2);
288 
289  data_list.emplace_back(std::make_pair(voltage, temperature));
290  }
291 
292  return res;
293 }
294 
301 template <typename reg_type>
302 int EndEffectorDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list,
303  std::vector<uint8_t> &hw_error_list)
304 {
305  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
306 }
307 
308 // buttons status
309 
316 template <typename reg_type>
317 int EndEffectorDriver<reg_type>::readButton0Status(uint8_t id, common::model::EActionType &action)
318 {
319  uint8_t status;
320  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_0_STATUS, id, status);
321  action = interpretActionValue(status);
322  return res;
323 }
324 
331 template <typename reg_type>
332 int EndEffectorDriver<reg_type>::readButton1Status(uint8_t id, common::model::EActionType &action)
333 {
334  uint8_t status;
335  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_1_STATUS, id, status);
336  action = interpretActionValue(status);
337  return res;
338 }
339 
346 template <typename reg_type>
347 int EndEffectorDriver<reg_type>::readButton2Status(uint8_t id, common::model::EActionType &action)
348 {
349  uint8_t status;
350  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_2_STATUS, id, status);
351  action = interpretActionValue(status);
352  return res;
353 }
354 
361 template <typename reg_type>
363  std::vector<common::model::EActionType> &action_list)
364 {
365  std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3> > data_array_list;
366  int res;
367  res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_BUTTON_0_STATUS, { id },
368  data_array_list);
369  if (res == COMM_SUCCESS && data_array_list.size() == 1)
370  {
371  for (auto data : data_array_list.at(0))
372  {
373  action_list.push_back(interpretActionValue(data));
374  }
375  }
376  return res;
377 }
378 // accelerometers and collision
379 
386 template <typename reg_type>
388 {
389  return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X, id, x_value);
390 }
391 
398 template <typename reg_type>
400 {
401  return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y, id, y_value);
402 }
403 
410 template <typename reg_type>
412 {
413  return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z, id, z_value);
414 }
415 
422 template <typename reg_type>
424 {
425  uint8_t value = 0;
426  status = false;
427  int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS, id, value);
428  if (COMM_SUCCESS == res)
429  {
430  status = (value > 0) ? true : false;
431  }
432  return res;
433 }
434 
441 template <typename reg_type>
443 {
444  uint8_t value;
445  int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_IN, id, value);
446  in = (value > 0) ? true : false;
447  return res;
448 }
449 
456 template <typename reg_type>
458 {
459  return COMM_TX_ERROR;
460 }
461 
468 template <typename reg_type>
470 {
471  return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUT, id, static_cast<uint8_t>(out));
472 }
473 
480 template <typename reg_type>
482 {
483  return write<typename reg_type::TYPE_COLLISION_THRESHOLD>(reg_type::ADDR_COLLISION_THRESHOLD, id,
484  static_cast<uint8_t>(thresh));
485 }
486 
493 template <typename reg_type>
495 {
496  std::cout << "writeCollisionThreshAlgo2 not implemented for end effector" << std::endl;
497 
498  return 0;
499 }
500 
501 } // namespace ttl_driver
502 
503 #endif // EndEffectorDriver
ttl_driver::EndEffectorDriver::readAccelerometerXValue
int readAccelerometerXValue(uint8_t id, uint32_t &x_value) override
EndEffectorDriver<reg_type>::readAccelerometerXValue.
Definition: end_effector_driver.hpp:387
ttl_driver::EndEffectorDriver::syncReadHwErrorStatus
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
EndEffectorDriver<reg_type>::syncReadHwErrorStatus.
Definition: end_effector_driver.hpp:302
ttl_driver::EndEffectorDriver::writeDigitalOutput
int writeDigitalOutput(uint8_t id, bool out) override
EndEffectorDriver<reg_type>::setDigitalOutput.
Definition: end_effector_driver.hpp:469
ttl_driver::EndEffectorDriver::readAccelerometerYValue
int readAccelerometerYValue(uint8_t id, uint32_t &y_value) override
EndEffectorDriver<reg_type>::readAccelerometerYValue.
Definition: end_effector_driver.hpp:399
ttl_driver::EndEffectorDriver::readAccelerometerZValue
int readAccelerometerZValue(uint8_t id, uint32_t &z_value) override
EndEffectorDriver<reg_type>::readAccelerometerZValue.
Definition: end_effector_driver.hpp:411
ttl_driver::EndEffectorDriver::syncReadRawVoltage
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
EndEffectorDriver<reg_type>::syncReadRawVoltage.
Definition: end_effector_driver.hpp:255
ttl_driver::EndEffectorDriver::syncReadVoltage
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
EndEffectorDriver<reg_type>::syncReadVoltage.
Definition: end_effector_driver.hpp:238
ttl_driver::EndEffectorDriver::syncReadFirmwareVersion
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
EndEffectorDriver<reg_type>::syncReadFirmwareVersion.
Definition: end_effector_driver.hpp:205
end_effector_reg.hpp
ttl_driver::EndEffectorDriver::writeCollisionThresh
int writeCollisionThresh(uint8_t id, int thresh) override
EndEffectorDriver<reg_type>::writeCollisionThresh.
Definition: end_effector_driver.hpp:481
ttl_driver::EndEffectorDriver::writeCollisionThreshAlgo2
int writeCollisionThreshAlgo2(uint8_t id, int thresh) override
EndEffectorDriver<reg_type>::writeCollisionThreshAlgo2.
Definition: end_effector_driver.hpp:494
ttl_driver::EndEffectorDriver::EndEffectorDriver
EndEffectorDriver(std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler)
EndEffectorDriver<reg_type>::EndEffectorDriver.
Definition: end_effector_driver.hpp:98
ttl_driver::EndEffectorDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
EndEffectorDriver<reg_type>::readFirmwareVersion.
Definition: end_effector_driver.hpp:147
ttl_driver::EndEffectorDriver::readDigitalInput
int readDigitalInput(uint8_t id, bool &in) override
EndEffectorDriver<reg_type>::readDigitalInput.
Definition: end_effector_driver.hpp:442
ttl_driver::AbstractEndEffectorDriver::str
std::string str() const override
AbstractEndEffectorDriver::str : build a string describing the object. For debug purpose only.
Definition: abstract_end_effector_driver.cpp:49
ttl_driver::EndEffectorDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
EndEffectorDriver<reg_type>::readVoltage.
Definition: end_effector_driver.hpp:177
ttl_driver::EndEffectorDriver::readButton1Status
int readButton1Status(uint8_t id, common::model::EActionType &action) override
EndEffectorDriver<reg_type>::readButton1Status.
Definition: end_effector_driver.hpp:332
abstract_end_effector_driver.hpp
ttl_driver::EndEffectorDriver::readCollisionStatus
int readCollisionStatus(uint8_t id, bool &status) override
EndEffectorDriver<reg_type>::readCollisionStatus.
Definition: end_effector_driver.hpp:423
ttl_driver::EndEffectorDriver::syncReadTemperature
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
EndEffectorDriver<reg_type>::syncReadTemperature.
Definition: end_effector_driver.hpp:224
ttl_driver::EndEffectorDriver
The EndEffectorDriver class.
Definition: end_effector_driver.hpp:42
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::EndEffectorDriver::syncReadButtonsStatus
int syncReadButtonsStatus(const uint8_t &id, std::vector< common::model::EActionType > &action_list) override
EndEffectorDriver<reg_type>::syncReadButtonsStatus.
Definition: end_effector_driver.hpp:362
ttl_driver::EndEffectorDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
EndEffectorDriver<reg_type>::readHwErrorStatus.
Definition: end_effector_driver.hpp:192
ttl_driver::EndEffectorDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
EndEffectorDriver<reg_type>::readTemperature.
Definition: end_effector_driver.hpp:165
ttl_driver::AbstractEndEffectorDriver
The AbstractEndEffectorDriver class.
Definition: abstract_end_effector_driver.hpp:41
ttl_driver::EndEffectorDriver::writeDigitalInput
int writeDigitalInput(uint8_t id, bool in) override
EndEffectorDriver<reg_type>::writeDigitalInput not implemented for real end effectors.
Definition: end_effector_driver.hpp:457
ttl_driver::EndEffectorDriver::readButton0Status
int readButton0Status(uint8_t id, common::model::EActionType &action) override
EndEffectorDriver<reg_type>::readButton0Status.
Definition: end_effector_driver.hpp:317
ttl_driver::EndEffectorDriver::str
std::string str() const override
EndEffectorDriver<reg_type>::str.
Definition: end_effector_driver.hpp:113
ttl_driver::EndEffectorDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
EndEffectorDriver<reg_type>::checkModelNumber.
Definition: end_effector_driver.hpp:125
ttl_driver::EndEffectorDriver::readButton2Status
int readButton2Status(uint8_t id, common::model::EActionType &action) override
EndEffectorDriver<reg_type>::readButton2Status.
Definition: end_effector_driver.hpp:347
ttl_driver::EndEffectorDriver::syncReadHwStatus
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t > > &data_list) override
EndEffectorDriver<reg_type>::syncReadHwStatus.
Definition: end_effector_driver.hpp:273


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