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) 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 
172  template <typename reg_type>
174  {
175  uint16_t model_number = 0;
176  int ping_result = getModelNumber(id, model_number);
177 
178  if (ping_result == COMM_SUCCESS)
179  {
180  if (model_number && model_number != reg_type::MODEL_NUMBER)
181  {
182  return PING_WRONG_MODEL_NUMBER;
183  }
184  }
185 
186  return ping_result;
187  }
188 
195  template <typename reg_type>
196  int Ned3ProStepperDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
197  {
198  int res = 0;
199  uint32_t data{};
200  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
201  version = interpretFirmwareVersion(data);
202  return res;
203  }
204 
205  // ram write
206 
213  template <typename reg_type>
214  int Ned3ProStepperDriver<reg_type>::writeTorquePercentage(uint8_t id, uint8_t torque_percentage)
215  {
216  return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id, torque_percentage);
217  }
218 
225  template <typename reg_type>
226  int Ned3ProStepperDriver<reg_type>::writePositionGoal(uint8_t id, uint32_t position)
227  {
228  return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id, position);
229  }
230 
231  // according to the registers, the data should be an int32_t ?
238  template <typename reg_type>
239  int Ned3ProStepperDriver<reg_type>::writeVelocityGoal(uint8_t id, uint32_t velocity)
240  {
241  return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id, velocity);
242  }
243 
250  template <typename reg_type>
251  int Ned3ProStepperDriver<reg_type>::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &torque_percentage_list)
252  {
253  return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list, torque_percentage_list);
254  }
255 
262  template <typename reg_type>
263  int Ned3ProStepperDriver<reg_type>::syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list)
264  {
265  return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
266  }
267 
274  template <typename reg_type>
275  int Ned3ProStepperDriver<reg_type>::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list)
276  {
277  return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
278  }
279 
280  // ram read
281 
288  template <typename reg_type>
289  int Ned3ProStepperDriver<reg_type>::readPosition(uint8_t id, uint32_t &present_position)
290  {
291  return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id, present_position);
292  }
293 
300  template <typename reg_type>
301  int Ned3ProStepperDriver<reg_type>::readVelocity(uint8_t id, uint32_t &present_velocity)
302  {
303  return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id, present_velocity);
304  }
305 
312  template <typename reg_type>
313  int Ned3ProStepperDriver<reg_type>::readTemperature(uint8_t id, uint8_t &temperature)
314  {
315  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
316  }
317 
324  template <typename reg_type>
325  int Ned3ProStepperDriver<reg_type>::readVoltage(uint8_t id, double &voltage)
326  {
327  uint16_t voltage_mV = 0;
328  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
329  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
330  return res;
331  }
332 
339  template <typename reg_type>
340  int Ned3ProStepperDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
341  {
342  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
343  }
344 
351  template <typename reg_type>
352  int Ned3ProStepperDriver<reg_type>::syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
353  {
354  return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
355  }
356 
363  template <typename reg_type>
364  int Ned3ProStepperDriver<reg_type>::syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
365  {
366  return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
367  }
368 
376  template <typename reg_type>
377  int Ned3ProStepperDriver<reg_type>::syncReadJointStatus(const std::vector<uint8_t> &id_list,
378  std::vector<std::array<uint32_t, 2>> &data_array_list)
379  {
380  int res = COMM_TX_FAIL;
381 
382  if (id_list.empty())
383  return res;
384 
385  data_array_list.clear();
386 
387  // read torque enable on first id
388  typename reg_type::TYPE_TORQUE_ENABLE torque{1};
389  res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
390  if (COMM_SUCCESS != res)
391  std::cout << "#############"
392  " ERROR reading stepper torque in syncReadJointStatus (error "
393  << res << ")" << std::endl;
394 
395  // if torque on, read position and velocity
396  if (torque)
397  {
398  res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
399  }
400  else // else read position only
401  {
402  std::vector<uint32_t> position_list;
403  res = syncReadPosition(id_list, position_list);
404  for (auto p : position_list)
405  data_array_list.emplace_back(std::array<uint32_t, 2>{1, p});
406  }
407 
408  return res;
409  }
410 
417  template <typename reg_type>
418  int Ned3ProStepperDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
419  {
420  int res = 0;
421  firmware_list.clear();
422  std::vector<uint32_t> data_list{};
423  res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
424  for (auto const &data : data_list)
425  firmware_list.emplace_back(interpretFirmwareVersion(data));
426  return res;
427  }
428 
435  template <typename reg_type>
436  int Ned3ProStepperDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
437  {
438  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
439  }
440 
447  template <typename reg_type>
448  int Ned3ProStepperDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
449  {
450  voltage_list.clear();
451  std::vector<uint16_t> v_read;
452  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
453  for (auto const &v : v_read)
454  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
455  return res;
456  }
457 
464  template <typename reg_type>
465  int Ned3ProStepperDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
466  {
467  voltage_list.clear();
468  std::vector<uint16_t> v_read;
469  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
470  for (auto const &v : v_read)
471  voltage_list.emplace_back(static_cast<double>(v));
472  return res;
473  }
474 
481  template <typename reg_type>
482  int Ned3ProStepperDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
483  std::vector<std::pair<double, uint8_t>> &data_list)
484  {
485  data_list.clear();
486 
487  std::vector<std::array<uint8_t, 3>> raw_data;
488  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
489 
490  for (auto const &data : raw_data)
491  {
492  // Voltage is first reg, uint16
493  auto v = static_cast<uint16_t>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0)); // concatenate 2 bytes
494  auto voltage = static_cast<double>(v);
495 
496  // Temperature is second reg, uint8
497  uint8_t temperature = data.at(2);
498 
499  data_list.emplace_back(std::make_pair(voltage, temperature));
500  }
501 
502  return res;
503  }
510  template <typename reg_type>
511  int Ned3ProStepperDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
512  {
513  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
514  }
515 
516  //*****************************
517  // AbstractStepperDriver interface
518  //*****************************
519 
525  template <typename reg_type>
526  common::model::EStepperCalibrationStatus Ned3ProStepperDriver<reg_type>::interpretHomingData(uint8_t status) const
527  {
528  enum Ned3ProStepperCalibrationStatus {
529  UNINITIALIZED_MASK = 0,
530  IN_PROGRESS_MASK = 2,
531  OK_MASK = 4,
532  FAIL_MASK = 8
533  };
534 
535  return status & IN_PROGRESS_MASK ? common::model::EStepperCalibrationStatus::IN_PROGRESS
536  : status & FAIL_MASK ? common::model::EStepperCalibrationStatus::FAIL
537  : status & OK_MASK ? common::model::EStepperCalibrationStatus::OK
538  : common::model::EStepperCalibrationStatus::FAIL;
539  }
540 
547  template <typename reg_type>
548  int Ned3ProStepperDriver<reg_type>::writeControlMode(uint8_t id, uint8_t operating_mode)
549  {
550  return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE, id, operating_mode);
551  }
552 
559  template <typename reg_type>
560  int Ned3ProStepperDriver<reg_type>::writeVelocityProfile(uint8_t id, const uint32_t &velocity_profile)
561  {
562  return write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY, id, velocity_profile);
563  }
564 
571  template <typename reg_type>
572  int Ned3ProStepperDriver<reg_type>::writeAccelerationProfile(uint8_t id, const uint32_t &acceleration_profile)
573  {
574  return write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION, id, acceleration_profile);
575  }
576 
583  template <typename reg_type>
584  int Ned3ProStepperDriver<reg_type>::factoryCalibration(const uint8_t id, const uint32_t &command)
585  {
586  return write<typename reg_type::TYPE_CONTROL>(reg_type::ADDR_CONTROL, id, command);
587  }
588 
595  template <typename reg_type>
596  int Ned3ProStepperDriver<reg_type>::readStatus(uint8_t id, const uint32_t &status)
597  {
598  return read<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id, status);
599  }
600 
601  template <typename reg_type>
602  int Ned3ProStepperDriver<reg_type>::syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list)
603  {
604  std::vector<uint32_t> status_list_tmp;
605  auto result = syncRead<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id_list, status_list_tmp);
606  for (const auto &status_tmp : status_list_tmp)
607  status_list.push_back(static_cast<uint8_t>(status_tmp));
608 
609  return result;
610  };
611 
618  template <typename reg_type>
619  int Ned3ProStepperDriver<reg_type>::readEncAngle(uint8_t id, const uint32_t &enc_angle)
620  {
621  return read<typename reg_type::TYPE_ENC_ANGLE>(reg_type::ADDR_ENC_ANGLE, id, enc_angle);
622  }
623 
630  template <typename reg_type>
631  int Ned3ProStepperDriver<reg_type>::readFirmwareRunning(uint8_t id, bool &is_running)
632  {
633  typename reg_type::TYPE_FIRMWARE_RUNNING data{};
634  int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING, id, data);
635  is_running = data;
636  return res;
637  }
638 
639  // unused inherited methods
640  template <typename reg_type>
641  int Ned3ProStepperDriver<reg_type>::readMinPosition(uint8_t id, uint32_t &min_pos)
642  {
643  ROS_WARN("Ned3ProStepperDriver::readMinPosition - Not implemented");
644 
645  return COMM_NOT_AVAILABLE;
646  };
647 
648  template <typename reg_type>
649  int Ned3ProStepperDriver<reg_type>::readMaxPosition(uint8_t id, uint32_t &max_pos)
650  {
651  ROS_WARN("Ned3ProStepperDriver::readMaxPosition - Not implemented");
652 
653  return COMM_NOT_AVAILABLE;
654  };
655 
656  template <typename reg_type>
657  int Ned3ProStepperDriver<reg_type>::readControlMode(uint8_t id, uint8_t &mode)
658  {
659  ROS_WARN("Ned3ProStepperDriver::readControlMode - Not implemented");
660 
661  return COMM_NOT_AVAILABLE;
662  };
663 
664  template <typename reg_type>
665  int Ned3ProStepperDriver<reg_type>::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list)
666  {
667  ROS_WARN("Ned3ProStepperDriver::readVelocityProfile std::vector<uint32_t> &data_list - Not implemented");
668 
669  return COMM_NOT_AVAILABLE;
670  };
671 
672  template <typename reg_type>
673  int Ned3ProStepperDriver<reg_type>::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list)
674  {
675  int tries = 10;
676  int res = COMM_RX_FAIL;
677  double wait_duration = 0.05;
678 
679  // Random positive value to activate the torque, we need this to write on other registers
680  constexpr auto ACTIVE_TORQUE_PERCENT = 40;
681  writeTorquePercentage(id, ACTIVE_TORQUE_PERCENT);
682 
683  tries = 10;
684  while (tries > 0) // try 10 times
685  {
686  tries--;
687  ros::Duration(wait_duration).sleep();
688  res = write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY, id, data_list.at(4));
689  if (res == COMM_SUCCESS)
690  break;
691  }
692  if (res != COMM_SUCCESS)
693  return res;
694 
695  tries = 10;
696  while (tries > 0) // try 10 times
697  {
698  tries--;
699  ros::Duration(wait_duration).sleep();
700  res = write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION, id, data_list.at(3));
701  if (res == COMM_SUCCESS)
702  break;
703  }
704 
705  return res;
706  };
707 
708  template <typename reg_type>
710  {
711  ROS_WARN("Ned3ProStepperDriver::startHoming - Not implemented");
712 
713  return COMM_NOT_AVAILABLE;
714  };
715 
716  template <typename reg_type>
717  int Ned3ProStepperDriver<reg_type>::writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)
718  {
719  ROS_WARN("Ned3ProStepperDriver::writeHomingSetup - Not implemented");
720 
721  return COMM_NOT_AVAILABLE;
722  };
723 
724  // read
725  template <typename reg_type>
726  int Ned3ProStepperDriver<reg_type>::readHomingStatus(uint8_t id, uint8_t &status)
727  {
728  ROS_WARN("Ned3ProStepperDriver::readHomingStatus - Not implemented");
729 
730  return COMM_NOT_AVAILABLE;
731  };
732  template <typename reg_type>
733  int Ned3ProStepperDriver<reg_type>::syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position)
734  {
735  ROS_WARN("Ned3ProStepperDriver::syncReadHomingAbsPosition - Not implemented");
736 
737  return COMM_NOT_AVAILABLE;
738  };
739  template <typename reg_type>
740  int Ned3ProStepperDriver<reg_type>::syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position)
741  {
742  ROS_WARN("Ned3ProStepperDriver::syncWriteHomingAbsPosition - Not implemented");
743 
744  return COMM_NOT_AVAILABLE;
745  };
746 
747  template <typename reg_type>
749  {
750  return reg_type::VELOCITY_UNIT;
751  }
752 } // ttl_driver
753 
754 #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:584
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:511
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:418
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:748
ttl_driver::Ned3ProStepperDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
Definition: ned3pro_stepper_driver.hpp:641
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:263
ttl_driver::Ned3ProStepperDriver::writeHomingSetup
int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)
Definition: ned3pro_stepper_driver.hpp:717
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:352
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:740
ttl_driver::Ned3ProStepperDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
Ned3ProStepperDriver<reg_type>::writePositionGoal.
Definition: ned3pro_stepper_driver.hpp:226
ttl_driver::Ned3ProStepperDriver::readFirmwareRunning
int readFirmwareRunning(uint8_t id, bool &is_running) override
Ned3ProStepperDriver<reg_type>::readFirmwareRunning.
Definition: ned3pro_stepper_driver.hpp:631
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:275
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:436
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:482
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:251
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:377
ttl_driver::Ned3ProStepperDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t operating_mode) override
Ned3ProStepperDriver<reg_type>::writeOperatingMode.
Definition: ned3pro_stepper_driver.hpp:548
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:572
ttl_driver::Ned3ProStepperDriver::syncReadHomingAbsPosition
int syncReadHomingAbsPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position)
Definition: ned3pro_stepper_driver.hpp:733
ttl_driver::Ned3ProStepperDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
Definition: ned3pro_stepper_driver.hpp:649
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:465
ttl_driver::Ned3ProStepperDriver::readStatus
int readStatus(uint8_t id, const uint32_t &status)
Ned3ProStepperDriver<reg_type>::readStatus.
Definition: ned3pro_stepper_driver.hpp:596
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:526
ttl_driver::Ned3ProStepperDriver::syncReadHomingStatus
int syncReadHomingStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list)
Definition: ned3pro_stepper_driver.hpp:602
ttl_driver::Ned3ProStepperDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &operating_mode) override
Definition: ned3pro_stepper_driver.hpp:657
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:560
ttl_driver::Ned3ProStepperDriver::readHomingStatus
int readHomingStatus(uint8_t id, uint8_t &status)
Definition: ned3pro_stepper_driver.hpp:726
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:665
ttl_driver::Ned3ProStepperDriver::checkModelNumber
int checkModelNumber(uint8_t id) override
Ned3ProStepperDriver<reg_type>::checkModelNumber.
Definition: ned3pro_stepper_driver.hpp:173
ttl_driver::Ned3ProStepperDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
Ned3ProStepperDriver<reg_type>::readHwErrorStatus.
Definition: ned3pro_stepper_driver.hpp:340
ttl_driver::Ned3ProStepperDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
Ned3ProStepperDriver<reg_type>::writeTorquePercentage.
Definition: ned3pro_stepper_driver.hpp:214
ttl_driver::Ned3ProStepperDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
Ned3ProStepperDriver<reg_type>::readVelocity.
Definition: ned3pro_stepper_driver.hpp:301
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:448
ttl_driver::Ned3ProStepperDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
Ned3ProStepperDriver<reg_type>::readVoltage.
Definition: ned3pro_stepper_driver.hpp:325
ttl_driver::Ned3ProStepperDriver::startHoming
int startHoming(uint8_t id)
Definition: ned3pro_stepper_driver.hpp:709
ttl_driver::Ned3ProStepperDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
Ned3ProStepperDriver<reg_type>::readTemperature.
Definition: ned3pro_stepper_driver.hpp:313
ttl_driver::Ned3ProStepperDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
Ned3ProStepperDriver<reg_type>::readPosition.
Definition: ned3pro_stepper_driver.hpp:289
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:364
ttl_driver::Ned3ProStepperDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
Ned3ProStepperDriver<reg_type>::readFirmwareVersion.
Definition: ned3pro_stepper_driver.hpp:196
ttl_driver::Ned3ProStepperDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
Ned3ProStepperDriver<reg_type>::writeVelocityGoal.
Definition: ned3pro_stepper_driver.hpp:239
ttl_driver::Ned3ProStepperDriver::readEncAngle
int readEncAngle(uint8_t id, const uint32_t &enc_angle)
Ned3ProStepperDriver<reg_type>::readEncAngle.
Definition: ned3pro_stepper_driver.hpp:619


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