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, std::vector<std::pair<double, uint8_t>> &data_list) override;
60 
61  int syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list) override;
62 
63  public:
64  // AbstractMotorDriver interface : we cannot define them globally in AbstractMotorDriver
65  // as it is needed here for polymorphism (AbstractMotorDriver cannot be a template class and does not
66  // have access to reg_type). So it seems like a duplicate of DxlDriver
67 
68  int changeId(uint8_t id, uint8_t new_id) override;
69 
70  int readMinPosition(uint8_t id, uint32_t &min_pos) override;
71  int readMaxPosition(uint8_t id, uint32_t &max_pos) override;
72 
73  int writeTorquePercentage(uint8_t id, uint8_t torque_enable) 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, const std::vector<uint8_t> &torque_percentage_list) override;
78  int syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list) override;
79  int syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list) override;
80 
81  // ram read
82  int readPosition(uint8_t id, uint32_t &present_position) override;
83  int readVelocity(uint8_t id, uint32_t &present_velocity) override;
84 
85  int syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list) override;
86  int syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list) override;
87  int syncReadJointStatus(const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2>> &data_array_list) override;
88 
89  // AbstractStepperDriver interface
90  public:
91  int readControlMode(uint8_t id, uint8_t &operating_mode) override;
92  int writeControlMode(uint8_t id, uint8_t operating_mode);
93 
94  int readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list) override;
95  int writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list) override;
96 
97  int startHoming(uint8_t id) override;
98  int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) override;
99 
100  int readHomingStatus(uint8_t id, uint8_t &status) override;
101  int syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list) override;
102 
103  int readFirmwareRunning(uint8_t id, bool &is_running) override;
104 
105  int syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position) override;
106  int syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position) override;
107 
108  float velocityUnit() const;
109 
110  private:
111  int writeVStart(uint8_t id, uint32_t v_start);
112  int writeA1(uint8_t id, uint32_t a_1);
113  int writeV1(uint8_t id, uint32_t v_1);
114  int writeAMax(uint8_t id, uint32_t a_max);
115  int writeVMax(uint8_t id, uint32_t v_max);
116  int writeDMax(uint8_t id, uint32_t d_max);
117  int writeD1(uint8_t id, uint32_t d_1);
118  int writeVStop(uint8_t id, uint32_t v_stop);
119  };
120 
121  // definition of methods
122 
126  template <typename reg_type>
127  StepperDriver<reg_type>::StepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
128  std::shared_ptr<dynamixel::PacketHandler> packetHandler) : AbstractStepperDriver(std::move(portHandler),
129  std::move(packetHandler))
130  {
131  }
132 
133  //*****************************
134  // AbstractMotorDriver interface
135  //*****************************
136 
141  template <typename reg_type>
142  std::string StepperDriver<reg_type>::str() const
143  {
144  return common::model::HardwareTypeEnum(reg_type::motor_type).toString() + " : " + AbstractStepperDriver::str();
145  }
146 
153  template <typename reg_type>
154  int StepperDriver<reg_type>::changeId(uint8_t id, uint8_t new_id)
155  {
156  // TODO(THUC) verify that COMM_RX_TIMEOUT error code do not impact on data sent to motor
157  // when COMM_RX_TIMEOUT error, id changed also, so we consider that change id successfully
158  int res = write<typename reg_type::TYPE_ID>(reg_type::ADDR_ID, id, new_id);
159  if (res == COMM_RX_TIMEOUT)
160  res = COMM_SUCCESS;
161  return res;
162  }
163 
173  template <typename reg_type>
174  int StepperDriver<reg_type>::checkModelNumber(uint8_t id, uint16_t& model_number)
175  {
176  int ping_result = getModelNumber(id, model_number);
177 
178  if (ping_result == COMM_SUCCESS && model_number != 0)
179  {
180  // Use the validator from register definition to check compatibility
181  auto validator = reg_type::createModelNumberValidator();
182  if (!validator->isValid(model_number))
183  {
184  ROS_WARN("StepperDriver: Model number %u not valid for %s (expected %s)",
185  model_number,
186  common::model::HardwareTypeEnum(reg_type::motor_type).toString().c_str(),
187  validator->describe().c_str());
188  return PING_WRONG_MODEL_NUMBER;
189  }
190  }
191 
192  return ping_result;
193  }
194 
201  template <typename reg_type>
202  int StepperDriver<reg_type>::readFirmwareVersion(uint8_t id, std::string &version)
203  {
204  int res = 0;
205  uint32_t data{};
206  res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id, data);
207  version = interpretFirmwareVersion(data);
208  return res;
209  }
210 
217  template <typename reg_type>
218  int StepperDriver<reg_type>::readMinPosition(uint8_t id, uint32_t &pos)
219  {
220  return read<typename reg_type::TYPE_MIN_POSITION_LIMIT>(reg_type::ADDR_MIN_POSITION_LIMIT, id, pos);
221  }
222 
229  template <typename reg_type>
230  int StepperDriver<reg_type>::readMaxPosition(uint8_t id, uint32_t &pos)
231  {
232  return read<typename reg_type::TYPE_MAX_POSITION_LIMIT>(reg_type::ADDR_MAX_POSITION_LIMIT, id, pos);
233  }
234 
235  // ram write
236 
243  template <typename reg_type>
244  int StepperDriver<reg_type>::writeTorquePercentage(uint8_t id, uint8_t torque_percentage)
245  {
246  auto torque_enable = torque_percentage > 0 ? 1 : 0;
247  return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id, torque_enable);
248  }
249 
256  template <typename reg_type>
257  int StepperDriver<reg_type>::writePositionGoal(uint8_t id, uint32_t position)
258  {
259  return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id, position);
260  }
261 
262  // according to the registers, the data should be an int32_t ?
269  template <typename reg_type>
270  int StepperDriver<reg_type>::writeVelocityGoal(uint8_t id, uint32_t velocity)
271  {
272  return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id, velocity);
273  }
274 
281  template <typename reg_type>
282  int StepperDriver<reg_type>::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &torque_percentage_list)
283  {
284  std::vector<uint8_t> torque_enable_list;
285  for(const auto &torque_percentage : torque_percentage_list)
286  {
287  auto torque_enable = torque_percentage > 0 ? 1 : 0;
288  torque_enable_list.push_back(torque_enable);
289  }
290  return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list, torque_enable_list);
291  }
292 
299  template <typename reg_type>
300  int StepperDriver<reg_type>::syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list)
301  {
302  return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
303  }
304 
311  template <typename reg_type>
312  int StepperDriver<reg_type>::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list)
313  {
314  return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
315  }
316 
317  // ram read
318 
325  template <typename reg_type>
326  int StepperDriver<reg_type>::readPosition(uint8_t id, uint32_t &present_position)
327  {
328  return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id, present_position);
329  }
330 
337  template <typename reg_type>
338  int StepperDriver<reg_type>::readVelocity(uint8_t id, uint32_t &present_velocity)
339  {
340  return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id, present_velocity);
341  }
342 
349  template <typename reg_type>
350  int StepperDriver<reg_type>::readTemperature(uint8_t id, uint8_t &temperature)
351  {
352  return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id, temperature);
353  }
354 
361  template <typename reg_type>
362  int StepperDriver<reg_type>::readVoltage(uint8_t id, double &voltage)
363  {
364  uint16_t voltage_mV = 0;
365  int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id, voltage_mV);
366  voltage = static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
367  return res;
368  }
369 
376  template <typename reg_type>
377  int StepperDriver<reg_type>::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
378  {
379  return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id, hardware_error_status);
380  }
381 
388  template <typename reg_type>
389  int StepperDriver<reg_type>::syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
390  {
391  return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
392  }
393 
400  template <typename reg_type>
401  int StepperDriver<reg_type>::syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
402  {
403  return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
404  }
405 
413  template <typename reg_type>
414  int StepperDriver<reg_type>::syncReadJointStatus(const std::vector<uint8_t> &id_list,
415  std::vector<std::array<uint32_t, 2>> &data_array_list)
416  {
417  int res = COMM_TX_FAIL;
418 
419  if (id_list.empty())
420  return res;
421 
422  data_array_list.clear();
423 
424  // read torque enable on first id
425  typename reg_type::TYPE_TORQUE_ENABLE torque{1};
426  res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
427  if (COMM_SUCCESS != res)
428  std::cout << "#############"
429  " ERROR reading stepper torque in syncReadJointStatus (error "
430  << res << ")" << std::endl;
431 
432  // if torque on, read position and velocity
433  if (torque)
434  {
435  res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
436  }
437  else // else read position only
438  {
439  std::vector<uint32_t> position_list;
440  res = syncReadPosition(id_list, position_list);
441  for (auto p : position_list)
442  data_array_list.emplace_back(std::array<uint32_t, 2>{1, p});
443  }
444 
445  return res;
446  }
447 
454  template <typename reg_type>
455  int StepperDriver<reg_type>::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
456  {
457  int res = 0;
458  firmware_list.clear();
459  std::vector<uint32_t> data_list{};
460  res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
461  for (auto const &data : data_list)
462  firmware_list.emplace_back(interpretFirmwareVersion(data));
463  return res;
464  }
465 
472  template <typename reg_type>
473  int StepperDriver<reg_type>::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
474  {
475  return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
476  }
477 
484  template <typename reg_type>
485  int StepperDriver<reg_type>::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
486  {
487  voltage_list.clear();
488  std::vector<uint16_t> v_read;
489  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
490  for (auto const &v : v_read)
491  voltage_list.emplace_back(static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
492  return res;
493  }
494 
501  template <typename reg_type>
502  int StepperDriver<reg_type>::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
503  {
504  voltage_list.clear();
505  std::vector<uint16_t> v_read;
506  int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
507  for (auto const &v : v_read)
508  voltage_list.emplace_back(static_cast<double>(v));
509  return res;
510  }
511 
518  template <typename reg_type>
519  int StepperDriver<reg_type>::syncReadHwStatus(const std::vector<uint8_t> &id_list,
520  std::vector<std::pair<double, uint8_t>> &data_list)
521  {
522  data_list.clear();
523 
524  std::vector<std::array<uint8_t, 3>> raw_data;
525  int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
526 
527  for (auto const &data : raw_data)
528  {
529  // Voltage is first reg, uint16
530  auto v = static_cast<uint16_t>((static_cast<uint16_t>(data.at(1)) << 8) | data.at(0)); // concatenate 2 bytes
531  auto voltage = static_cast<double>(v);
532 
533  // Temperature is second reg, uint8
534  uint8_t temperature = data.at(2);
535 
536  data_list.emplace_back(std::make_pair(voltage, temperature));
537  }
538 
539  return res;
540  }
547  template <typename reg_type>
548  int StepperDriver<reg_type>::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
549  {
550  return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
551  }
552 
553  //*****************************
554  // AbstractStepperDriver interface
555  //*****************************
556 
557  template <typename reg_type>
558  int StepperDriver<reg_type>::readControlMode(uint8_t id, uint8_t &operating_mode)
559  {
560  return read<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE, id, operating_mode);
561  }
562 
563  template <typename reg_type>
564  int StepperDriver<reg_type>::writeControlMode(uint8_t id, const uint8_t operating_mode)
565  {
566  return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE, id, operating_mode);
567  }
568 
575  template <typename reg_type>
576  int StepperDriver<reg_type>::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list)
577  {
578  int res = COMM_RX_FAIL;
579  data_list.clear();
580 
581  std::vector<std::array<typename reg_type::TYPE_PROFILE, 8>> data_array_list;
582  if (COMM_SUCCESS == syncReadConsecutiveBytes<typename reg_type::TYPE_PROFILE, 8>(reg_type::ADDR_VSTART, {id}, data_array_list))
583  {
584  if (!data_array_list.empty())
585  {
586  auto block = data_array_list.at(0);
587 
588  for (auto data : block)
589  {
590  data_list.emplace_back(data);
591  }
592  }
593 
594  res = COMM_SUCCESS;
595  }
596  else
597  {
598  std::cout << "Failures during read Velocity Profile" << std::endl;
599  }
600 
601  return res;
602  }
603 
611  template <typename reg_type>
612  int StepperDriver<reg_type>::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list)
613  {
614  int tries = 10;
615  int res = COMM_RX_FAIL;
616  double wait_duration = 0.05;
617 
618  // Random positive value to activate the torque, we need this to write on other registers
619  constexpr auto ACTIVE_TORQUE_PERCENT = 1;
620  writeTorquePercentage(id, ACTIVE_TORQUE_PERCENT);
621 
622  // only rewrite the params which is not success
623  while (tries > 0) // try 10 times
624  {
625  tries--;
626  ros::Duration(wait_duration).sleep();
627  res = writeVStart(id, data_list.at(0));
628  if (res == COMM_SUCCESS)
629  break;
630  }
631  if (res != COMM_SUCCESS)
632  return res;
633 
634  tries = 10;
635  while (tries > 0) // try 10 times
636  {
637  tries--;
638  ros::Duration(wait_duration).sleep();
639  res = writeA1(id, data_list.at(1));
640  if (res == COMM_SUCCESS)
641  break;
642  }
643  if (res != COMM_SUCCESS)
644  return res;
645 
646  tries = 10;
647  while (tries > 0) // try 10 times
648  {
649  tries--;
650  ros::Duration(wait_duration).sleep();
651  res = writeV1(id, data_list.at(2));
652  if (res == COMM_SUCCESS)
653  break;
654  }
655  if (res != COMM_SUCCESS)
656  return res;
657 
658  tries = 10;
659  while (tries > 0) // try 10 times
660  {
661  tries--;
662  ros::Duration(wait_duration).sleep();
663  res = writeAMax(id, data_list.at(3));
664  if (res == COMM_SUCCESS)
665  break;
666  }
667  if (res != COMM_SUCCESS)
668  return res;
669 
670  tries = 10;
671  while (tries > 0) // try 10 times
672  {
673  tries--;
674  ros::Duration(wait_duration).sleep();
675  res = writeVMax(id, data_list.at(4));
676  if (res == COMM_SUCCESS)
677  break;
678  }
679  if (res != COMM_SUCCESS)
680  return res;
681 
682  tries = 10;
683  while (tries > 0) // try 10 times
684  {
685  tries--;
686  ros::Duration(wait_duration).sleep();
687  res = writeDMax(id, data_list.at(5));
688  if (res == COMM_SUCCESS)
689  break;
690  }
691  if (res != COMM_SUCCESS)
692  return res;
693 
694  tries = 10;
695  while (tries > 0) // try 10 times
696  {
697  tries--;
698  ros::Duration(wait_duration).sleep();
699  res = writeD1(id, data_list.at(6));
700  if (res == COMM_SUCCESS)
701  break;
702  }
703  if (res != COMM_SUCCESS)
704  return res;
705 
706  tries = 10;
707  while (tries > 0) // try 10 times
708  {
709  tries--;
710  ros::Duration(wait_duration).sleep();
711  res = writeVStop(id, data_list.at(7));
712  if (res == COMM_SUCCESS)
713  break;
714  }
715 
716  return res;
717  }
718 
724  template <typename reg_type>
726  {
727  return write<typename reg_type::TYPE_COMMAND>(reg_type::ADDR_COMMAND, id, 0);
728  }
729 
738  template <typename reg_type>
739  int StepperDriver<reg_type>::writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)
740  {
741  int res = 0;
742  double wait_duration = 0.05;
743 
744  // Random positive value to activate the torque, we need this to write on other registers
745  constexpr auto ACTIVE_TORQUE_PERCENT = 1;
746  writeTorquePercentage(id, ACTIVE_TORQUE_PERCENT);
747  ros::Duration(wait_duration).sleep();
748 
749  if (COMM_SUCCESS != write<typename reg_type::TYPE_HOMING_DIRECTION>(reg_type::ADDR_HOMING_DIRECTION, id, direction))
750  res++;
751  ros::Duration(wait_duration).sleep();
752 
753  // if (COMM_SUCCESS != write<typename reg_type::TYPE_HOMING_STALL_THRESHOLD>(reg_type::ADDR_HOMING_STALL_THRESHOLD, id, stall_threshold))
754  // res++;
755  // ros::Duration(wait_duration).sleep();
756 
757  if (res > 0)
758  {
759  std::cout << "Failures during writeVelocityProfile : " << res << std::endl;
760  return COMM_TX_FAIL;
761  }
762 
763  return COMM_SUCCESS;
764  }
765 
772  template <typename reg_type>
773  int StepperDriver<reg_type>::readHomingStatus(uint8_t id, uint8_t &status)
774  {
775  return read<typename reg_type::TYPE_HOMING_STATUS>(reg_type::ADDR_HOMING_STATUS, id, status);
776  }
777 
784  template <typename reg_type>
785  int StepperDriver<reg_type>::syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list)
786  {
787  return syncRead<typename reg_type::TYPE_HOMING_STATUS>(reg_type::ADDR_HOMING_STATUS, id_list, status_list);
788  }
789 
796  template <typename reg_type>
797  int StepperDriver<reg_type>::readFirmwareRunning(uint8_t id, bool &is_running)
798  {
799  typename reg_type::TYPE_FIRMWARE_RUNNING data{};
800  int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING, id, data);
801  is_running = data;
802  return res;
803  }
804 
811  template <typename reg_type>
812  int StepperDriver<reg_type>::syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position)
813  {
814  return syncWrite<typename reg_type::TYPE_HOMING_ABS_POSITION>(reg_type::ADDR_HOMING_ABS_POSITION, id_list, abs_position);
815  }
816 
823  template <typename reg_type>
824  int StepperDriver<reg_type>::syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position)
825  {
826  return syncRead<typename reg_type::TYPE_HOMING_ABS_POSITION>(reg_type::ADDR_HOMING_ABS_POSITION, id_list, abs_position);
827  }
828 
829  // private
830 
837  template <typename reg_type>
838  int StepperDriver<reg_type>::writeVStart(uint8_t id, uint32_t v_start)
839  {
840  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VSTART, id, v_start);
841  }
842 
849  template <typename reg_type>
850  int StepperDriver<reg_type>::writeA1(uint8_t id, uint32_t a_1)
851  {
852  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_A1, id, a_1);
853  }
854 
861  template <typename reg_type>
862  int StepperDriver<reg_type>::writeV1(uint8_t id, uint32_t v_1)
863  {
864  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_V1, id, v_1);
865  }
866 
873  template <typename reg_type>
874  int StepperDriver<reg_type>::writeAMax(uint8_t id, uint32_t a_max)
875  {
876  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_AMAX, id, a_max);
877  }
878 
885  template <typename reg_type>
886  int StepperDriver<reg_type>::writeVMax(uint8_t id, uint32_t v_max)
887  {
888  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VMAX, id, v_max);
889  }
890 
897  template <typename reg_type>
898  int StepperDriver<reg_type>::writeDMax(uint8_t id, uint32_t d_max)
899  {
900  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_DMAX, id, d_max);
901  }
902 
909  template <typename reg_type>
910  int StepperDriver<reg_type>::writeD1(uint8_t id, uint32_t d_1)
911  {
912  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_D1, id, d_1);
913  }
914 
921  template <typename reg_type>
922  int StepperDriver<reg_type>::writeVStop(uint8_t id, uint32_t v_stop)
923  {
924  return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VSTOP, id, v_stop);
925  }
926 
927  template <typename reg_type>
929  {
930  return reg_type::VELOCITY_UNIT;
931  }
932 
933 } // ttl_driver
934 
935 #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:389
ttl_driver::StepperDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
StepperDriver<reg_type>::readTemperature.
Definition: stepper_driver.hpp:350
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:502
ttl_driver::AbstractStepperDriver::str
std::string str() const override
AbstractStepperDriver::str.
Definition: abstract_stepper_driver.cpp:48
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:485
ttl_driver::StepperDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
StepperDriver<reg_type>::writeVelocityGoal.
Definition: stepper_driver.hpp:270
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:127
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:300
ttl_driver::StepperDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
StepperDriver<reg_type>::readVoltage.
Definition: stepper_driver.hpp:362
ttl_driver::StepperDriver::writeVMax
int writeVMax(uint8_t id, uint32_t v_max)
StepperDriver<reg_type>::writeVMax.
Definition: stepper_driver.hpp:886
ttl_driver::StepperDriver::writeAMax
int writeAMax(uint8_t id, uint32_t a_max)
StepperDriver<reg_type>::writeAMax.
Definition: stepper_driver.hpp:874
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:414
stepper_reg.hpp
ttl_driver::StepperDriver::writeVStop
int writeVStop(uint8_t id, uint32_t v_stop)
StepperDriver<reg_type>::writeVStop.
Definition: stepper_driver.hpp:922
ttl_driver::StepperDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
StepperDriver<reg_type>::checkModelNumber.
Definition: stepper_driver.hpp:174
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:739
ttl_driver::StepperDriver::writeVStart
int writeVStart(uint8_t id, uint32_t v_start)
StepperDriver<reg_type>::writeVStart.
Definition: stepper_driver.hpp:838
ttl_driver::StepperDriver::writeDMax
int writeDMax(uint8_t id, uint32_t d_max)
StepperDriver<reg_type>::writeDMax.
Definition: stepper_driver.hpp:898
ttl_driver::StepperDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
StepperDriver<reg_type>::writePositionGoal.
Definition: stepper_driver.hpp:257
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:202
ttl_driver::StepperDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
StepperDriver<reg_type>::changeId.
Definition: stepper_driver.hpp:154
ttl_driver::StepperDriver::readHomingStatus
int readHomingStatus(uint8_t id, uint8_t &status) override
StepperDriver<reg_type>::readHomingStatus.
Definition: stepper_driver.hpp:773
ttl_driver::StepperDriver::writeA1
int writeA1(uint8_t id, uint32_t a_1)
StepperDriver<reg_type>::writeA1.
Definition: stepper_driver.hpp:850
ttl_driver::StepperDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
StepperDriver::readVelocityProfile.
Definition: stepper_driver.hpp:576
ttl_driver::StepperDriver::velocityUnit
float velocityUnit() const
writeVelocityGoal: define the unit of the velocity in RPM
Definition: stepper_driver.hpp:928
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:455
ttl_driver::StepperDriver::readFirmwareRunning
int readFirmwareRunning(uint8_t id, bool &is_running) override
StepperDriver<reg_type>::readFirmwareRunning.
Definition: stepper_driver.hpp:797
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:519
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:282
ttl_driver::StepperDriver::writeD1
int writeD1(uint8_t id, uint32_t d_1)
StepperDriver<reg_type>::writeD1.
Definition: stepper_driver.hpp:910
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:312
ttl_driver::StepperDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
StepperDriver<reg_type>::readMaxPosition.
Definition: stepper_driver.hpp:230
ttl_driver::StepperDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
StepperDriver<reg_type>::readMinPosition.
Definition: stepper_driver.hpp:218
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:785
ttl_driver::StepperDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
StepperDriver<reg_type>::readPosition.
Definition: stepper_driver.hpp:326
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:812
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:473
ttl_driver::StepperDriver::str
std::string str() const override
StepperDriver<reg_type>::str.
Definition: stepper_driver.hpp:142
ttl_driver::StepperDriver::writeV1
int writeV1(uint8_t id, uint32_t v_1)
StepperDriver<reg_type>::writeV1.
Definition: stepper_driver.hpp:862
ttl_driver::StepperDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &operating_mode) override
Definition: stepper_driver.hpp:558
ttl_driver::StepperDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
StepperDriver<reg_type>::readVelocity.
Definition: stepper_driver.hpp:338
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:401
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:548
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:612
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:824
ttl_driver::StepperDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
StepperDriver<reg_type>::readHwErrorStatus.
Definition: stepper_driver.hpp:377
ttl_driver::StepperDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_enable) override
StepperDriver<reg_type>::writeTorquePercentage.
Definition: stepper_driver.hpp:244
ttl_driver::StepperDriver::startHoming
int startHoming(uint8_t id) override
StepperDriver<reg_type>::startHoming.
Definition: stepper_driver.hpp:725
ttl_driver::StepperDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t operating_mode)
Definition: stepper_driver.hpp:564


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