ned3pro_stepper_driver.hpp
Go to the documentation of this file.
1 /*
2 ned3pro_stepper_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_STEPPER_DRIVER_HPP
18 #define NED3PRO_STEPPER_DRIVER_HPP
19 
20 #include <memory>
21 #include <vector>
22 #include <string>
23 #include <iostream>
24 #include <sstream>
25 
26 #include <ros/duration.h>
27 #include <ros/console.h>
28 
30 
31 #include "ned3pro_stepper_reg.hpp"
32 
33 namespace ttl_driver
34 {
35 
39  template <typename reg_type = Ned3ProStepperReg>
41  {
42  public:
43  Ned3ProStepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
44  std::shared_ptr<dynamixel::PacketHandler> packetHandler);
45 
46  public:
47  // AbstractTtlDriver interface
48  std::string str() const override;
49 
50  int checkModelNumber(uint8_t id, uint16_t& model_number) override;
51  int readFirmwareVersion(uint8_t id, std::string &version) override;
52 
53  int readTemperature(uint8_t id, uint8_t &temperature) override;
54  int readVoltage(uint8_t id, double &voltage) override;
55  int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override;
56 
57  int syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list) override;
58  int syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list) override;
59  int syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
60  int syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
61  int syncReadHwStatus(const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list) override;
62 
63  int syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list) override;
64 
65  public:
66  // AbstractMotorDriver interface : we cannot define them globally in AbstractMotorDriver
67  // as it is needed here for polymorphism (AbstractMotorDriver cannot be a template class and does not
68  // have access to reg_type). So it seems like a duplicate of DxlDriver
69 
70  int changeId(uint8_t id, uint8_t new_id) override;
71 
72  int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override;
73  int writePositionGoal(uint8_t id, uint32_t position) override;
74  int writeVelocityGoal(uint8_t id, uint32_t velocity) override;
75 
76  int syncWriteTorquePercentage(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &torque_percentage_list) override;
77  int syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list) override;
78  int syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list) override;
79 
80  // ram read
81  int readPosition(uint8_t id, uint32_t &present_position) override;
82  int readVelocity(uint8_t id, uint32_t &present_velocity) override;
83 
84  int syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list) override;
85  int syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list) override;
86  int syncReadJointStatus(const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2>> &data_array_list) override;
87 
88  // AbstractStepperDriver interface
89  public:
90  common::model::EStepperCalibrationStatus interpretHomingData(uint8_t status) const override;
91 
92  int writeControlMode(uint8_t id, uint8_t operating_mode) override;
93  int writeVelocityProfile(uint8_t id, const uint32_t &velocity_profile);
94  int writeAccelerationProfile(uint8_t id, const uint32_t &acceleration_profile);
95 
96  int factoryCalibration(const uint8_t id, const uint32_t &control);
97  int readStatus(uint8_t id, const uint32_t &status);
98  int readEncAngle(uint8_t id, const uint32_t &enc_angle);
99 
100  int readFirmwareRunning(uint8_t id, bool &is_running) override;
101 
102  // unused inherited methods
103  int readMinPosition(uint8_t id, uint32_t &min_pos) override;
104  int readMaxPosition(uint8_t id, uint32_t &max_pos) override;
105 
106  int readControlMode(uint8_t id, uint8_t &operating_mode) override;
107  int readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list) override;
108  int writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list) override;
109 
110  // ram write
111  int startHoming(uint8_t id);
112  int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold);
113 
114  // read
115  int readHomingStatus(uint8_t id, uint8_t &status);
116  int syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list);
117  int syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position);
118  int syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position);
119 
120  // parameters
121  float velocityUnit() const override;
122  };
123 
124  // definition of methods
125 
129  template <typename reg_type>
130  Ned3ProStepperDriver<reg_type>::Ned3ProStepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
131  std::shared_ptr<dynamixel::PacketHandler> packetHandler) : AbstractStepperDriver(std::move(portHandler),
132  std::move(packetHandler))
133  {
134  }
135 
136  //*****************************
137  // AbstractMotorDriver interface
138  //*****************************
139 
144  template <typename reg_type>
146  {
147  return common::model::HardwareTypeEnum(reg_type::motor_type).toString() + " : " + AbstractStepperDriver::str();
148  }
149 
156  template <typename reg_type>
157  int Ned3ProStepperDriver<reg_type>::changeId(uint8_t id, uint8_t new_id)
158  {
159  // TODO(THUC) verify that COMM_RX_TIMEOUT error code do not impact on data sent to motor
160  // when COMM_RX_TIMEOUT error, id changed also, so we consider that change id successfully
161  int res = write<typename reg_type::TYPE_ID>(reg_type::ADDR_ID, id, new_id);
162  if (res == COMM_RX_TIMEOUT)
163  res = COMM_SUCCESS;
164  return res;
165  }
166 
176  template <typename reg_type>
177  int Ned3ProStepperDriver<reg_type>::checkModelNumber(uint8_t id, uint16_t& model_number)
178  {
179  int ping_result = getModelNumber(id, model_number);
180 
181  if (ping_result == COMM_SUCCESS)
182  {
183  // Use the validator from register definition to check compatibility
184  auto validator = reg_type::createModelNumberValidator();
185  if (!validator->isValid(model_number))
186  {
187  ROS_WARN("Ned3ProStepperDriver: Model number %u not valid for %s (expected %s)",
188  model_number,
189  common::model::HardwareTypeEnum(reg_type::motor_type).toString().c_str(),
190  validator->describe().c_str());
191  return PING_WRONG_MODEL_NUMBER;
192  }
193  }
194 
195  return ping_result;
196  }
197 
204  template <typename reg_type>
205  int Ned3ProStepperDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
206  {
207  int res = 0;
208  uint32_t data{};
209  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
210  version = interpretFirmwareVersion(data);
211  return res;
212  }
213 
214  // ram write
215 
222  template <typename reg_type>
223  int Ned3ProStepperDriver<reg_type>::writeTorquePercentage(uint8_t id, uint8_t torque_percentage)
224  {
225  return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id, torque_percentage);
226  }
227 
234  template <typename reg_type>
235  int Ned3ProStepperDriver<reg_type>::writePositionGoal(uint8_t id, uint32_t position)
236  {
237  return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id, position);
238  }
239 
240  // according to the registers, the data should be an int32_t ?
247  template <typename reg_type>
248  int Ned3ProStepperDriver<reg_type>::writeVelocityGoal(uint8_t id, uint32_t velocity)
249  {
250  return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id, velocity);
251  }
252 
259  template <typename reg_type>
260  int Ned3ProStepperDriver<reg_type>::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &torque_percentage_list)
261  {
262  return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list, torque_percentage_list);
263  }
264 
271  template <typename reg_type>
272  int Ned3ProStepperDriver<reg_type>::syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list)
273  {
274  return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
275  }
276 
283  template <typename reg_type>
284  int Ned3ProStepperDriver<reg_type>::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list)
285  {
286  return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
287  }
288 
289  // ram read
290 
297  template <typename reg_type>
298  int Ned3ProStepperDriver<reg_type>::readPosition(uint8_t id, uint32_t &present_position)
299  {
300  return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id, present_position);
301  }
302 
309  template <typename reg_type>
310  int Ned3ProStepperDriver<reg_type>::readVelocity(uint8_t id, uint32_t &present_velocity)
311  {
312  return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id, present_velocity);
313  }
314 
321  template <typename reg_type>
322  int Ned3ProStepperDriver<reg_type>::readTemperature(uint8_t id, uint8_t &temperature)
323  {
324  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
325  }
326 
333  template <typename reg_type>
334  int Ned3ProStepperDriver<reg_type>::readVoltage(uint8_t id, double &voltage)
335  {
336  uint16_t voltage_mV = 0;
337  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
338  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
339  return res;
340  }
341 
348  template <typename reg_type>
349  int Ned3ProStepperDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
350  {
351  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
352  }
353 
360  template <typename reg_type>
361  int Ned3ProStepperDriver<reg_type>::syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
362  {
363  return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
364  }
365 
372  template <typename reg_type>
373  int Ned3ProStepperDriver<reg_type>::syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
374  {
375  return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
376  }
377 
385  template <typename reg_type>
386  int Ned3ProStepperDriver<reg_type>::syncReadJointStatus(const std::vector<uint8_t> &id_list,
387  std::vector<std::array<uint32_t, 2>> &data_array_list)
388  {
389  int res = COMM_TX_FAIL;
390 
391  if (id_list.empty())
392  return res;
393 
394  data_array_list.clear();
395 
396  // read torque enable on first id
397  typename reg_type::TYPE_TORQUE_ENABLE torque{1};
398  res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
399  if (COMM_SUCCESS != res)
400  std::cout << "#############"
401  " ERROR reading stepper torque in syncReadJointStatus (error "
402  << res << ")" << std::endl;
403 
404  // if torque on, read position and velocity
405  if (torque)
406  {
407  res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
408  }
409  else // else read position only
410  {
411  std::vector<uint32_t> position_list;
412  res = syncReadPosition(id_list, position_list);
413  for (auto p : position_list)
414  data_array_list.emplace_back(std::array<uint32_t, 2>{1, p});
415  }
416 
417  return res;
418  }
419 
426  template <typename reg_type>
427  int Ned3ProStepperDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
428  {
429  int res = 0;
430  firmware_list.clear();
431  std::vector<uint32_t> data_list{};
432  res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
433  for (auto const &data : data_list)
434  firmware_list.emplace_back(interpretFirmwareVersion(data));
435  return res;
436  }
437 
444  template <typename reg_type>
445  int Ned3ProStepperDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
446  {
447  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
448  }
449 
456  template <typename reg_type>
457  int Ned3ProStepperDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
458  {
459  voltage_list.clear();
460  std::vector<uint16_t> v_read;
461  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
462  for (auto const &v : v_read)
463  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
464  return res;
465  }
466 
473  template <typename reg_type>
474  int Ned3ProStepperDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
475  {
476  voltage_list.clear();
477  std::vector<uint16_t> v_read;
478  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
479  for (auto const &v : v_read)
480  voltage_list.emplace_back(static_cast<double>(v));
481  return res;
482  }
483 
490  template <typename reg_type>
491  int Ned3ProStepperDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
492  std::vector<std::pair<double, uint8_t>> &data_list)
493  {
494  data_list.clear();
495 
496  std::vector<std::array<uint8_t, 3>> raw_data;
497  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
498 
499  for (auto const &data : raw_data)
500  {
501  // Voltage is first reg, uint16
502  auto v = static_cast<uint16_t>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0)); // concatenate 2 bytes
503  auto voltage = static_cast<double>(v);
504 
505  // Temperature is second reg, uint8
506  uint8_t temperature = data.at(2);
507 
508  data_list.emplace_back(std::make_pair(voltage, temperature));
509  }
510 
511  return res;
512  }
519  template <typename reg_type>
520  int Ned3ProStepperDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
521  {
522  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
523  }
524 
525  //*****************************
526  // AbstractStepperDriver interface
527  //*****************************
528 
534  template <typename reg_type>
535  common::model::EStepperCalibrationStatus Ned3ProStepperDriver<reg_type>::interpretHomingData(uint8_t status) const
536  {
537  enum Ned3ProStepperCalibrationStatus {
538  UNINITIALIZED_MASK = 0,
539  IN_PROGRESS_MASK = 2,
540  OK_MASK = 4,
541  FAIL_MASK = 8
542  };
543 
544  return status & IN_PROGRESS_MASK ? common::model::EStepperCalibrationStatus::IN_PROGRESS
545  : status & FAIL_MASK ? common::model::EStepperCalibrationStatus::FAIL
546  : status & OK_MASK ? common::model::EStepperCalibrationStatus::OK
547  : common::model::EStepperCalibrationStatus::FAIL;
548  }
549 
556  template <typename reg_type>
557  int Ned3ProStepperDriver<reg_type>::writeControlMode(uint8_t id, uint8_t operating_mode)
558  {
559  return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE, id, operating_mode);
560  }
561 
568  template <typename reg_type>
569  int Ned3ProStepperDriver<reg_type>::writeVelocityProfile(uint8_t id, const uint32_t &velocity_profile)
570  {
571  return write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY, id, velocity_profile);
572  }
573 
580  template <typename reg_type>
581  int Ned3ProStepperDriver<reg_type>::writeAccelerationProfile(uint8_t id, const uint32_t &acceleration_profile)
582  {
583  return write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION, id, acceleration_profile);
584  }
585 
592  template <typename reg_type>
593  int Ned3ProStepperDriver<reg_type>::factoryCalibration(const uint8_t id, const uint32_t &command)
594  {
595  return write<typename reg_type::TYPE_CONTROL>(reg_type::ADDR_CONTROL, id, command);
596  }
597 
604  template <typename reg_type>
605  int Ned3ProStepperDriver<reg_type>::readStatus(uint8_t id, const uint32_t &status)
606  {
607  return read<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id, status);
608  }
609 
610  template <typename reg_type>
611  int Ned3ProStepperDriver<reg_type>::syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list)
612  {
613  std::vector<uint32_t> status_list_tmp;
614  auto result = syncRead<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id_list, status_list_tmp);
615  for (const auto &status_tmp : status_list_tmp)
616  status_list.push_back(static_cast<uint8_t>(status_tmp));
617 
618  return result;
619  };
620 
627  template <typename reg_type>
628  int Ned3ProStepperDriver<reg_type>::readEncAngle(uint8_t id, const uint32_t &enc_angle)
629  {
630  return read<typename reg_type::TYPE_ENC_ANGLE>(reg_type::ADDR_ENC_ANGLE, id, enc_angle);
631  }
632 
639  template <typename reg_type>
640  int Ned3ProStepperDriver<reg_type>::readFirmwareRunning(uint8_t id, bool &is_running)
641  {
642  typename reg_type::TYPE_FIRMWARE_RUNNING data{};
643  int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING, id, data);
644  is_running = data;
645  return res;
646  }
647 
648  // unused inherited methods
649  template <typename reg_type>
650  int Ned3ProStepperDriver<reg_type>::readMinPosition(uint8_t id, uint32_t &min_pos)
651  {
652  ROS_WARN("Ned3ProStepperDriver::readMinPosition - Not implemented");
653 
654  return COMM_NOT_AVAILABLE;
655  };
656 
657  template <typename reg_type>
658  int Ned3ProStepperDriver<reg_type>::readMaxPosition(uint8_t id, uint32_t &max_pos)
659  {
660  ROS_WARN("Ned3ProStepperDriver::readMaxPosition - Not implemented");
661 
662  return COMM_NOT_AVAILABLE;
663  };
664 
665  template <typename reg_type>
666  int Ned3ProStepperDriver<reg_type>::readControlMode(uint8_t id, uint8_t &mode)
667  {
668  ROS_WARN("Ned3ProStepperDriver::readControlMode - Not implemented");
669 
670  return COMM_NOT_AVAILABLE;
671  };
672 
673  template <typename reg_type>
674  int Ned3ProStepperDriver<reg_type>::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list)
675  {
676  ROS_WARN("Ned3ProStepperDriver::readVelocityProfile std::vector<uint32_t> &data_list - Not implemented");
677 
678  return COMM_NOT_AVAILABLE;
679  };
680 
681  template <typename reg_type>
682  int Ned3ProStepperDriver<reg_type>::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list)
683  {
684  int tries = 10;
685  int res = COMM_RX_FAIL;
686  double wait_duration = 0.05;
687 
688  // Random positive value to activate the torque, we need this to write on other registers
689  constexpr auto ACTIVE_TORQUE_PERCENT = 40;
690  writeTorquePercentage(id, ACTIVE_TORQUE_PERCENT);
691 
692  tries = 10;
693  while (tries > 0) // try 10 times
694  {
695  tries--;
696  ros::Duration(wait_duration).sleep();
697  res = write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY, id, data_list.at(4));
698  if (res == COMM_SUCCESS)
699  break;
700  }
701  if (res != COMM_SUCCESS)
702  return res;
703 
704  tries = 10;
705  while (tries > 0) // try 10 times
706  {
707  tries--;
708  ros::Duration(wait_duration).sleep();
709  res = write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION, id, data_list.at(3));
710  if (res == COMM_SUCCESS)
711  break;
712  }
713 
714  return res;
715  };
716 
717  template <typename reg_type>
719  {
720  ROS_WARN("Ned3ProStepperDriver::startHoming - Not implemented");
721 
722  return COMM_NOT_AVAILABLE;
723  };
724 
725  template <typename reg_type>
726  int Ned3ProStepperDriver<reg_type>::writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)
727  {
728  ROS_WARN("Ned3ProStepperDriver::writeHomingSetup - Not implemented");
729 
730  return COMM_NOT_AVAILABLE;
731  };
732 
733  // read
734  template <typename reg_type>
735  int Ned3ProStepperDriver<reg_type>::readHomingStatus(uint8_t id, uint8_t &status)
736  {
737  ROS_WARN("Ned3ProStepperDriver::readHomingStatus - Not implemented");
738 
739  return COMM_NOT_AVAILABLE;
740  };
741  template <typename reg_type>
742  int Ned3ProStepperDriver<reg_type>::syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position)
743  {
744  ROS_WARN("Ned3ProStepperDriver::syncReadHomingAbsPosition - Not implemented");
745 
746  return COMM_NOT_AVAILABLE;
747  };
748  template <typename reg_type>
749  int Ned3ProStepperDriver<reg_type>::syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position)
750  {
751  ROS_WARN("Ned3ProStepperDriver::syncWriteHomingAbsPosition - Not implemented");
752 
753  return COMM_NOT_AVAILABLE;
754  };
755 
756  template <typename reg_type>
758  {
759  return reg_type::VELOCITY_UNIT;
760  }
761 } // ttl_driver
762 
763 #endif // NED3PRO_STEPPER_DRIVER_HPP
ttl_driver::Ned3ProStepperDriver::Ned3ProStepperDriver
Ned3ProStepperDriver(std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler)
DxlDriver<reg_type>::DxlDriver.
Definition: ned3pro_stepper_driver.hpp:130
ttl_driver::Ned3ProStepperDriver::factoryCalibration
int factoryCalibration(const uint8_t id, const uint32_t &control)
Ned3ProStepperDriver<reg_type>::factoryCalibration.
Definition: ned3pro_stepper_driver.hpp:593
ttl_driver::Ned3ProStepperDriver::syncReadHwErrorStatus
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
Ned3ProStepperDriver<reg_type>::syncReadHwErrorStatus.
Definition: ned3pro_stepper_driver.hpp:520
ttl_driver::AbstractStepperDriver::str
std::string str() const override
AbstractStepperDriver::str.
Definition: abstract_stepper_driver.cpp:48
ttl_driver::Ned3ProStepperDriver::syncReadFirmwareVersion
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
Ned3ProStepperDriver<reg_type>::syncReadFirmwareVersion.
Definition: ned3pro_stepper_driver.hpp:427
ned3pro_stepper_reg.hpp
ttl_driver::Ned3ProStepperDriver::velocityUnit
float velocityUnit() const override
writeVelocityGoal: define the unit of the velocity in RPM
Definition: ned3pro_stepper_driver.hpp:757
ttl_driver::Ned3ProStepperDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
Definition: ned3pro_stepper_driver.hpp:650
ttl_driver::Ned3ProStepperDriver::syncWritePositionGoal
int syncWritePositionGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list) override
Ned3ProStepperDriver<reg_type>::syncWritePositionGoal.
Definition: ned3pro_stepper_driver.hpp:272
ttl_driver::Ned3ProStepperDriver::writeHomingSetup
int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)
Definition: ned3pro_stepper_driver.hpp:726
ttl_driver::Ned3ProStepperDriver::syncReadPosition
int syncReadPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list) override
Ned3ProStepperDriver<reg_type>::syncReadPosition.
Definition: ned3pro_stepper_driver.hpp:361
ttl_driver::Ned3ProStepperDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
Ned3ProStepperDriver<reg_type>::changeId.
Definition: ned3pro_stepper_driver.hpp:157
ttl_driver::Ned3ProStepperDriver::syncWriteHomingAbsPosition
int syncWriteHomingAbsPosition(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position)
Definition: ned3pro_stepper_driver.hpp:749
ttl_driver::Ned3ProStepperDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
Ned3ProStepperDriver<reg_type>::writePositionGoal.
Definition: ned3pro_stepper_driver.hpp:235
ttl_driver::Ned3ProStepperDriver::readFirmwareRunning
int readFirmwareRunning(uint8_t id, bool &is_running) override
Ned3ProStepperDriver<reg_type>::readFirmwareRunning.
Definition: ned3pro_stepper_driver.hpp:640
ttl_driver::Ned3ProStepperDriver::syncWriteVelocityGoal
int syncWriteVelocityGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list) override
Ned3ProStepperDriver<reg_type>::syncWriteVelocityGoal.
Definition: ned3pro_stepper_driver.hpp:284
ttl_driver::Ned3ProStepperDriver::syncReadTemperature
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
Ned3ProStepperDriver<reg_type>::syncReadTemperature.
Definition: ned3pro_stepper_driver.hpp:445
ttl_driver::Ned3ProStepperDriver
The Ned3ProStepperDriver class.
Definition: ned3pro_stepper_driver.hpp:40
ttl_driver::Ned3ProStepperDriver::syncReadHwStatus
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t >> &data_list) override
Ned3ProStepperDriver<reg_type>::syncReadHwStatus.
Definition: ned3pro_stepper_driver.hpp:491
ttl_driver::Ned3ProStepperDriver::syncWriteTorquePercentage
int syncWriteTorquePercentage(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list) override
Ned3ProStepperDriver<reg_type>::syncWriteTorquePercentage.
Definition: ned3pro_stepper_driver.hpp:260
ttl_driver::Ned3ProStepperDriver::syncReadJointStatus
int syncReadJointStatus(const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 >> &data_array_list) override
Ned3ProStepperDriver<reg_type>::syncReadJointStatus.
Definition: ned3pro_stepper_driver.hpp:386
ttl_driver::Ned3ProStepperDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t operating_mode) override
Ned3ProStepperDriver<reg_type>::writeOperatingMode.
Definition: ned3pro_stepper_driver.hpp:557
abstract_stepper_driver.hpp
ttl_driver::Ned3ProStepperDriver::writeAccelerationProfile
int writeAccelerationProfile(uint8_t id, const uint32_t &acceleration_profile)
Ned3ProStepperDriver<reg_type>::writeAccelerationProfile.
Definition: ned3pro_stepper_driver.hpp:581
ttl_driver::Ned3ProStepperDriver::syncReadHomingAbsPosition
int syncReadHomingAbsPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position)
Definition: ned3pro_stepper_driver.hpp:742
ttl_driver::Ned3ProStepperDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
Definition: ned3pro_stepper_driver.hpp:658
ttl_driver::Ned3ProStepperDriver::syncReadRawVoltage
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
Ned3ProStepperDriver<reg_type>::syncReadRawVoltage.
Definition: ned3pro_stepper_driver.hpp:474
ttl_driver::Ned3ProStepperDriver::readStatus
int readStatus(uint8_t id, const uint32_t &status)
Ned3ProStepperDriver<reg_type>::readStatus.
Definition: ned3pro_stepper_driver.hpp:605
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::Ned3ProStepperDriver::interpretHomingData
common::model::EStepperCalibrationStatus interpretHomingData(uint8_t status) const override
AbstractStepperDriver::interpretHomingData.
Definition: ned3pro_stepper_driver.hpp:535
ttl_driver::Ned3ProStepperDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
Ned3ProStepperDriver<reg_type>::checkModelNumber.
Definition: ned3pro_stepper_driver.hpp:177
ttl_driver::Ned3ProStepperDriver::syncReadHomingStatus
int syncReadHomingStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list)
Definition: ned3pro_stepper_driver.hpp:611
ttl_driver::Ned3ProStepperDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &operating_mode) override
Definition: ned3pro_stepper_driver.hpp:666
ttl_driver::Ned3ProStepperDriver::str
std::string str() const override
Ned3ProStepperDriver<reg_type>::str.
Definition: ned3pro_stepper_driver.hpp:145
ttl_driver::Ned3ProStepperDriver::writeVelocityProfile
int writeVelocityProfile(uint8_t id, const uint32_t &velocity_profile)
Ned3ProStepperDriver<reg_type>::writeVelocityProfile.
Definition: ned3pro_stepper_driver.hpp:569
ttl_driver::Ned3ProStepperDriver::readHomingStatus
int readHomingStatus(uint8_t id, uint8_t &status)
Definition: ned3pro_stepper_driver.hpp:735
ttl_driver::AbstractStepperDriver
Definition: abstract_stepper_driver.hpp:34
ttl_driver::Ned3ProStepperDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
Definition: ned3pro_stepper_driver.hpp:674
ttl_driver::Ned3ProStepperDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
Ned3ProStepperDriver<reg_type>::readHwErrorStatus.
Definition: ned3pro_stepper_driver.hpp:349
ttl_driver::Ned3ProStepperDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
Ned3ProStepperDriver<reg_type>::writeTorquePercentage.
Definition: ned3pro_stepper_driver.hpp:223
ttl_driver::Ned3ProStepperDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
Ned3ProStepperDriver<reg_type>::readVelocity.
Definition: ned3pro_stepper_driver.hpp:310
ttl_driver::Ned3ProStepperDriver::syncReadVoltage
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
Ned3ProStepperDriver<reg_type>::syncReadVoltage.
Definition: ned3pro_stepper_driver.hpp:457
ttl_driver::Ned3ProStepperDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
Ned3ProStepperDriver<reg_type>::readVoltage.
Definition: ned3pro_stepper_driver.hpp:334
ttl_driver::Ned3ProStepperDriver::startHoming
int startHoming(uint8_t id)
Definition: ned3pro_stepper_driver.hpp:718
ttl_driver::Ned3ProStepperDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
Ned3ProStepperDriver<reg_type>::readTemperature.
Definition: ned3pro_stepper_driver.hpp:322
ttl_driver::Ned3ProStepperDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
Ned3ProStepperDriver<reg_type>::readPosition.
Definition: ned3pro_stepper_driver.hpp:298
ttl_driver::Ned3ProStepperDriver::syncReadVelocity
int syncReadVelocity(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list) override
Ned3ProStepperDriver<reg_type>::syncReadVelocity.
Definition: ned3pro_stepper_driver.hpp:373
ttl_driver::Ned3ProStepperDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
Ned3ProStepperDriver<reg_type>::readFirmwareVersion.
Definition: ned3pro_stepper_driver.hpp:205
ttl_driver::Ned3ProStepperDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
Ned3ProStepperDriver<reg_type>::writeVelocityGoal.
Definition: ned3pro_stepper_driver.hpp:248
ttl_driver::Ned3ProStepperDriver::readEncAngle
int readEncAngle(uint8_t id, const uint32_t &enc_angle)
Ned3ProStepperDriver<reg_type>::readEncAngle.
Definition: ned3pro_stepper_driver.hpp:628


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Tue Jan 13 2026 12:43:08