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,
62  std::vector<std::pair<double, uint8_t>> &data_list) override;
63 
64  int syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list) override;
65 
66 public:
67  // AbstractMotorDriver interface : we cannot define them globally in AbstractMotorDriver
68  // as it is needed here for polymorphism (AbstractMotorDriver cannot be a template class and does not
69  // have access to reg_type). So it seems like a duplicate of DxlDriver
70 
71  int changeId(uint8_t id, uint8_t new_id) override;
72 
73  int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override;
74  int writePositionGoal(uint8_t id, uint32_t position) override;
75  int writeVelocityGoal(uint8_t id, uint32_t velocity) override;
76 
77  int syncWriteTorquePercentage(const std::vector<uint8_t> &id_list,
78  const std::vector<uint8_t> &torque_percentage_list) override;
79  int syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list) override;
80  int syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list) override;
81 
82  // ram read
83  int readPosition(uint8_t id, uint32_t &present_position) override;
84  int readVelocity(uint8_t id, uint32_t &present_velocity) override;
85 
86  int syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list) override;
87  int syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list) override;
88  int syncReadJointStatus(const std::vector<uint8_t> &id_list,
89  std::vector<std::array<uint32_t, 2>> &data_array_list) override;
90 
91  // AbstractStepperDriver interface
92 public:
93  common::model::EStepperCalibrationStatus interpretHomingData(uint8_t status) const override;
94 
95  int writeControlMode(uint8_t id, uint8_t operating_mode) override;
96  int writeVelocityProfile(uint8_t id, const uint32_t &velocity_profile);
97  int writeAccelerationProfile(uint8_t id, const uint32_t &acceleration_profile);
98 
99  int factoryCalibration(const uint8_t id, const uint32_t &control);
100  int readStatus(uint8_t id, const uint32_t &status);
101  int readEncAngle(uint8_t id, const uint32_t &enc_angle);
102 
103  int readFirmwareRunning(uint8_t id, bool &is_running) override;
104 
105  // unused inherited methods
106  int readMinPosition(uint8_t id, uint32_t &min_pos) override;
107  int readMaxPosition(uint8_t id, uint32_t &max_pos) override;
108 
109  int readControlMode(uint8_t id, uint8_t &operating_mode) override;
110  int readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list) override;
111  int writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list) override;
112 
113  // ram write
114  int startHoming(uint8_t id);
115  int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold);
116 
117  // read
118  int readHomingStatus(uint8_t id, uint8_t &status);
119  int syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list);
120  int syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position);
121  int syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position);
122 
123  // parameters
124  float velocityUnit() const override;
125 };
126 
127 // definition of methods
128 
132 template <typename reg_type>
133 Ned3ProStepperDriver<reg_type>::Ned3ProStepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
134  std::shared_ptr<dynamixel::PacketHandler> packetHandler)
135  : AbstractStepperDriver(std::move(portHandler), std::move(packetHandler))
136 {
137 }
138 
139 //*****************************
140 // AbstractMotorDriver interface
141 //*****************************
142 
147 template <typename reg_type>
149 {
150  return common::model::HardwareTypeEnum(reg_type::motor_type).toString() + " : " + AbstractStepperDriver::str();
151 }
152 
159 template <typename reg_type>
160 int Ned3ProStepperDriver<reg_type>::changeId(uint8_t id, uint8_t new_id)
161 {
162  // TODO(THUC) verify that COMM_RX_TIMEOUT error code do not impact on data sent to motor
163  // when COMM_RX_TIMEOUT error, id changed also, so we consider that change id successfully
164  int res = write<typename reg_type::TYPE_ID>(reg_type::ADDR_ID, id, new_id);
165  if (res == COMM_RX_TIMEOUT)
166  res = COMM_SUCCESS;
167  return res;
168 }
169 
179 template <typename reg_type>
180 int Ned3ProStepperDriver<reg_type>::checkModelNumber(uint8_t id, uint16_t &model_number)
181 {
182  int ping_result = getModelNumber(id, model_number);
183 
184  if (ping_result == COMM_SUCCESS)
185  {
186  // Use the validator from register definition to check compatibility
187  auto validator = reg_type::createModelNumberValidator();
188  if (!validator->isValid(model_number))
189  {
190  ROS_WARN("Ned3ProStepperDriver: Model number %u not valid for %s (expected %s)", model_number,
191  common::model::HardwareTypeEnum(reg_type::motor_type).toString().c_str(), validator->describe().c_str());
192  return PING_WRONG_MODEL_NUMBER;
193  }
194  }
195 
196  return ping_result;
197 }
198 
205 template <typename reg_type>
206 int Ned3ProStepperDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
207 {
208  int res = 0;
209  uint32_t data{};
210  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
211  version = interpretFirmwareVersion(data);
212  return res;
213 }
214 
215 // ram write
216 
223 template <typename reg_type>
224 int Ned3ProStepperDriver<reg_type>::writeTorquePercentage(uint8_t id, uint8_t torque_percentage)
225 {
226  return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id, torque_percentage);
227 }
228 
235 template <typename reg_type>
236 int Ned3ProStepperDriver<reg_type>::writePositionGoal(uint8_t id, uint32_t position)
237 {
238  return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id, position);
239 }
240 
241 // according to the registers, the data should be an int32_t ?
248 template <typename reg_type>
249 int Ned3ProStepperDriver<reg_type>::writeVelocityGoal(uint8_t id, uint32_t velocity)
250 {
251  return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id, velocity);
252 }
253 
260 template <typename reg_type>
261 int Ned3ProStepperDriver<reg_type>::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list,
262  const std::vector<uint8_t> &torque_percentage_list)
263 {
264  return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list,
265  torque_percentage_list);
266 }
267 
274 template <typename reg_type>
275 int Ned3ProStepperDriver<reg_type>::syncWritePositionGoal(const std::vector<uint8_t> &id_list,
276  const std::vector<uint32_t> &position_list)
277 {
278  return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
279 }
280 
287 template <typename reg_type>
288 int Ned3ProStepperDriver<reg_type>::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list,
289  const std::vector<uint32_t> &velocity_list)
290 {
291  return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
292 }
293 
294 // ram read
295 
302 template <typename reg_type>
303 int Ned3ProStepperDriver<reg_type>::readPosition(uint8_t id, uint32_t &present_position)
304 {
305  return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id, present_position);
306 }
307 
314 template <typename reg_type>
315 int Ned3ProStepperDriver<reg_type>::readVelocity(uint8_t id, uint32_t &present_velocity)
316 {
317  return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id, present_velocity);
318 }
319 
326 template <typename reg_type>
327 int Ned3ProStepperDriver<reg_type>::readTemperature(uint8_t id, uint8_t &temperature)
328 {
329  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
330 }
331 
338 template <typename reg_type>
339 int Ned3ProStepperDriver<reg_type>::readVoltage(uint8_t id, double &voltage)
340 {
341  uint16_t voltage_mV = 0;
342  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
343  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
344  return res;
345 }
346 
353 template <typename reg_type>
354 int Ned3ProStepperDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
355 {
356  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
357 }
358 
365 template <typename reg_type>
366 int Ned3ProStepperDriver<reg_type>::syncReadPosition(const std::vector<uint8_t> &id_list,
367  std::vector<uint32_t> &position_list)
368 {
369  return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
370 }
371 
378 template <typename reg_type>
379 int Ned3ProStepperDriver<reg_type>::syncReadVelocity(const std::vector<uint8_t> &id_list,
380  std::vector<uint32_t> &velocity_list)
381 {
382  return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
383 }
384 
392 template <typename reg_type>
393 int Ned3ProStepperDriver<reg_type>::syncReadJointStatus(const std::vector<uint8_t> &id_list,
394  std::vector<std::array<uint32_t, 2>> &data_array_list)
395 {
396  int res = COMM_TX_FAIL;
397 
398  if (id_list.empty())
399  return res;
400 
401  data_array_list.clear();
402 
403  // read torque enable on first id
404  typename reg_type::TYPE_TORQUE_ENABLE torque{ 1 };
405  res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
406  if (COMM_SUCCESS != res)
407  std::cout << "#############"
408  " ERROR reading stepper torque in syncReadJointStatus (error "
409  << res << ")" << std::endl;
410 
411  // if torque on, read position and velocity
412  if (torque)
413  {
414  res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
415  }
416  else // else read position only
417  {
418  std::vector<uint32_t> position_list;
419  res = syncReadPosition(id_list, position_list);
420  for (auto p : position_list)
421  data_array_list.emplace_back(std::array<uint32_t, 2>{ 1, p });
422  }
423 
424  return res;
425 }
426 
433 template <typename reg_type>
434 int Ned3ProStepperDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list,
435  std::vector<std::string> &firmware_list)
436 {
437  int res = 0;
438  firmware_list.clear();
439  std::vector<uint32_t> data_list{};
440  res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
441  for (auto const &data : data_list)
442  firmware_list.emplace_back(interpretFirmwareVersion(data));
443  return res;
444 }
445 
452 template <typename reg_type>
453 int Ned3ProStepperDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list,
454  std::vector<uint8_t> &temperature_list)
455 {
456  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list,
457  temperature_list);
458 }
459 
466 template <typename reg_type>
467 int Ned3ProStepperDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list,
468  std::vector<double> &voltage_list)
469 {
470  voltage_list.clear();
471  std::vector<uint16_t> v_read;
472  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
473  for (auto const &v : v_read)
474  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
475  return res;
476 }
477 
484 template <typename reg_type>
485 int Ned3ProStepperDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list,
486  std::vector<double> &voltage_list)
487 {
488  voltage_list.clear();
489  std::vector<uint16_t> v_read;
490  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
491  for (auto const &v : v_read)
492  voltage_list.emplace_back(static_cast<double>(v));
493  return res;
494 }
495 
502 template <typename reg_type>
503 int Ned3ProStepperDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
504  std::vector<std::pair<double, uint8_t>> &data_list)
505 {
506  data_list.clear();
507 
508  std::vector<std::array<uint8_t, 3>> raw_data;
509  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
510 
511  for (auto const &data : raw_data)
512  {
513  // Voltage is first reg, uint16
514  auto v = static_cast<uint16_t>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0)); // concatenate 2 bytes
515  auto voltage = static_cast<double>(v);
516 
517  // Temperature is second reg, uint8
518  uint8_t temperature = data.at(2);
519 
520  data_list.emplace_back(std::make_pair(voltage, temperature));
521  }
522 
523  return res;
524 }
531 template <typename reg_type>
532 int Ned3ProStepperDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list,
533  std::vector<uint8_t> &hw_error_list)
534 {
535  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
536 }
537 
538 //*****************************
539 // AbstractStepperDriver interface
540 //*****************************
541 
547 template <typename reg_type>
548 common::model::EStepperCalibrationStatus Ned3ProStepperDriver<reg_type>::interpretHomingData(uint8_t status) const
549 {
550  enum Ned3ProStepperCalibrationStatus
551  {
552  UNINITIALIZED_MASK = 0,
553  IN_PROGRESS_MASK = 2,
554  OK_MASK = 4,
555  FAIL_MASK = 8
556  };
557 
558  return status & IN_PROGRESS_MASK ? common::model::EStepperCalibrationStatus::IN_PROGRESS :
559  status & FAIL_MASK ? common::model::EStepperCalibrationStatus::FAIL :
560  status & OK_MASK ? common::model::EStepperCalibrationStatus::OK :
561  common::model::EStepperCalibrationStatus::FAIL;
562 }
563 
570 template <typename reg_type>
571 int Ned3ProStepperDriver<reg_type>::writeControlMode(uint8_t id, uint8_t operating_mode)
572 {
573  return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE, id, operating_mode);
574 }
575 
582 template <typename reg_type>
583 int Ned3ProStepperDriver<reg_type>::writeVelocityProfile(uint8_t id, const uint32_t &velocity_profile)
584 {
585  return write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY, id, velocity_profile);
586 }
587 
594 template <typename reg_type>
595 int Ned3ProStepperDriver<reg_type>::writeAccelerationProfile(uint8_t id, const uint32_t &acceleration_profile)
596 {
597  return write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION, id,
598  acceleration_profile);
599 }
600 
607 template <typename reg_type>
608 int Ned3ProStepperDriver<reg_type>::factoryCalibration(const uint8_t id, const uint32_t &command)
609 {
610  return write<typename reg_type::TYPE_CONTROL>(reg_type::ADDR_CONTROL, id, command);
611 }
612 
619 template <typename reg_type>
620 int Ned3ProStepperDriver<reg_type>::readStatus(uint8_t id, const uint32_t &status)
621 {
622  return read<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id, status);
623 }
624 
625 template <typename reg_type>
626 int Ned3ProStepperDriver<reg_type>::syncReadHomingStatus(const std::vector<uint8_t> &id_list,
627  std::vector<uint8_t> &status_list)
628 {
629  std::vector<uint32_t> status_list_tmp;
630  auto result = syncRead<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id_list, status_list_tmp);
631  for (const auto &status_tmp : status_list_tmp)
632  status_list.push_back(static_cast<uint8_t>(status_tmp));
633 
634  return result;
635 };
636 
643 template <typename reg_type>
644 int Ned3ProStepperDriver<reg_type>::readEncAngle(uint8_t id, const uint32_t &enc_angle)
645 {
646  return read<typename reg_type::TYPE_ENC_ANGLE>(reg_type::ADDR_ENC_ANGLE, id, enc_angle);
647 }
648 
655 template <typename reg_type>
657 {
658  typename reg_type::TYPE_FIRMWARE_RUNNING data{};
659  int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING, id, data);
660  is_running = data;
661  return res;
662 }
663 
664 // unused inherited methods
665 template <typename reg_type>
666 int Ned3ProStepperDriver<reg_type>::readMinPosition(uint8_t id, uint32_t &min_pos)
667 {
668  ROS_WARN("Ned3ProStepperDriver::readMinPosition - Not implemented");
669 
670  return COMM_NOT_AVAILABLE;
671 };
672 
673 template <typename reg_type>
674 int Ned3ProStepperDriver<reg_type>::readMaxPosition(uint8_t id, uint32_t &max_pos)
675 {
676  ROS_WARN("Ned3ProStepperDriver::readMaxPosition - Not implemented");
677 
678  return COMM_NOT_AVAILABLE;
679 };
680 
681 template <typename reg_type>
683 {
684  ROS_WARN("Ned3ProStepperDriver::readControlMode - Not implemented");
685 
686  return COMM_NOT_AVAILABLE;
687 };
688 
689 template <typename reg_type>
690 int Ned3ProStepperDriver<reg_type>::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list)
691 {
692  ROS_WARN("Ned3ProStepperDriver::readVelocityProfile std::vector<uint32_t> &data_list - Not implemented");
693 
694  return COMM_NOT_AVAILABLE;
695 };
696 
697 template <typename reg_type>
698 int Ned3ProStepperDriver<reg_type>::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list)
699 {
700  int tries = 10;
701  int res = COMM_RX_FAIL;
702  double wait_duration = 0.05;
703 
704  // Random positive value to activate the torque, we need this to write on other registers
705  constexpr auto ACTIVE_TORQUE_PERCENT = 40;
706  writeTorquePercentage(id, ACTIVE_TORQUE_PERCENT);
707 
708  tries = 10;
709  while (tries > 0) // try 10 times
710  {
711  tries--;
712  ros::Duration(wait_duration).sleep();
713  res = write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY, id, data_list.at(4));
714  if (res == COMM_SUCCESS)
715  break;
716  }
717  if (res != COMM_SUCCESS)
718  return res;
719 
720  tries = 10;
721  while (tries > 0) // try 10 times
722  {
723  tries--;
724  ros::Duration(wait_duration).sleep();
725  res = write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION, id, data_list.at(3));
726  if (res == COMM_SUCCESS)
727  break;
728  }
729 
730  return res;
731 };
732 
733 template <typename reg_type>
735 {
736  ROS_WARN("Ned3ProStepperDriver::startHoming - Not implemented");
737 
738  return COMM_NOT_AVAILABLE;
739 };
740 
741 template <typename reg_type>
742 int Ned3ProStepperDriver<reg_type>::writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)
743 {
744  ROS_WARN("Ned3ProStepperDriver::writeHomingSetup - Not implemented");
745 
746  return COMM_NOT_AVAILABLE;
747 };
748 
749 // read
750 template <typename reg_type>
751 int Ned3ProStepperDriver<reg_type>::readHomingStatus(uint8_t id, uint8_t &status)
752 {
753  ROS_WARN("Ned3ProStepperDriver::readHomingStatus - Not implemented");
754 
755  return COMM_NOT_AVAILABLE;
756 };
757 template <typename reg_type>
758 int Ned3ProStepperDriver<reg_type>::syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list,
759  std::vector<uint32_t> &abs_position)
760 {
761  ROS_WARN("Ned3ProStepperDriver::syncReadHomingAbsPosition - Not implemented");
762 
763  return COMM_NOT_AVAILABLE;
764 };
765 template <typename reg_type>
766 int Ned3ProStepperDriver<reg_type>::syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list,
767  const std::vector<uint32_t> &abs_position)
768 {
769  ROS_WARN("Ned3ProStepperDriver::syncWriteHomingAbsPosition - Not implemented");
770 
771  return COMM_NOT_AVAILABLE;
772 };
773 
774 template <typename reg_type>
776 {
777  return reg_type::VELOCITY_UNIT;
778 }
779 } // namespace ttl_driver
780 
781 #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:133
ttl_driver::Ned3ProStepperDriver::factoryCalibration
int factoryCalibration(const uint8_t id, const uint32_t &control)
Ned3ProStepperDriver<reg_type>::factoryCalibration.
Definition: ned3pro_stepper_driver.hpp:608
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:532
ttl_driver::AbstractStepperDriver::str
std::string str() const override
AbstractStepperDriver::str.
Definition: abstract_stepper_driver.cpp:49
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:434
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:775
ttl_driver::Ned3ProStepperDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
Definition: ned3pro_stepper_driver.hpp:666
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:275
ttl_driver::Ned3ProStepperDriver::writeHomingSetup
int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)
Definition: ned3pro_stepper_driver.hpp:742
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:366
ttl_driver::Ned3ProStepperDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
Ned3ProStepperDriver<reg_type>::changeId.
Definition: ned3pro_stepper_driver.hpp:160
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:766
ttl_driver::Ned3ProStepperDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
Ned3ProStepperDriver<reg_type>::writePositionGoal.
Definition: ned3pro_stepper_driver.hpp:236
ttl_driver::Ned3ProStepperDriver::readFirmwareRunning
int readFirmwareRunning(uint8_t id, bool &is_running) override
Ned3ProStepperDriver<reg_type>::readFirmwareRunning.
Definition: ned3pro_stepper_driver.hpp:656
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:288
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:453
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:503
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:261
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:393
ttl_driver::Ned3ProStepperDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t operating_mode) override
Ned3ProStepperDriver<reg_type>::writeOperatingMode.
Definition: ned3pro_stepper_driver.hpp:571
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:595
ttl_driver::Ned3ProStepperDriver::syncReadHomingAbsPosition
int syncReadHomingAbsPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position)
Definition: ned3pro_stepper_driver.hpp:758
ttl_driver::Ned3ProStepperDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
Definition: ned3pro_stepper_driver.hpp:674
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:485
ttl_driver::Ned3ProStepperDriver::readStatus
int readStatus(uint8_t id, const uint32_t &status)
Ned3ProStepperDriver<reg_type>::readStatus.
Definition: ned3pro_stepper_driver.hpp:620
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:548
ttl_driver::Ned3ProStepperDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
Ned3ProStepperDriver<reg_type>::checkModelNumber.
Definition: ned3pro_stepper_driver.hpp:180
ttl_driver::Ned3ProStepperDriver::syncReadHomingStatus
int syncReadHomingStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list)
Definition: ned3pro_stepper_driver.hpp:626
ttl_driver::Ned3ProStepperDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &operating_mode) override
Definition: ned3pro_stepper_driver.hpp:682
ttl_driver::Ned3ProStepperDriver::str
std::string str() const override
Ned3ProStepperDriver<reg_type>::str.
Definition: ned3pro_stepper_driver.hpp:148
ttl_driver::Ned3ProStepperDriver::writeVelocityProfile
int writeVelocityProfile(uint8_t id, const uint32_t &velocity_profile)
Ned3ProStepperDriver<reg_type>::writeVelocityProfile.
Definition: ned3pro_stepper_driver.hpp:583
ttl_driver::Ned3ProStepperDriver::readHomingStatus
int readHomingStatus(uint8_t id, uint8_t &status)
Definition: ned3pro_stepper_driver.hpp:751
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:690
ttl_driver::Ned3ProStepperDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
Ned3ProStepperDriver<reg_type>::readHwErrorStatus.
Definition: ned3pro_stepper_driver.hpp:354
ttl_driver::Ned3ProStepperDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
Ned3ProStepperDriver<reg_type>::writeTorquePercentage.
Definition: ned3pro_stepper_driver.hpp:224
ttl_driver::Ned3ProStepperDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
Ned3ProStepperDriver<reg_type>::readVelocity.
Definition: ned3pro_stepper_driver.hpp:315
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:467
ttl_driver::Ned3ProStepperDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
Ned3ProStepperDriver<reg_type>::readVoltage.
Definition: ned3pro_stepper_driver.hpp:339
ttl_driver::Ned3ProStepperDriver::startHoming
int startHoming(uint8_t id)
Definition: ned3pro_stepper_driver.hpp:734
ttl_driver::Ned3ProStepperDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
Ned3ProStepperDriver<reg_type>::readTemperature.
Definition: ned3pro_stepper_driver.hpp:327
ttl_driver::Ned3ProStepperDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
Ned3ProStepperDriver<reg_type>::readPosition.
Definition: ned3pro_stepper_driver.hpp:303
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:379
ttl_driver::Ned3ProStepperDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
Ned3ProStepperDriver<reg_type>::readFirmwareVersion.
Definition: ned3pro_stepper_driver.hpp:206
ttl_driver::Ned3ProStepperDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
Ned3ProStepperDriver<reg_type>::writeVelocityGoal.
Definition: ned3pro_stepper_driver.hpp:249
ttl_driver::Ned3ProStepperDriver::readEncAngle
int readEncAngle(uint8_t id, const uint32_t &enc_angle)
Ned3ProStepperDriver<reg_type>::readEncAngle.
Definition: ned3pro_stepper_driver.hpp:644


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