ned3pro_end_effector_driver.hpp
Go to the documentation of this file.
1 /*
2 ned3pro_end_effector_driver.hpp
3 Copyright (C) 2024 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 NED3PRO_END_EFFECTOR_DRIVER_HPP
18 #define NED3PRO_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 
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 = Ned3ProEndEffectorReg>
43  {
44  public:
45  Ned3ProEndEffectorDriver(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 readCollisionThresh(uint8_t id, uint32_t &thresh);
88 
89  int writeCollisionThreshAlgo2(uint8_t id, int thresh) override;
90  int readCollisionThreshAlgo2(uint8_t id, uint32_t &thresh);
91  };
92 
93  // definition of methods
94 
98  template <typename reg_type>
99  Ned3ProEndEffectorDriver<reg_type>::Ned3ProEndEffectorDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
100  std::shared_ptr<dynamixel::PacketHandler> packetHandler) : AbstractEndEffectorDriver(std::move(portHandler),
101  std::move(packetHandler))
102  {
103  }
104 
105  //*****************************
106  // AbstractTtlDriver interface
107  //*****************************
108 
113  template <typename reg_type>
115  {
116  return common::model::HardwareTypeEnum(reg_type::motor_type).toString() + " : " + ttl_driver::AbstractEndEffectorDriver::str();
117  }
118 
124  template <typename reg_type>
126  {
127  uint16_t model_number = 0;
128  int ping_result = getModelNumber(id, model_number);
129 
130  if (ping_result == COMM_SUCCESS)
131  {
132  if (model_number && model_number != reg_type::MODEL_NUMBER)
133  {
134  return PING_WRONG_MODEL_NUMBER;
135  }
136  }
137 
138  return ping_result;
139  }
140 
147  template <typename reg_type>
148  int Ned3ProEndEffectorDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
149  {
150  int res = COMM_RX_FAIL;
151  uint32_t data{};
152  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
153  version = interpretFirmwareVersion(data);
154  return res;
155  }
156 
157  // ram read
158 
165  template <typename reg_type>
166  int Ned3ProEndEffectorDriver<reg_type>::readTemperature(uint8_t id, uint8_t &temperature)
167  {
168  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
169  }
170 
177  template <typename reg_type>
178  int Ned3ProEndEffectorDriver<reg_type>::readVoltage(uint8_t id, double &voltage)
179  {
180  uint16_t voltage_mV = 0;
181  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
182  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
183  return res;
184  }
185 
192  template <typename reg_type>
193  int Ned3ProEndEffectorDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
194  {
195  hardware_error_status = 0;
196  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
197  }
198 
205  template <typename reg_type>
206  int Ned3ProEndEffectorDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, 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 Ned3ProEndEffectorDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
225  {
226  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
227  }
228 
235  template <typename reg_type>
236  int Ned3ProEndEffectorDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
237  {
238  voltage_list.clear();
239  std::vector<uint16_t> v_read;
240  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
241  for (auto const &v : v_read)
242  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
243  return res;
244  }
245 
252  template <typename reg_type>
253  int Ned3ProEndEffectorDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
254  {
255  voltage_list.clear();
256  std::vector<uint16_t> v_read;
257  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
258  for (auto const &v : v_read)
259  voltage_list.emplace_back(static_cast<double>(v));
260  return res;
261  }
262 
269  template <typename reg_type>
270  int Ned3ProEndEffectorDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
271  std::vector<std::pair<double, uint8_t>> &data_list)
272  {
273  data_list.clear();
274 
275  std::vector<std::array<uint8_t, 3>> raw_data;
276  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
277 
278  for (auto const &data : raw_data)
279  {
280  // Voltage is first reg, uint16
281  auto voltage = static_cast<double>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0));
282 
283  // Temperature is second reg, uint8
284  uint8_t temperature = data.at(2);
285 
286  data_list.emplace_back(std::make_pair(voltage, temperature));
287  }
288 
289  return res;
290  }
291 
298  template <typename reg_type>
299  int Ned3ProEndEffectorDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
300  {
301  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
302  }
303 
304  // buttons status
305 
312  template <typename reg_type>
314  common::model::EActionType &action)
315  {
316  uint8_t status;
317  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_CUSTOM, id, status);
318  action = interpretActionValue(status);
319  return res;
320  }
321 
328  template <typename reg_type>
329  int Ned3ProEndEffectorDriver<reg_type>::readButton1Status(uint8_t id, common::model::EActionType &action)
330  {
331  uint8_t status;
332  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_SAVE, id, status);
333  action = interpretActionValue(status);
334  return res;
335  }
336 
343  template <typename reg_type>
344  int Ned3ProEndEffectorDriver<reg_type>::readButton2Status(uint8_t id, common::model::EActionType &action)
345  {
346  uint8_t status;
347  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_FREEDRIVE, id, status);
348  action = interpretActionValue(status);
349  return res;
350  }
351 
358  template <typename reg_type>
360  std::vector<common::model::EActionType> &action_list)
361  {
362  std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3>> data_array_list;
363  int res;
364  res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_STATE_BUTTON_FREEDRIVE, {id}, data_array_list);
365  if (res == COMM_SUCCESS && data_array_list.size() == 1)
366  {
367  for (auto data : data_array_list.at(0))
368  {
369  action_list.push_back(interpretActionValue(data));
370  }
371  }
372  return res;
373  }
374  // accelerometers and collision
375 
382  template <typename reg_type>
384  {
385  return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X, id, x_value);
386  }
387 
394  template <typename reg_type>
396  {
397  return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y, id, y_value);
398  }
399 
406  template <typename reg_type>
408  {
409  return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z, id, z_value);
410  }
411 
418  template <typename reg_type>
420  {
421  uint8_t value = 0;
422  status = false;
423  int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS, id, value);
424  if (COMM_SUCCESS == res)
425  {
426  status = (value > 0) ? true : false;
427  }
428  return res;
429  }
430 
437  template <typename reg_type>
439  {
440  uint8_t value;
441  int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_INPUT, id, value);
442  in = (value > 0) ? true : false;
443  return res;
444  }
445 
452  template <typename reg_type>
454  {
455  return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUTPUT, id, static_cast<uint8_t>(out));
456  }
457 
464  template <typename reg_type>
466  {
467  return write<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_1>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_1, id, static_cast<uint32_t>(thresh));
468  }
469 
476  template <typename reg_type>
478  {
479  return read<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_1>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_1, id, thresh);
480  }
481 
488  template <typename reg_type>
490  {
491  return write<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_2>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_2, id, static_cast<uint32_t>(thresh));
492  }
493 
500  template <typename reg_type>
502  {
503  return read<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_2>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_2, id, thresh);
504  }
505 
506 } // ttl_driver
507 
508 #endif // Ned3ProEndEffectorDriver
ned3pro_end_effector_reg.hpp
ttl_driver::Ned3ProEndEffectorDriver::syncReadHwErrorStatus
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
Ned3ProEndEffectorDriver<reg_type>::syncReadHwErrorStatus.
Definition: ned3pro_end_effector_driver.hpp:299
ttl_driver::Ned3ProEndEffectorDriver::writeCollisionThreshAlgo2
int writeCollisionThreshAlgo2(uint8_t id, int thresh) override
Ned3ProEndEffectorDriver<reg_type>::writeCollisionThreshAlgo2.
Definition: ned3pro_end_effector_driver.hpp:489
ttl_driver::Ned3ProEndEffectorDriver::readCollisionStatus
int readCollisionStatus(uint8_t id, bool &status) override
Ned3ProEndEffectorDriver<reg_type>::readCollisionStatus.
Definition: ned3pro_end_effector_driver.hpp:419
ttl_driver::Ned3ProEndEffectorDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
Ned3ProEndEffectorDriver<reg_type>::readVoltage.
Definition: ned3pro_end_effector_driver.hpp:178
ttl_driver::Ned3ProEndEffectorDriver::syncReadButtonsStatus
int syncReadButtonsStatus(const uint8_t &id, std::vector< common::model::EActionType > &action_list) override
Ned3ProEndEffectorDriver<reg_type>::syncReadButtonsStatus.
Definition: ned3pro_end_effector_driver.hpp:359
ttl_driver::Ned3ProEndEffectorDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
Ned3ProEndEffectorDriver<reg_type>::readHwErrorStatus.
Definition: ned3pro_end_effector_driver.hpp:193
ttl_driver::Ned3ProEndEffectorDriver::writeCollisionThresh
int writeCollisionThresh(uint8_t id, int thresh) override
Ned3ProEndEffectorDriver<reg_type>::writeCollisionThresh.
Definition: ned3pro_end_effector_driver.hpp:465
ttl_driver::Ned3ProEndEffectorDriver::checkModelNumber
int checkModelNumber(uint8_t id) override
Ned3ProEndEffectorDriver<reg_type>::checkModelNumber.
Definition: ned3pro_end_effector_driver.hpp:125
ttl_driver::Ned3ProEndEffectorDriver::syncReadVoltage
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
Ned3ProEndEffectorDriver<reg_type>::syncReadVoltage.
Definition: ned3pro_end_effector_driver.hpp:236
ttl_driver::Ned3ProEndEffectorDriver::readAccelerometerZValue
int readAccelerometerZValue(uint8_t id, uint32_t &z_value) override
Ned3ProEndEffectorDriver<reg_type>::readAccelerometerZValue.
Definition: ned3pro_end_effector_driver.hpp:407
ttl_driver::Ned3ProEndEffectorDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
Ned3ProEndEffectorDriver<reg_type>::readTemperature.
Definition: ned3pro_end_effector_driver.hpp:166
ttl_driver::Ned3ProEndEffectorDriver::writeDigitalOutput
int writeDigitalOutput(uint8_t id, bool out) override
Ned3ProEndEffectorDriver<reg_type>::setDigitalOutput.
Definition: ned3pro_end_effector_driver.hpp:453
ttl_driver::Ned3ProEndEffectorDriver::readButton1Status
int readButton1Status(uint8_t id, common::model::EActionType &action) override
Ned3ProEndEffectorDriver<reg_type>::readButton1Status.
Definition: ned3pro_end_effector_driver.hpp:329
ttl_driver::Ned3ProEndEffectorDriver::Ned3ProEndEffectorDriver
Ned3ProEndEffectorDriver(std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler)
Ned3ProEndEffectorDriver<reg_type>::Ned3ProEndEffectorDriver.
Definition: ned3pro_end_effector_driver.hpp:99
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
abstract_end_effector_driver.hpp
ttl_driver::Ned3ProEndEffectorDriver::readCollisionThreshAlgo2
int readCollisionThreshAlgo2(uint8_t id, uint32_t &thresh)
Ned3ProEndEffectorDriver<reg_type>::readCollisionThreshAlgo2.
Definition: ned3pro_end_effector_driver.hpp:501
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::Ned3ProEndEffectorDriver::readAccelerometerYValue
int readAccelerometerYValue(uint8_t id, uint32_t &y_value) override
Ned3ProEndEffectorDriver<reg_type>::readAccelerometerYValue.
Definition: ned3pro_end_effector_driver.hpp:395
ttl_driver::Ned3ProEndEffectorDriver::readCollisionThresh
int readCollisionThresh(uint8_t id, uint32_t &thresh)
Ned3ProEndEffectorDriver<reg_type>::readCollisionThresh.
Definition: ned3pro_end_effector_driver.hpp:477
ttl_driver::Ned3ProEndEffectorDriver::readButton0Status
int readButton0Status(uint8_t id, common::model::EActionType &action) override
Ned3ProEndEffectorDriver<reg_type>::readButton0Status.
Definition: ned3pro_end_effector_driver.hpp:313
ttl_driver::Ned3ProEndEffectorDriver::syncReadRawVoltage
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
Ned3ProEndEffectorDriver<reg_type>::syncReadRawVoltage.
Definition: ned3pro_end_effector_driver.hpp:253
ttl_driver::AbstractEndEffectorDriver
The AbstractEndEffectorDriver class.
Definition: abstract_end_effector_driver.hpp:41
ttl_driver::Ned3ProEndEffectorDriver::readButton2Status
int readButton2Status(uint8_t id, common::model::EActionType &action) override
Ned3ProEndEffectorDriver<reg_type>::readButton2Status.
Definition: ned3pro_end_effector_driver.hpp:344
ttl_driver::Ned3ProEndEffectorDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
Ned3ProEndEffectorDriver<reg_type>::readFirmwareVersion.
Definition: ned3pro_end_effector_driver.hpp:148
ttl_driver::Ned3ProEndEffectorDriver
The Ned3ProEndEffectorDriver class.
Definition: ned3pro_end_effector_driver.hpp:42
ttl_driver::Ned3ProEndEffectorDriver::syncReadTemperature
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
Ned3ProEndEffectorDriver<reg_type>::syncReadTemperature.
Definition: ned3pro_end_effector_driver.hpp:224
ttl_driver::Ned3ProEndEffectorDriver::readDigitalInput
int readDigitalInput(uint8_t id, bool &in) override
Ned3ProEndEffectorDriver<reg_type>::readDigitalInput.
Definition: ned3pro_end_effector_driver.hpp:438
ttl_driver::Ned3ProEndEffectorDriver::syncReadHwStatus
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t >> &data_list) override
Ned3ProEndEffectorDriver<reg_type>::syncReadHwStatus.
Definition: ned3pro_end_effector_driver.hpp:270
ttl_driver::Ned3ProEndEffectorDriver::readAccelerometerXValue
int readAccelerometerXValue(uint8_t id, uint32_t &x_value) override
Ned3ProEndEffectorDriver<reg_type>::readAccelerometerXValue.
Definition: ned3pro_end_effector_driver.hpp:383
ttl_driver::Ned3ProEndEffectorDriver::str
std::string str() const override
Ned3ProEndEffectorDriver<reg_type>::str.
Definition: ned3pro_end_effector_driver.hpp:114
ttl_driver::Ned3ProEndEffectorDriver::syncReadFirmwareVersion
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
Ned3ProEndEffectorDriver<reg_type>::syncReadFirmwareVersion.
Definition: ned3pro_end_effector_driver.hpp:206


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