stepper_driver.hpp
Go to the documentation of this file.
1 /*
2 stepper_driver.hpp
3 Copyright (C) 2020 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 STEPPER_DRIVER_HPP
18 #define STEPPER_DRIVER_HPP
19 
20 #include <memory>
21 #include <vector>
22 #include <string>
23 #include <iostream>
24 #include <sstream>
25 #include "ros/duration.h"
26 
28 
29 #include "stepper_reg.hpp"
30 
31 namespace ttl_driver
32 {
33 
37 template <typename reg_type = StepperReg>
39 {
40 public:
41  StepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
42  std::shared_ptr<dynamixel::PacketHandler> packetHandler);
43 
44 public:
45  // AbstractTtlDriver interface
46  std::string str() const override;
47 
48  int checkModelNumber(uint8_t id, uint16_t &model_number) override;
49  int readFirmwareVersion(uint8_t id, std::string &version) override;
50 
51  int readTemperature(uint8_t id, uint8_t &temperature) override;
52  int readVoltage(uint8_t id, double &voltage) override;
53  int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override;
54 
55  int syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list) override;
56  int syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list) override;
57  int syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
58  int syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
59  int syncReadHwStatus(const std::vector<uint8_t> &id_list,
60  std::vector<std::pair<double, uint8_t>> &data_list) override;
61 
62  int syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list) override;
63 
64 public:
65  // AbstractMotorDriver interface : we cannot define them globally in AbstractMotorDriver
66  // as it is needed here for polymorphism (AbstractMotorDriver cannot be a template class and does not
67  // have access to reg_type). So it seems like a duplicate of DxlDriver
68 
69  int changeId(uint8_t id, uint8_t new_id) override;
70 
71  int readMinPosition(uint8_t id, uint32_t &min_pos) override;
72  int readMaxPosition(uint8_t id, uint32_t &max_pos) override;
73 
74  int writeTorquePercentage(uint8_t id, uint8_t torque_enable) override;
75  int writePositionGoal(uint8_t id, uint32_t position) override;
76  int writeVelocityGoal(uint8_t id, uint32_t velocity) override;
77 
78  int syncWriteTorquePercentage(const std::vector<uint8_t> &id_list,
79  const std::vector<uint8_t> &torque_percentage_list) override;
80  int syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list) override;
81  int syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list) override;
82 
83  // ram read
84  int readPosition(uint8_t id, uint32_t &present_position) override;
85  int readVelocity(uint8_t id, uint32_t &present_velocity) override;
86 
87  int syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list) override;
88  int syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list) override;
89  int syncReadJointStatus(const std::vector<uint8_t> &id_list,
90  std::vector<std::array<uint32_t, 2>> &data_array_list) override;
91 
92  // AbstractStepperDriver interface
93 public:
94  int readControlMode(uint8_t id, uint8_t &operating_mode) override;
95  int writeControlMode(uint8_t id, uint8_t operating_mode);
96 
97  int readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list) override;
98  int writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list) override;
99 
100  int startHoming(uint8_t id) override;
101  int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) override;
102 
103  int readHomingStatus(uint8_t id, uint8_t &status) override;
104  int syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list) override;
105 
106  int readFirmwareRunning(uint8_t id, bool &is_running) override;
107 
108  int syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position) override;
109  int syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list,
110  const std::vector<uint32_t> &abs_position) override;
111 
112  float velocityUnit() const;
113 
114 private:
115  int writeVStart(uint8_t id, uint32_t v_start);
116  int writeA1(uint8_t id, uint32_t a_1);
117  int writeV1(uint8_t id, uint32_t v_1);
118  int writeAMax(uint8_t id, uint32_t a_max);
119  int writeVMax(uint8_t id, uint32_t v_max);
120  int writeDMax(uint8_t id, uint32_t d_max);
121  int writeD1(uint8_t id, uint32_t d_1);
122  int writeVStop(uint8_t id, uint32_t v_stop);
123 };
124 
125 // definition of methods
126 
130 template <typename reg_type>
131 StepperDriver<reg_type>::StepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
132  std::shared_ptr<dynamixel::PacketHandler> packetHandler)
133  : AbstractStepperDriver(std::move(portHandler), std::move(packetHandler))
134 {
135 }
136 
137 //*****************************
138 // AbstractMotorDriver interface
139 //*****************************
140 
145 template <typename reg_type>
146 std::string StepperDriver<reg_type>::str() const
147 {
148  return common::model::HardwareTypeEnum(reg_type::motor_type).toString() + " : " + AbstractStepperDriver::str();
149 }
150 
157 template <typename reg_type>
158 int StepperDriver<reg_type>::changeId(uint8_t id, uint8_t new_id)
159 {
160  // TODO(THUC) verify that COMM_RX_TIMEOUT error code do not impact on data sent to motor
161  // when COMM_RX_TIMEOUT error, id changed also, so we consider that change id successfully
162  int res = write<typename reg_type::TYPE_ID>(reg_type::ADDR_ID, id, new_id);
163  if (res == COMM_RX_TIMEOUT)
164  res = COMM_SUCCESS;
165  return res;
166 }
167 
177 template <typename reg_type>
178 int StepperDriver<reg_type>::checkModelNumber(uint8_t id, uint16_t &model_number)
179 {
180  int ping_result = getModelNumber(id, model_number);
181 
182  if (ping_result == COMM_SUCCESS && model_number != 0)
183  {
184  // Use the validator from register definition to check compatibility
185  auto validator = reg_type::createModelNumberValidator();
186  if (!validator->isValid(model_number))
187  {
188  ROS_WARN("StepperDriver: Model number %u not valid for %s (expected %s)", model_number,
189  common::model::HardwareTypeEnum(reg_type::motor_type).toString().c_str(), validator->describe().c_str());
190  return PING_WRONG_MODEL_NUMBER;
191  }
192  }
193 
194  return ping_result;
195 }
196 
203 template <typename reg_type>
204 int StepperDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
205 {
206  int res = 0;
207  uint32_t data{};
208  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
209  version = interpretFirmwareVersion(data);
210  return res;
211 }
212 
219 template <typename reg_type>
220 int StepperDriver<reg_type>::readMinPosition(uint8_t id, uint32_t &pos)
221 {
222  return read<typename reg_type::TYPE_MIN_POSITION_LIMIT>(reg_type::ADDR_MIN_POSITION_LIMIT, id, pos);
223 }
224 
231 template <typename reg_type>
232 int StepperDriver<reg_type>::readMaxPosition(uint8_t id, uint32_t &pos)
233 {
234  return read<typename reg_type::TYPE_MAX_POSITION_LIMIT>(reg_type::ADDR_MAX_POSITION_LIMIT, id, pos);
235 }
236 
237 // ram write
238 
245 template <typename reg_type>
246 int StepperDriver<reg_type>::writeTorquePercentage(uint8_t id, uint8_t torque_percentage)
247 {
248  auto torque_enable = torque_percentage > 0 ? 1 : 0;
249  return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id, torque_enable);
250 }
251 
258 template <typename reg_type>
259 int StepperDriver<reg_type>::writePositionGoal(uint8_t id, uint32_t position)
260 {
261  return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id, position);
262 }
263 
264 // according to the registers, the data should be an int32_t ?
271 template <typename reg_type>
272 int StepperDriver<reg_type>::writeVelocityGoal(uint8_t id, uint32_t velocity)
273 {
274  return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id, velocity);
275 }
276 
283 template <typename reg_type>
284 int StepperDriver<reg_type>::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list,
285  const std::vector<uint8_t> &torque_percentage_list)
286 {
287  std::vector<uint8_t> torque_enable_list;
288  for (const auto &torque_percentage : torque_percentage_list)
289  {
290  auto torque_enable = torque_percentage > 0 ? 1 : 0;
291  torque_enable_list.push_back(torque_enable);
292  }
293  return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list, torque_enable_list);
294 }
295 
302 template <typename reg_type>
303 int StepperDriver<reg_type>::syncWritePositionGoal(const std::vector<uint8_t> &id_list,
304  const std::vector<uint32_t> &position_list)
305 {
306  return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
307 }
308 
315 template <typename reg_type>
316 int StepperDriver<reg_type>::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list,
317  const std::vector<uint32_t> &velocity_list)
318 {
319  return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
320 }
321 
322 // ram read
323 
330 template <typename reg_type>
331 int StepperDriver<reg_type>::readPosition(uint8_t id, uint32_t &present_position)
332 {
333  return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id, present_position);
334 }
335 
342 template <typename reg_type>
343 int StepperDriver<reg_type>::readVelocity(uint8_t id, uint32_t &present_velocity)
344 {
345  return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id, present_velocity);
346 }
347 
354 template <typename reg_type>
355 int StepperDriver<reg_type>::readTemperature(uint8_t id, uint8_t &temperature)
356 {
357  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
358 }
359 
366 template <typename reg_type>
367 int StepperDriver<reg_type>::readVoltage(uint8_t id, double &voltage)
368 {
369  uint16_t voltage_mV = 0;
370  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
371  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
372  return res;
373 }
374 
381 template <typename reg_type>
382 int StepperDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
383 {
384  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
385 }
386 
393 template <typename reg_type>
394 int StepperDriver<reg_type>::syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
395 {
396  return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
397 }
398 
405 template <typename reg_type>
406 int StepperDriver<reg_type>::syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
407 {
408  return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
409 }
410 
418 template <typename reg_type>
419 int StepperDriver<reg_type>::syncReadJointStatus(const std::vector<uint8_t> &id_list,
420  std::vector<std::array<uint32_t, 2>> &data_array_list)
421 {
422  int res = COMM_TX_FAIL;
423 
424  if (id_list.empty())
425  return res;
426 
427  data_array_list.clear();
428 
429  // read torque enable on first id
430  typename reg_type::TYPE_TORQUE_ENABLE torque{ 1 };
431  res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
432  if (COMM_SUCCESS != res)
433  std::cout << "#############"
434  " ERROR reading stepper torque in syncReadJointStatus (error "
435  << res << ")" << std::endl;
436 
437  // if torque on, read position and velocity
438  if (torque)
439  {
440  res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
441  }
442  else // else read position only
443  {
444  std::vector<uint32_t> position_list;
445  res = syncReadPosition(id_list, position_list);
446  for (auto p : position_list)
447  data_array_list.emplace_back(std::array<uint32_t, 2>{ 1, p });
448  }
449 
450  return res;
451 }
452 
459 template <typename reg_type>
460 int StepperDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list,
461  std::vector<std::string> &firmware_list)
462 {
463  int res = 0;
464  firmware_list.clear();
465  std::vector<uint32_t> data_list{};
466  res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
467  for (auto const &data : data_list)
468  firmware_list.emplace_back(interpretFirmwareVersion(data));
469  return res;
470 }
471 
478 template <typename reg_type>
479 int StepperDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list,
480  std::vector<uint8_t> &temperature_list)
481 {
482  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list,
483  temperature_list);
484 }
485 
492 template <typename reg_type>
493 int StepperDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
494 {
495  voltage_list.clear();
496  std::vector<uint16_t> v_read;
497  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
498  for (auto const &v : v_read)
499  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
500  return res;
501 }
502 
509 template <typename reg_type>
510 int StepperDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
511 {
512  voltage_list.clear();
513  std::vector<uint16_t> v_read;
514  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
515  for (auto const &v : v_read)
516  voltage_list.emplace_back(static_cast<double>(v));
517  return res;
518 }
519 
526 template <typename reg_type>
527 int StepperDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
528  std::vector<std::pair<double, uint8_t>> &data_list)
529 {
530  data_list.clear();
531 
532  std::vector<std::array<uint8_t, 3>> raw_data;
533  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
534 
535  for (auto const &data : raw_data)
536  {
537  // Voltage is first reg, uint16
538  auto v = static_cast<uint16_t>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0)); // concatenate 2 bytes
539  auto voltage = static_cast<double>(v);
540 
541  // Temperature is second reg, uint8
542  uint8_t temperature = data.at(2);
543 
544  data_list.emplace_back(std::make_pair(voltage, temperature));
545  }
546 
547  return res;
548 }
555 template <typename reg_type>
556 int StepperDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list,
557  std::vector<uint8_t> &hw_error_list)
558 {
559  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
560 }
561 
562 //*****************************
563 // AbstractStepperDriver interface
564 //*****************************
565 
566 template <typename reg_type>
567 int StepperDriver<reg_type>::readControlMode(uint8_t id, uint8_t &operating_mode)
568 {
569  return read<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE, id, operating_mode);
570 }
571 
572 template <typename reg_type>
573 int StepperDriver<reg_type>::writeControlMode(uint8_t id, const uint8_t operating_mode)
574 {
575  return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE, id, operating_mode);
576 }
577 
584 template <typename reg_type>
585 int StepperDriver<reg_type>::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list)
586 {
587  int res = COMM_RX_FAIL;
588  data_list.clear();
589 
590  std::vector<std::array<typename reg_type::TYPE_PROFILE, 8>> data_array_list;
591  if (COMM_SUCCESS ==
592  syncReadConsecutiveBytes<typename reg_type::TYPE_PROFILE, 8>(reg_type::ADDR_VSTART, { id }, data_array_list))
593  {
594  if (!data_array_list.empty())
595  {
596  auto block = data_array_list.at(0);
597 
598  for (auto data : block)
599  {
600  data_list.emplace_back(data);
601  }
602  }
603 
604  res = COMM_SUCCESS;
605  }
606  else
607  {
608  std::cout << "Failures during read Velocity Profile" << std::endl;
609  }
610 
611  return res;
612 }
613 
621 template <typename reg_type>
622 int StepperDriver<reg_type>::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list)
623 {
624  int tries = 10;
625  int res = COMM_RX_FAIL;
626  double wait_duration = 0.05;
627 
628  // Random positive value to activate the torque, we need this to write on other registers
629  constexpr auto ACTIVE_TORQUE_PERCENT = 1;
630  writeTorquePercentage(id, ACTIVE_TORQUE_PERCENT);
631 
632  // only rewrite the params which is not success
633  while (tries > 0) // try 10 times
634  {
635  tries--;
636  ros::Duration(wait_duration).sleep();
637  res = writeVStart(id, data_list.at(0));
638  if (res == COMM_SUCCESS)
639  break;
640  }
641  if (res != COMM_SUCCESS)
642  return res;
643 
644  tries = 10;
645  while (tries > 0) // try 10 times
646  {
647  tries--;
648  ros::Duration(wait_duration).sleep();
649  res = writeA1(id, data_list.at(1));
650  if (res == COMM_SUCCESS)
651  break;
652  }
653  if (res != COMM_SUCCESS)
654  return res;
655 
656  tries = 10;
657  while (tries > 0) // try 10 times
658  {
659  tries--;
660  ros::Duration(wait_duration).sleep();
661  res = writeV1(id, data_list.at(2));
662  if (res == COMM_SUCCESS)
663  break;
664  }
665  if (res != COMM_SUCCESS)
666  return res;
667 
668  tries = 10;
669  while (tries > 0) // try 10 times
670  {
671  tries--;
672  ros::Duration(wait_duration).sleep();
673  res = writeAMax(id, data_list.at(3));
674  if (res == COMM_SUCCESS)
675  break;
676  }
677  if (res != COMM_SUCCESS)
678  return res;
679 
680  tries = 10;
681  while (tries > 0) // try 10 times
682  {
683  tries--;
684  ros::Duration(wait_duration).sleep();
685  res = writeVMax(id, data_list.at(4));
686  if (res == COMM_SUCCESS)
687  break;
688  }
689  if (res != COMM_SUCCESS)
690  return res;
691 
692  tries = 10;
693  while (tries > 0) // try 10 times
694  {
695  tries--;
696  ros::Duration(wait_duration).sleep();
697  res = writeDMax(id, data_list.at(5));
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 = writeD1(id, data_list.at(6));
710  if (res == COMM_SUCCESS)
711  break;
712  }
713  if (res != COMM_SUCCESS)
714  return res;
715 
716  tries = 10;
717  while (tries > 0) // try 10 times
718  {
719  tries--;
720  ros::Duration(wait_duration).sleep();
721  res = writeVStop(id, data_list.at(7));
722  if (res == COMM_SUCCESS)
723  break;
724  }
725 
726  return res;
727 }
728 
734 template <typename reg_type>
736 {
737  return write<typename reg_type::TYPE_COMMAND>(reg_type::ADDR_COMMAND, id, 0);
738 }
739 
748 template <typename reg_type>
749 int StepperDriver<reg_type>::writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)
750 {
751  int res = 0;
752  double wait_duration = 0.05;
753 
754  // Random positive value to activate the torque, we need this to write on other registers
755  constexpr auto ACTIVE_TORQUE_PERCENT = 1;
756  writeTorquePercentage(id, ACTIVE_TORQUE_PERCENT);
757  ros::Duration(wait_duration).sleep();
758 
759  if (COMM_SUCCESS != write<typename reg_type::TYPE_HOMING_DIRECTION>(reg_type::ADDR_HOMING_DIRECTION, id, direction))
760  res++;
761  ros::Duration(wait_duration).sleep();
762 
763  // if (COMM_SUCCESS != write<typename reg_type::TYPE_HOMING_STALL_THRESHOLD>(reg_type::ADDR_HOMING_STALL_THRESHOLD,
764  // id, stall_threshold))
765  // res++;
766  // ros::Duration(wait_duration).sleep();
767 
768  if (res > 0)
769  {
770  std::cout << "Failures during writeVelocityProfile : " << res << std::endl;
771  return COMM_TX_FAIL;
772  }
773 
774  return COMM_SUCCESS;
775 }
776 
783 template <typename reg_type>
784 int StepperDriver<reg_type>::readHomingStatus(uint8_t id, uint8_t &status)
785 {
786  return read<typename reg_type::TYPE_HOMING_STATUS>(reg_type::ADDR_HOMING_STATUS, id, status);
787 }
788 
795 template <typename reg_type>
796 int StepperDriver<reg_type>::syncReadHomingStatus(const std::vector<uint8_t> &id_list,
797  std::vector<uint8_t> &status_list)
798 {
799  return syncRead<typename reg_type::TYPE_HOMING_STATUS>(reg_type::ADDR_HOMING_STATUS, id_list, status_list);
800 }
801 
808 template <typename reg_type>
809 int StepperDriver<reg_type>::readFirmwareRunning(uint8_t id, bool &is_running)
810 {
811  typename reg_type::TYPE_FIRMWARE_RUNNING data{};
812  int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING, id, data);
813  is_running = data;
814  return res;
815 }
816 
823 template <typename reg_type>
824 int StepperDriver<reg_type>::syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list,
825  const std::vector<uint32_t> &abs_position)
826 {
827  return syncWrite<typename reg_type::TYPE_HOMING_ABS_POSITION>(reg_type::ADDR_HOMING_ABS_POSITION, id_list,
828  abs_position);
829 }
830 
837 template <typename reg_type>
838 int StepperDriver<reg_type>::syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list,
839  std::vector<uint32_t> &abs_position)
840 {
841  return syncRead<typename reg_type::TYPE_HOMING_ABS_POSITION>(reg_type::ADDR_HOMING_ABS_POSITION, id_list,
842  abs_position);
843 }
844 
845 // private
846 
853 template <typename reg_type>
854 int StepperDriver<reg_type>::writeVStart(uint8_t id, uint32_t v_start)
855 {
856  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VSTART, id, v_start);
857 }
858 
865 template <typename reg_type>
866 int StepperDriver<reg_type>::writeA1(uint8_t id, uint32_t a_1)
867 {
868  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_A1, id, a_1);
869 }
870 
877 template <typename reg_type>
878 int StepperDriver<reg_type>::writeV1(uint8_t id, uint32_t v_1)
879 {
880  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_V1, id, v_1);
881 }
882 
889 template <typename reg_type>
890 int StepperDriver<reg_type>::writeAMax(uint8_t id, uint32_t a_max)
891 {
892  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_AMAX, id, a_max);
893 }
894 
901 template <typename reg_type>
902 int StepperDriver<reg_type>::writeVMax(uint8_t id, uint32_t v_max)
903 {
904  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VMAX, id, v_max);
905 }
906 
913 template <typename reg_type>
914 int StepperDriver<reg_type>::writeDMax(uint8_t id, uint32_t d_max)
915 {
916  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_DMAX, id, d_max);
917 }
918 
925 template <typename reg_type>
926 int StepperDriver<reg_type>::writeD1(uint8_t id, uint32_t d_1)
927 {
928  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_D1, id, d_1);
929 }
930 
937 template <typename reg_type>
938 int StepperDriver<reg_type>::writeVStop(uint8_t id, uint32_t v_stop)
939 {
940  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VSTOP, id, v_stop);
941 }
942 
943 template <typename reg_type>
945 {
946  return reg_type::VELOCITY_UNIT;
947 }
948 
949 } // namespace ttl_driver
950 
951 #endif // STEPPER_DRIVER_HPP
ttl_driver::StepperDriver
The StepperDriver class.
Definition: stepper_driver.hpp:38
ttl_driver::StepperDriver::syncReadPosition
int syncReadPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list) override
StepperDriver<reg_type>::syncReadPosition.
Definition: stepper_driver.hpp:394
ttl_driver::StepperDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
StepperDriver<reg_type>::readTemperature.
Definition: stepper_driver.hpp:355
ttl_driver::StepperDriver::syncReadRawVoltage
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
StepperDriver<reg_type>::syncReadRawVoltage.
Definition: stepper_driver.hpp:510
ttl_driver::AbstractStepperDriver::str
std::string str() const override
AbstractStepperDriver::str.
Definition: abstract_stepper_driver.cpp:49
ttl_driver::StepperDriver::syncReadVoltage
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
StepperDriver<reg_type>::syncReadVoltage.
Definition: stepper_driver.hpp:493
ttl_driver::StepperDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
StepperDriver<reg_type>::writeVelocityGoal.
Definition: stepper_driver.hpp:272
ttl_driver::StepperDriver::StepperDriver
StepperDriver(std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler)
DxlDriver<reg_type>::DxlDriver.
Definition: stepper_driver.hpp:131
ttl_driver::StepperDriver::syncWritePositionGoal
int syncWritePositionGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list) override
StepperDriver<reg_type>::syncWritePositionGoal.
Definition: stepper_driver.hpp:303
ttl_driver::StepperDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
StepperDriver<reg_type>::readVoltage.
Definition: stepper_driver.hpp:367
ttl_driver::StepperDriver::writeVMax
int writeVMax(uint8_t id, uint32_t v_max)
StepperDriver<reg_type>::writeVMax.
Definition: stepper_driver.hpp:902
ttl_driver::StepperDriver::writeAMax
int writeAMax(uint8_t id, uint32_t a_max)
StepperDriver<reg_type>::writeAMax.
Definition: stepper_driver.hpp:890
ttl_driver::StepperDriver::syncReadJointStatus
int syncReadJointStatus(const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 >> &data_array_list) override
StepperDriver<reg_type>::syncReadJointStatus.
Definition: stepper_driver.hpp:419
stepper_reg.hpp
ttl_driver::StepperDriver::writeVStop
int writeVStop(uint8_t id, uint32_t v_stop)
StepperDriver<reg_type>::writeVStop.
Definition: stepper_driver.hpp:938
ttl_driver::StepperDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
StepperDriver<reg_type>::checkModelNumber.
Definition: stepper_driver.hpp:178
ttl_driver::StepperDriver::writeHomingSetup
int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) override
StepperDriver<reg_type>::writeHomingDirection.
Definition: stepper_driver.hpp:749
ttl_driver::StepperDriver::writeVStart
int writeVStart(uint8_t id, uint32_t v_start)
StepperDriver<reg_type>::writeVStart.
Definition: stepper_driver.hpp:854
ttl_driver::StepperDriver::writeDMax
int writeDMax(uint8_t id, uint32_t d_max)
StepperDriver<reg_type>::writeDMax.
Definition: stepper_driver.hpp:914
ttl_driver::StepperDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
StepperDriver<reg_type>::writePositionGoal.
Definition: stepper_driver.hpp:259
abstract_stepper_driver.hpp
ttl_driver::StepperDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
StepperDriver<reg_type>::readFirmwareVersion.
Definition: stepper_driver.hpp:204
ttl_driver::StepperDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
StepperDriver<reg_type>::changeId.
Definition: stepper_driver.hpp:158
ttl_driver::StepperDriver::readHomingStatus
int readHomingStatus(uint8_t id, uint8_t &status) override
StepperDriver<reg_type>::readHomingStatus.
Definition: stepper_driver.hpp:784
ttl_driver::StepperDriver::writeA1
int writeA1(uint8_t id, uint32_t a_1)
StepperDriver<reg_type>::writeA1.
Definition: stepper_driver.hpp:866
ttl_driver::StepperDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
StepperDriver::readVelocityProfile.
Definition: stepper_driver.hpp:585
ttl_driver::StepperDriver::velocityUnit
float velocityUnit() const
writeVelocityGoal: define the unit of the velocity in RPM
Definition: stepper_driver.hpp:944
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::StepperDriver::syncReadFirmwareVersion
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
StepperDriver<reg_type>::syncReadFirmwareVersion.
Definition: stepper_driver.hpp:460
ttl_driver::StepperDriver::readFirmwareRunning
int readFirmwareRunning(uint8_t id, bool &is_running) override
StepperDriver<reg_type>::readFirmwareRunning.
Definition: stepper_driver.hpp:809
ttl_driver::StepperDriver::syncReadHwStatus
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t >> &data_list) override
StepperDriver<reg_type>::syncReadHwStatus.
Definition: stepper_driver.hpp:527
ttl_driver::StepperDriver::syncWriteTorquePercentage
int syncWriteTorquePercentage(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list) override
StepperDriver<reg_type>::syncWriteTorquePercentage.
Definition: stepper_driver.hpp:284
ttl_driver::StepperDriver::writeD1
int writeD1(uint8_t id, uint32_t d_1)
StepperDriver<reg_type>::writeD1.
Definition: stepper_driver.hpp:926
ttl_driver::AbstractStepperDriver
Definition: abstract_stepper_driver.hpp:34
ttl_driver::StepperDriver::syncWriteVelocityGoal
int syncWriteVelocityGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list) override
StepperDriver<reg_type>::syncWriteVelocityGoal.
Definition: stepper_driver.hpp:316
ttl_driver::StepperDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
StepperDriver<reg_type>::readMaxPosition.
Definition: stepper_driver.hpp:232
ttl_driver::StepperDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
StepperDriver<reg_type>::readMinPosition.
Definition: stepper_driver.hpp:220
ttl_driver::StepperDriver::syncReadHomingStatus
int syncReadHomingStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list) override
StepperDriver<reg_type>::syncReadHomingStatus.
Definition: stepper_driver.hpp:796
ttl_driver::StepperDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
StepperDriver<reg_type>::readPosition.
Definition: stepper_driver.hpp:331
ttl_driver::StepperDriver::syncWriteHomingAbsPosition
int syncWriteHomingAbsPosition(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position) override
StepperDriver<reg_type>::syncWriteHomingAbsPosition.
Definition: stepper_driver.hpp:824
ttl_driver::StepperDriver::syncReadTemperature
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
StepperDriver<reg_type>::syncReadTemperature.
Definition: stepper_driver.hpp:479
ttl_driver::StepperDriver::str
std::string str() const override
StepperDriver<reg_type>::str.
Definition: stepper_driver.hpp:146
ttl_driver::StepperDriver::writeV1
int writeV1(uint8_t id, uint32_t v_1)
StepperDriver<reg_type>::writeV1.
Definition: stepper_driver.hpp:878
ttl_driver::StepperDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &operating_mode) override
Definition: stepper_driver.hpp:567
ttl_driver::StepperDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
StepperDriver<reg_type>::readVelocity.
Definition: stepper_driver.hpp:343
ttl_driver::StepperDriver::syncReadVelocity
int syncReadVelocity(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list) override
StepperDriver<reg_type>::syncReadVelocity.
Definition: stepper_driver.hpp:406
ttl_driver::StepperDriver::syncReadHwErrorStatus
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
StepperDriver<reg_type>::syncReadHwErrorStatus.
Definition: stepper_driver.hpp:556
ttl_driver::StepperDriver::writeVelocityProfile
int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data_list) override
StepperDriver<reg_type>::writeVelocityProfile.
Definition: stepper_driver.hpp:622
ttl_driver::StepperDriver::syncReadHomingAbsPosition
int syncReadHomingAbsPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position) override
StepperDriver<reg_type>::syncReadHomingAbsPosition.
Definition: stepper_driver.hpp:838
ttl_driver::StepperDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
StepperDriver<reg_type>::readHwErrorStatus.
Definition: stepper_driver.hpp:382
ttl_driver::StepperDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_enable) override
StepperDriver<reg_type>::writeTorquePercentage.
Definition: stepper_driver.hpp:246
ttl_driver::StepperDriver::startHoming
int startHoming(uint8_t id) override
StepperDriver<reg_type>::startHoming.
Definition: stepper_driver.hpp:735
ttl_driver::StepperDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t operating_mode)
Definition: stepper_driver.hpp:573


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