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


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Thu Dec 11 2025 11:41:10