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, 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 readCollisionThresh(uint8_t id, uint32_t &thresh);
90 
91  int writeCollisionThreshAlgo2(uint8_t id, int thresh) override;
92  int readCollisionThreshAlgo2(uint8_t id, uint32_t &thresh);
93 };
94 
95 // definition of methods
96 
100 template <typename reg_type>
101 Ned3ProEndEffectorDriver<reg_type>::Ned3ProEndEffectorDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
102  std::shared_ptr<dynamixel::PacketHandler> packetHandler)
103  : AbstractEndEffectorDriver(std::move(portHandler), std::move(packetHandler))
104 {
105 }
106 
107 //*****************************
108 // AbstractTtlDriver interface
109 //*****************************
110 
115 template <typename reg_type>
117 {
118  return common::model::HardwareTypeEnum(reg_type::motor_type).toString() + " : " +
120 }
121 
127 template <typename reg_type>
128 int Ned3ProEndEffectorDriver<reg_type>::checkModelNumber(uint8_t id, uint16_t &model_number)
129 {
130  int ping_result = getModelNumber(id, model_number);
131 
132  if (ping_result == COMM_SUCCESS)
133  {
134  if (model_number && model_number != reg_type::MODEL_NUMBER)
135  {
136  return PING_WRONG_MODEL_NUMBER;
137  }
138  }
139 
140  return ping_result;
141 }
142 
149 template <typename reg_type>
150 int Ned3ProEndEffectorDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
151 {
152  int res = COMM_RX_FAIL;
153  uint32_t data{};
154  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
155  version = interpretFirmwareVersion(data);
156  return res;
157 }
158 
159 // ram read
160 
167 template <typename reg_type>
168 int Ned3ProEndEffectorDriver<reg_type>::readTemperature(uint8_t id, uint8_t &temperature)
169 {
170  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
171 }
172 
179 template <typename reg_type>
180 int Ned3ProEndEffectorDriver<reg_type>::readVoltage(uint8_t id, double &voltage)
181 {
182  uint16_t voltage_mV = 0;
183  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
184  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
185  return res;
186 }
187 
194 template <typename reg_type>
195 int Ned3ProEndEffectorDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
196 {
197  hardware_error_status = 0;
198  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
199 }
200 
207 template <typename reg_type>
208 int Ned3ProEndEffectorDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list,
209  std::vector<std::string> &firmware_list)
210 {
211  int res = 0;
212  firmware_list.clear();
213  std::vector<uint32_t> data_list{};
214  res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
215  for (auto const &data : data_list)
216  firmware_list.emplace_back(interpretFirmwareVersion(data));
217  return res;
218 }
219 
226 template <typename reg_type>
227 int Ned3ProEndEffectorDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list,
228  std::vector<uint8_t> &temperature_list)
229 {
230  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list,
231  temperature_list);
232 }
233 
240 template <typename reg_type>
241 int Ned3ProEndEffectorDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list,
242  std::vector<double> &voltage_list)
243 {
244  voltage_list.clear();
245  std::vector<uint16_t> v_read;
246  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
247  for (auto const &v : v_read)
248  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
249  return res;
250 }
251 
258 template <typename reg_type>
259 int Ned3ProEndEffectorDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list,
260  std::vector<double> &voltage_list)
261 {
262  voltage_list.clear();
263  std::vector<uint16_t> v_read;
264  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
265  for (auto const &v : v_read)
266  voltage_list.emplace_back(static_cast<double>(v));
267  return res;
268 }
269 
276 template <typename reg_type>
277 int Ned3ProEndEffectorDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
278  std::vector<std::pair<double, uint8_t>> &data_list)
279 {
280  data_list.clear();
281 
282  std::vector<std::array<uint8_t, 3>> raw_data;
283  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
284 
285  for (auto const &data : raw_data)
286  {
287  // Voltage is first reg, uint16
288  auto voltage = static_cast<double>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0));
289 
290  // Temperature is second reg, uint8
291  uint8_t temperature = data.at(2);
292 
293  data_list.emplace_back(std::make_pair(voltage, temperature));
294  }
295 
296  return res;
297 }
298 
305 template <typename reg_type>
306 int Ned3ProEndEffectorDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list,
307  std::vector<uint8_t> &hw_error_list)
308 {
309  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
310 }
311 
312 // buttons status
313 
320 template <typename reg_type>
321 int Ned3ProEndEffectorDriver<reg_type>::readButton0Status(uint8_t id, common::model::EActionType &action)
322 {
323  uint8_t status;
324  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_CUSTOM, id, status);
325  action = interpretActionValue(status);
326  return res;
327 }
328 
335 template <typename reg_type>
336 int Ned3ProEndEffectorDriver<reg_type>::readButton1Status(uint8_t id, common::model::EActionType &action)
337 {
338  uint8_t status;
339  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_SAVE, id, status);
340  action = interpretActionValue(status);
341  return res;
342 }
343 
350 template <typename reg_type>
351 int Ned3ProEndEffectorDriver<reg_type>::readButton2Status(uint8_t id, common::model::EActionType &action)
352 {
353  uint8_t status;
354  int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_FREEDRIVE, id, status);
355  action = interpretActionValue(status);
356  return res;
357 }
358 
365 template <typename reg_type>
367  std::vector<common::model::EActionType> &action_list)
368 {
369  std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3>> data_array_list;
370  int res;
371  res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_STATE_BUTTON_FREEDRIVE,
372  { id }, data_array_list);
373  if (res == COMM_SUCCESS && data_array_list.size() == 1)
374  {
375  for (auto data : data_array_list.at(0))
376  {
377  action_list.push_back(interpretActionValue(data));
378  }
379  }
380  return res;
381 }
382 // accelerometers and collision
383 
390 template <typename reg_type>
392 {
393  return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X, id, x_value);
394 }
395 
402 template <typename reg_type>
404 {
405  return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y, id, y_value);
406 }
407 
414 template <typename reg_type>
416 {
417  return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z, id, z_value);
418 }
419 
426 template <typename reg_type>
428 {
429  uint8_t value = 0;
430  status = false;
431  int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS, id, value);
432  if (COMM_SUCCESS == res)
433  {
434  status = (value > 0) ? true : false;
435  }
436  return res;
437 }
438 
445 template <typename reg_type>
447 {
448  uint8_t value;
449  int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_INPUT, id, value);
450  in = (value > 0) ? true : false;
451  return res;
452 }
453 
460 template <typename reg_type>
462 {
463  return COMM_TX_ERROR;
464 }
465 
472 template <typename reg_type>
474 {
475  return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUTPUT, id, static_cast<uint8_t>(out));
476 }
477 
484 template <typename reg_type>
486 {
487  return write<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_1>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_1, id,
488  static_cast<uint32_t>(thresh));
489 }
490 
497 template <typename reg_type>
499 {
500  return read<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_1>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_1, id,
501  thresh);
502 }
503 
510 template <typename reg_type>
512 {
513  return write<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_2>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_2, id,
514  static_cast<uint32_t>(thresh));
515 }
516 
523 template <typename reg_type>
525 {
526  return read<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_2>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_2, id,
527  thresh);
528 }
529 
530 } // namespace ttl_driver
531 
532 #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:306
ttl_driver::Ned3ProEndEffectorDriver::writeCollisionThreshAlgo2
int writeCollisionThreshAlgo2(uint8_t id, int thresh) override
Ned3ProEndEffectorDriver<reg_type>::writeCollisionThreshAlgo2.
Definition: ned3pro_end_effector_driver.hpp:511
ttl_driver::Ned3ProEndEffectorDriver::readCollisionStatus
int readCollisionStatus(uint8_t id, bool &status) override
Ned3ProEndEffectorDriver<reg_type>::readCollisionStatus.
Definition: ned3pro_end_effector_driver.hpp:427
ttl_driver::Ned3ProEndEffectorDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
Ned3ProEndEffectorDriver<reg_type>::readVoltage.
Definition: ned3pro_end_effector_driver.hpp:180
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:366
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:195
ttl_driver::Ned3ProEndEffectorDriver::writeCollisionThresh
int writeCollisionThresh(uint8_t id, int thresh) override
Ned3ProEndEffectorDriver<reg_type>::writeCollisionThresh.
Definition: ned3pro_end_effector_driver.hpp:485
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:241
ttl_driver::Ned3ProEndEffectorDriver::readAccelerometerZValue
int readAccelerometerZValue(uint8_t id, uint32_t &z_value) override
Ned3ProEndEffectorDriver<reg_type>::readAccelerometerZValue.
Definition: ned3pro_end_effector_driver.hpp:415
ttl_driver::Ned3ProEndEffectorDriver::writeDigitalInput
int writeDigitalInput(uint8_t id, bool in) override
Ned3ProEndEffectorDriver<reg_type>::writeDigitalInput not implemented for real end effectors.
Definition: ned3pro_end_effector_driver.hpp:461
ttl_driver::Ned3ProEndEffectorDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
Ned3ProEndEffectorDriver<reg_type>::readTemperature.
Definition: ned3pro_end_effector_driver.hpp:168
ttl_driver::Ned3ProEndEffectorDriver::writeDigitalOutput
int writeDigitalOutput(uint8_t id, bool out) override
Ned3ProEndEffectorDriver<reg_type>::setDigitalOutput.
Definition: ned3pro_end_effector_driver.hpp:473
ttl_driver::Ned3ProEndEffectorDriver::readButton1Status
int readButton1Status(uint8_t id, common::model::EActionType &action) override
Ned3ProEndEffectorDriver<reg_type>::readButton1Status.
Definition: ned3pro_end_effector_driver.hpp:336
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:101
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
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:524
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::Ned3ProEndEffectorDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
Ned3ProEndEffectorDriver<reg_type>::checkModelNumber.
Definition: ned3pro_end_effector_driver.hpp:128
ttl_driver::Ned3ProEndEffectorDriver::readAccelerometerYValue
int readAccelerometerYValue(uint8_t id, uint32_t &y_value) override
Ned3ProEndEffectorDriver<reg_type>::readAccelerometerYValue.
Definition: ned3pro_end_effector_driver.hpp:403
ttl_driver::Ned3ProEndEffectorDriver::readCollisionThresh
int readCollisionThresh(uint8_t id, uint32_t &thresh)
Ned3ProEndEffectorDriver<reg_type>::readCollisionThresh.
Definition: ned3pro_end_effector_driver.hpp:498
ttl_driver::Ned3ProEndEffectorDriver::readButton0Status
int readButton0Status(uint8_t id, common::model::EActionType &action) override
Ned3ProEndEffectorDriver<reg_type>::readButton0Status.
Definition: ned3pro_end_effector_driver.hpp:321
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:259
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:351
ttl_driver::Ned3ProEndEffectorDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
Ned3ProEndEffectorDriver<reg_type>::readFirmwareVersion.
Definition: ned3pro_end_effector_driver.hpp:150
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:227
ttl_driver::Ned3ProEndEffectorDriver::readDigitalInput
int readDigitalInput(uint8_t id, bool &in) override
Ned3ProEndEffectorDriver<reg_type>::readDigitalInput.
Definition: ned3pro_end_effector_driver.hpp:446
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:277
ttl_driver::Ned3ProEndEffectorDriver::readAccelerometerXValue
int readAccelerometerXValue(uint8_t id, uint32_t &x_value) override
Ned3ProEndEffectorDriver<reg_type>::readAccelerometerXValue.
Definition: ned3pro_end_effector_driver.hpp:391
ttl_driver::Ned3ProEndEffectorDriver::str
std::string str() const override
Ned3ProEndEffectorDriver<reg_type>::str.
Definition: ned3pro_end_effector_driver.hpp:116
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:208


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