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) 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, std::vector<std::pair<double, uint8_t> >& data_list) override;
66 
67  int syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list) override;
68 
69  public:
70  // AbstractEndEffectorDriver
71 
72  int readButton0Status(uint8_t id, common::model::EActionType& action) override;
73  int readButton1Status(uint8_t id, common::model::EActionType& action) override;
74  int readButton2Status(uint8_t id, common::model::EActionType& action) override;
75  int syncReadButtonsStatus(const uint8_t& id, std::vector<common::model::EActionType>& action_list) override;
76 
77  int readAccelerometerXValue(uint8_t id, uint32_t& x_value) override;
78  int readAccelerometerYValue(uint8_t id, uint32_t& y_value) override;
79  int readAccelerometerZValue(uint8_t id, uint32_t& z_value) override;
80 
81  int readCollisionStatus(uint8_t id, bool& status) override;
82 
83  int readDigitalInput(uint8_t id, bool& in) override;
84  int writeDigitalOutput(uint8_t id, bool out) override;
85 
86  int writeCollisionThresh(uint8_t id, int thresh) override;
87  int writeCollisionThreshAlgo2(uint8_t id, int thresh) override;
88 };
89 
90 // definition of methods
91 
95 template<typename reg_type>
96 EndEffectorDriver<reg_type>::EndEffectorDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
97  std::shared_ptr<dynamixel::PacketHandler> packetHandler) :
98  AbstractEndEffectorDriver(std::move(portHandler),
99  std::move(packetHandler))
100 {}
101 
102 //*****************************
103 // AbstractTtlDriver interface
104 //*****************************
105 
110 template<typename reg_type>
112 {
113  return common::model::HardwareTypeEnum(reg_type::motor_type).toString() + " : " + ttl_driver::AbstractEndEffectorDriver::str();
114 }
115 
121 template<typename reg_type>
123 {
124  uint16_t model_number = 0;
125  int ping_result = getModelNumber(id, model_number);
126 
127  if (ping_result == COMM_SUCCESS)
128  {
129  if (model_number && model_number != reg_type::MODEL_NUMBER)
130  {
131  return PING_WRONG_MODEL_NUMBER;
132  }
133  }
134 
135  return ping_result;
136 }
137 
144 template<typename reg_type>
145 int EndEffectorDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
146 {
147  int res = COMM_RX_FAIL;
148  uint32_t data{};
149  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
150  version = interpretFirmwareVersion(data);
151  return res;
152 }
153 
154 // ram read
155 
162 template<typename reg_type>
163 int EndEffectorDriver<reg_type>::readTemperature(uint8_t id, uint8_t& temperature)
164 {
165  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
166 }
167 
174 template<typename reg_type>
175 int EndEffectorDriver<reg_type>::readVoltage(uint8_t id, double& voltage)
176 {
177  uint16_t voltage_mV = 0;
178  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
179  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
180  return res;
181 }
182 
189 template<typename reg_type>
190 int EndEffectorDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t& hardware_error_status)
191 {
192  hardware_error_status = 0;
193  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
194 }
195 
202 template<typename reg_type>
203 int EndEffectorDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
204 {
205  int res = 0;
206  firmware_list.clear();
207  std::vector<uint32_t> data_list{};
208  res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
209  for(auto const& data : data_list)
210  firmware_list.emplace_back(interpretFirmwareVersion(data));
211  return res;
212 }
213 
220 template<typename reg_type>
221 int EndEffectorDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t>& temperature_list)
222 {
223  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
224 }
225 
232 template<typename reg_type>
233 int EndEffectorDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
234 {
235  voltage_list.clear();
236  std::vector<uint16_t> v_read;
237  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
238  for(auto const& v : v_read)
239  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
240  return res;
241 }
242 
249 template<typename reg_type>
250 int EndEffectorDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
251 {
252  voltage_list.clear();
253  std::vector<uint16_t> v_read;
254  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
255  for(auto const& v : v_read)
256  voltage_list.emplace_back(static_cast<double>(v));
257  return res;
258 }
259 
266 template<typename reg_type>
267 int EndEffectorDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
268  std::vector<std::pair<double, uint8_t> > &data_list)
269 {
270  data_list.clear();
271 
272  std::vector<std::array<uint8_t, 3> > raw_data;
273  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
274 
275  for (auto const& data : raw_data)
276  {
277  // Voltage is first reg, uint16
278  auto voltage = static_cast<double>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0));
279 
280  // Temperature is second reg, uint8
281  uint8_t temperature = data.at(2);
282 
283  data_list.emplace_back(std::make_pair(voltage, temperature));
284  }
285 
286  return res;
287 }
288 
295 template<typename reg_type>
296 int EndEffectorDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
297 {
298  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
299 }
300 
301 // buttons status
302 
309 template<typename reg_type>
311  common::model::EActionType& action)
312 {
313  uint8_t status;
314  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_0_STATUS, id, status);
315  action = interpretActionValue(status);
316  return res;
317 }
318 
325 template<typename reg_type>
326 int EndEffectorDriver<reg_type>::readButton1Status(uint8_t id, common::model::EActionType& action)
327 {
328  uint8_t status;
329  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_1_STATUS, id, status);
330  action = interpretActionValue(status);
331  return res;
332 }
333 
340 template<typename reg_type>
341 int EndEffectorDriver<reg_type>::readButton2Status(uint8_t id, common::model::EActionType& action)
342 {
343  uint8_t status;
344  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_2_STATUS, id, status);
345  action = interpretActionValue(status);
346  return res;
347 }
348 
355 template<typename reg_type>
357  std::vector<common::model::EActionType>& action_list)
358 {
359  std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3> > data_array_list;
360  int res;
361  res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_BUTTON_0_STATUS, {id}, data_array_list);
362  if (res == COMM_SUCCESS && data_array_list.size() == 1)
363  {
364  for (auto data : data_array_list.at(0))
365  {
366  action_list.push_back(interpretActionValue(data));
367  }
368  }
369  return res;
370 }
371 // accelerometers and collision
372 
379 template<typename reg_type>
381 {
382  return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X, id, x_value);
383 }
384 
391 template<typename reg_type>
393 {
394  return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y, id, y_value);
395 }
396 
403 template<typename reg_type>
405 {
406  return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z, id, z_value);
407 }
408 
415 template<typename reg_type>
417 {
418  uint8_t value = 0;
419  status = false;
420  int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS, id, value);
421  if (COMM_SUCCESS == res)
422  {
423  status = (value > 0) ? true : false;
424  }
425  return res;
426 }
427 
434 template<typename reg_type>
436 {
437  uint8_t value;
438  int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_IN, id, value);
439  in = (value > 0) ? true : false;
440  return res;
441 }
442 
449 template<typename reg_type>
451 {
452  return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUT, id, static_cast<uint8_t>(out));
453 }
454 
461 template<typename reg_type>
463 {
464  return write<typename reg_type::TYPE_COLLISION_THRESHOLD>(reg_type::ADDR_COLLISION_THRESHOLD, id, static_cast<uint8_t>(thresh));
465 }
466 
473 template<typename reg_type>
475 {
476  std::cout << "writeCollisionThreshAlgo2 not implemented for end effector" << std::endl;
477 
478  return 0;
479 }
480 
481 } // ttl_driver
482 
483 #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:380
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:296
ttl_driver::EndEffectorDriver::writeDigitalOutput
int writeDigitalOutput(uint8_t id, bool out) override
EndEffectorDriver<reg_type>::setDigitalOutput.
Definition: end_effector_driver.hpp:450
ttl_driver::EndEffectorDriver::readAccelerometerYValue
int readAccelerometerYValue(uint8_t id, uint32_t &y_value) override
EndEffectorDriver<reg_type>::readAccelerometerYValue.
Definition: end_effector_driver.hpp:392
ttl_driver::EndEffectorDriver::readAccelerometerZValue
int readAccelerometerZValue(uint8_t id, uint32_t &z_value) override
EndEffectorDriver<reg_type>::readAccelerometerZValue.
Definition: end_effector_driver.hpp:404
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:250
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:233
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:203
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:462
ttl_driver::EndEffectorDriver::writeCollisionThreshAlgo2
int writeCollisionThreshAlgo2(uint8_t id, int thresh) override
EndEffectorDriver<reg_type>::writeCollisionThreshAlgo2.
Definition: end_effector_driver.hpp:474
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:96
ttl_driver::EndEffectorDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
EndEffectorDriver<reg_type>::readFirmwareVersion.
Definition: end_effector_driver.hpp:145
ttl_driver::EndEffectorDriver::readDigitalInput
int readDigitalInput(uint8_t id, bool &in) override
EndEffectorDriver<reg_type>::readDigitalInput.
Definition: end_effector_driver.hpp:435
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:48
ttl_driver::EndEffectorDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
EndEffectorDriver<reg_type>::readVoltage.
Definition: end_effector_driver.hpp:175
ttl_driver::EndEffectorDriver::readButton1Status
int readButton1Status(uint8_t id, common::model::EActionType &action) override
EndEffectorDriver<reg_type>::readButton1Status.
Definition: end_effector_driver.hpp:326
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:416
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:221
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:356
ttl_driver::EndEffectorDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
EndEffectorDriver<reg_type>::readHwErrorStatus.
Definition: end_effector_driver.hpp:190
ttl_driver::EndEffectorDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
EndEffectorDriver<reg_type>::readTemperature.
Definition: end_effector_driver.hpp:163
ttl_driver::AbstractEndEffectorDriver
The AbstractEndEffectorDriver class.
Definition: abstract_end_effector_driver.hpp:41
ttl_driver::EndEffectorDriver::readButton0Status
int readButton0Status(uint8_t id, common::model::EActionType &action) override
EndEffectorDriver<reg_type>::readButton0Status.
Definition: end_effector_driver.hpp:310
ttl_driver::EndEffectorDriver::str
std::string str() const override
EndEffectorDriver<reg_type>::str.
Definition: end_effector_driver.hpp:111
ttl_driver::EndEffectorDriver::readButton2Status
int readButton2Status(uint8_t id, common::model::EActionType &action) override
EndEffectorDriver<reg_type>::readButton2Status.
Definition: end_effector_driver.hpp:341
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:267
ttl_driver::EndEffectorDriver::checkModelNumber
int checkModelNumber(uint8_t id) override
EndEffectorDriver<reg_type>::checkModelNumber.
Definition: end_effector_driver.hpp:122


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Wed May 21 2025 08:30:14