mock_stepper_driver.cpp
Go to the documentation of this file.
1 /*
2 mock_dxl_driver.cpp
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 
18 #include "dynamixel_sdk/packet_handler.h"
19 #include <algorithm>
20 #include <cstdint>
21 #include <cstdio>
22 #include <map>
23 #include <memory>
24 #include <ros/ros.h>
25 #include <set>
26 #include <string>
27 #include <type_traits>
28 #include <utility>
29 #include <vector>
30 
31 namespace ttl_driver
32 {
33 // definition of methods
34 
39 MockStepperDriver::MockStepperDriver(std::shared_ptr<FakeTtlData> data) : _fake_data(std::move(data)) { init(); }
40 
46 {
47  bool res = false;
48 
49  if (_fake_data)
50  {
51  // retrieve list of ids
52  for (auto const &imap : _fake_data->stepper_registers)
53  _id_list.emplace_back(imap.first);
54 
55  res = true;
56  }
57  else
58  {
59  std::cout << "ERROR : Fake data not initialized" << std::endl;
60  }
61 
62  return res;
63 }
68 std::string MockStepperDriver::str() const { return "Mock Stepper Driver (OK)"; }
69 
70 //*****************************
71 // AbstractTtlDriver interface
72 //*****************************
78 int MockStepperDriver::ping(uint8_t id)
79 {
80  if (std::find(_fake_data->full_id_list.begin(), _fake_data->full_id_list.end(), id) != _fake_data->full_id_list.end())
81  return COMM_SUCCESS;
82  return COMM_TX_FAIL;
83 }
84 
91 int MockStepperDriver::getModelNumber(uint8_t id, uint16_t &model_number)
92 {
93  if (_fake_data->stepper_registers.count(id))
94  model_number = _fake_data->stepper_registers.at(id).model_number;
95  return COMM_SUCCESS;
96 }
97 
103 int MockStepperDriver::checkModelNumber(uint8_t id, uint16_t& model_number)
104 {
105  int ping_result = getModelNumber(id, model_number);
106 
107  return ping_result;
108 }
109 
115 int MockStepperDriver::scan(std::vector<uint8_t> &id_list)
116 {
117  // full id list using only for scan
118  id_list = _fake_data->full_id_list;
119  return COMM_SUCCESS;
120 }
121 
127 int MockStepperDriver::reboot(uint8_t id) { return ping(id); }
128 
135 int MockStepperDriver::changeId(uint8_t id, uint8_t new_id)
136 {
137  int result = COMM_TX_FAIL;
138  if (std::find(_id_list.begin(), _id_list.end(), id) != _id_list.end() &&
139  std::find(_fake_data->full_id_list.begin(), _fake_data->full_id_list.end(), id) != _fake_data->full_id_list.end())
140  {
141  _id_list.erase(std::remove(_id_list.begin(), _id_list.end(), id), _id_list.end());
142  _fake_data->full_id_list.erase(std::remove(_fake_data->full_id_list.begin(), _fake_data->full_id_list.end(), id), _fake_data->full_id_list.end());
143  _id_list.emplace_back(new_id);
144  _fake_data->full_id_list.emplace_back(new_id);
145 
146  result = COMM_SUCCESS;
147  }
148 
149  const auto it = _fake_data->stepper_registers.find(id);
150  if (it != _fake_data->stepper_registers.end())
151  {
152  std::swap(_fake_data->stepper_registers[new_id], it->second);
153  result = COMM_SUCCESS;
154  }
155  else
156  result = COMM_TX_FAIL;
157 
158  return result;
159 }
160 
167 int MockStepperDriver::readFirmwareVersion(uint8_t id, std::string &version)
168 {
169  if (_fake_data->stepper_registers.count(id))
170  version = _fake_data->stepper_registers.at(id).firmware;
171  else
172  return COMM_RX_FAIL;
173  return COMM_SUCCESS;
174 }
175 
182 int MockStepperDriver::readMinPosition(uint8_t id, uint32_t &pos)
183 {
184  if (_fake_data->stepper_registers.count(id))
185  pos = _fake_data->stepper_registers.at(id).min_position;
186  else
187  return COMM_RX_FAIL;
188  return COMM_SUCCESS;
189 }
190 
197 int MockStepperDriver::readMaxPosition(uint8_t id, uint32_t &pos)
198 {
199  if (_fake_data->stepper_registers.count(id))
200  pos = _fake_data->stepper_registers.at(id).max_position;
201  else
202  return COMM_RX_FAIL;
203  return COMM_SUCCESS;
204 }
205 
206 // ram write
207 
214 int MockStepperDriver::writeTorquePercentage(uint8_t id, uint8_t /*torque_percentage*/)
215 {
216  if (COMM_SUCCESS != ping(id))
217  return COMM_RX_FAIL;
218 
219  return COMM_SUCCESS;
220 }
221 
228 int MockStepperDriver::writePositionGoal(uint8_t id, uint32_t position)
229 {
230  if (_fake_data->stepper_registers.count(id))
231  _fake_data->stepper_registers.at(id).position = position;
232  else
233  return COMM_RX_FAIL;
234  return COMM_SUCCESS;
235 }
236 
237 // according to the registers, the data should be an int32_t ?
244 int MockStepperDriver::writeVelocityGoal(uint8_t id, uint32_t velocity)
245 {
246  if (_fake_data->stepper_registers.count(id))
247  _fake_data->stepper_registers.at(id).velocity = velocity;
248  else
249  return COMM_RX_FAIL;
250  return COMM_SUCCESS;
251 }
252 
259 int MockStepperDriver::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> & /*torque_percentage_list*/)
260 {
261  // Create a map to store the frequency of each element in vector
262  std::set<uint8_t> countSet;
263 
264  // Iterate over the vector and store the frequency of each element in map
265  for (auto &id : id_list)
266  {
267  auto result = countSet.insert(id);
268  if (!result.second)
269  return GROUP_SYNC_REDONDANT_ID; // redondant id
270  }
271  return COMM_SUCCESS;
272 }
273 
280 int MockStepperDriver::syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list)
281 {
282  if (id_list.size() != position_list.size())
283  return LEN_ID_DATA_NOT_SAME;
284 
285  // Create a map to store the frequency of each element in vector
286  std::set<uint8_t> countSet;
287 
288  for (size_t i = 0; i < id_list.size(); ++i)
289  {
290  if (_fake_data->dxl_registers.count(id_list.at(i)))
291  _fake_data->dxl_registers.at(id_list.at(i)).position = position_list.at(i);
292  else if (_fake_data->stepper_registers.count(id_list.at(i)))
293  _fake_data->stepper_registers.at(id_list.at(i)).position = position_list.at(i);
294  else
295  return COMM_TX_ERROR;
296 
297  auto result = countSet.insert(id_list.at(i));
298  if (!result.second)
299  return GROUP_SYNC_REDONDANT_ID; // redondant id
300  }
301  return COMM_SUCCESS;
302 }
303 
310 int MockStepperDriver::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> & /*velocity_list*/)
311 {
312  // Create a map to store the frequency of each element in vector
313  std::set<uint8_t> countSet;
314 
315  // Iterate over the vector and store the frequency of each element in map
316  for (auto &id : id_list)
317  {
318  auto result = countSet.insert(id);
319  if (!result.second)
320  return GROUP_SYNC_REDONDANT_ID; // redondant id
321  }
322  return COMM_SUCCESS;
323 }
324 
325 // ram read
326 
333 int MockStepperDriver::readPosition(uint8_t id, uint32_t &present_position)
334 {
335  if (_fake_data->stepper_registers.count(id))
336  present_position = _fake_data->stepper_registers.at(id).position;
337  else
338  return COMM_RX_FAIL;
339  return COMM_SUCCESS;
340 }
341 
348 int MockStepperDriver::readVelocity(uint8_t id, uint32_t &present_velocity)
349 {
350  if (_fake_data->stepper_registers.count(id))
351  present_velocity = _fake_data->stepper_registers.at(id).velocity;
352  return COMM_SUCCESS;
353 }
354 
361 int MockStepperDriver::readTemperature(uint8_t id, uint8_t &temperature)
362 {
363  if (_fake_data->stepper_registers.count(id))
364  temperature = _fake_data->stepper_registers.at(id).temperature;
365  else
366  return COMM_RX_FAIL;
367  return COMM_SUCCESS;
368 }
369 
376 int MockStepperDriver::readVoltage(uint8_t id, double &voltage)
377 {
378  if (_fake_data->stepper_registers.count(id))
379  voltage = _fake_data->stepper_registers.at(id).voltage;
380  else
381  return COMM_RX_FAIL;
382  return COMM_SUCCESS;
383 }
384 
391 int MockStepperDriver::readHwErrorStatus(uint8_t /*id*/, uint8_t &hardware_error_status)
392 {
393  hardware_error_status = 0;
394  return COMM_SUCCESS;
395 }
396 
403 int MockStepperDriver::syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
404 {
405  std::set<uint8_t> countSet;
406 
407  position_list.clear();
408  for (auto &id : id_list)
409  {
410  if (_fake_data->dxl_registers.count(id))
411  position_list.emplace_back(_fake_data->dxl_registers.at(id).position);
412  else if (_fake_data->stepper_registers.count(id))
413  position_list.emplace_back(_fake_data->stepper_registers.at(id).position);
414  else
415  return COMM_RX_FAIL;
416 
417  auto result = countSet.insert(id);
418  if (!result.second)
419  return GROUP_SYNC_REDONDANT_ID; // redondant id
420  }
421  return COMM_SUCCESS;
422 }
423 
430 int MockStepperDriver::syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
431 {
432  std::set<uint8_t> countSet;
433 
434  velocity_list.clear();
435  for (auto &id : id_list)
436  {
437  if (_fake_data->dxl_registers.count(id))
438  velocity_list.emplace_back(_fake_data->dxl_registers.at(id).velocity);
439  else if (_fake_data->stepper_registers.count(id))
440  velocity_list.emplace_back(_fake_data->stepper_registers.at(id).velocity);
441  else
442  return COMM_RX_FAIL;
443 
444  auto result = countSet.insert(id);
445  if (!result.second)
446  return GROUP_SYNC_REDONDANT_ID; // redondant id
447  }
448  return COMM_SUCCESS;
449 }
450 
457 int MockStepperDriver::syncReadJointStatus(const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2>> &data_array_list)
458 {
459  std::set<uint8_t> countSet;
460 
461  data_array_list.clear();
462  for (auto &id : id_list)
463  {
464  if (_fake_data->stepper_registers.count(id))
465  {
466  std::array<uint32_t, 2> blocks{};
467 
468  blocks.at(0) = _fake_data->stepper_registers.at(id).velocity;
469  blocks.at(1) = _fake_data->stepper_registers.at(id).position;
470 
471  data_array_list.emplace_back(blocks);
472  }
473  else if (_fake_data->dxl_registers.count(id))
474  {
475  std::array<uint32_t, 2> blocks{};
476 
477  blocks.at(0) = _fake_data->dxl_registers.at(id).velocity;
478  blocks.at(1) = _fake_data->dxl_registers.at(id).position;
479 
480  data_array_list.emplace_back(blocks);
481  }
482  else
483  return COMM_RX_FAIL;
484 
485  auto result = countSet.insert(id);
486  if (!result.second)
487  return GROUP_SYNC_REDONDANT_ID; // redondant id
488  }
489  return COMM_SUCCESS;
490 }
491 
498 int MockStepperDriver::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
499 {
500  std::set<uint8_t> countSet;
501 
502  firmware_list.clear();
503  for (auto &id : id_list)
504  {
505  if (_fake_data->dxl_registers.count(id))
506  firmware_list.emplace_back(_fake_data->dxl_registers.at(id).firmware);
507  else if (_fake_data->stepper_registers.count(id))
508  firmware_list.emplace_back(_fake_data->stepper_registers.at(id).firmware);
509  else
510  return COMM_RX_FAIL;
511 
512  auto result = countSet.insert(id);
513  if (!result.second)
514  return GROUP_SYNC_REDONDANT_ID; // redondant id
515  }
516  return COMM_SUCCESS;
517 }
518 
525 int MockStepperDriver::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
526 {
527  std::set<uint8_t> countSet;
528 
529  temperature_list.clear();
530  for (auto &id : id_list)
531  {
532  if (_fake_data->dxl_registers.count(id))
533  temperature_list.emplace_back(_fake_data->dxl_registers.at(id).temperature);
534  else if (_fake_data->stepper_registers.count(id))
535  temperature_list.emplace_back(_fake_data->stepper_registers.at(id).temperature);
536  else if (_fake_data->end_effector.id == id)
537  temperature_list.emplace_back(_fake_data->end_effector.temperature);
538  else
539  return COMM_RX_FAIL;
540 
541  auto result = countSet.insert(id);
542  if (!result.second)
543  return GROUP_SYNC_REDONDANT_ID; // redondant id
544  }
545  return COMM_SUCCESS;
546 }
547 
554 int MockStepperDriver::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
555 {
556  std::set<uint8_t> countSet;
557 
558  voltage_list.clear();
559  for (auto &id : id_list)
560  {
561  if (_fake_data->dxl_registers.count(id))
562  voltage_list.emplace_back(_fake_data->dxl_registers.at(id).voltage / 10);
563  else if (_fake_data->stepper_registers.count(id))
564  voltage_list.emplace_back(_fake_data->stepper_registers.at(id).voltage / 1000);
565  else if (_fake_data->end_effector.id == id)
566  voltage_list.emplace_back(_fake_data->end_effector.voltage / 1000);
567  else
568  return COMM_RX_FAIL;
569 
570  auto result = countSet.insert(id);
571  if (!result.second)
572  return GROUP_SYNC_REDONDANT_ID; // redondant id
573  }
574  return COMM_SUCCESS;
575 }
576 
583 int MockStepperDriver::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
584 {
585  std::set<uint8_t> countSet;
586 
587  voltage_list.clear();
588  for (auto &id : id_list)
589  {
590  if (_fake_data->dxl_registers.count(id))
591  voltage_list.emplace_back(_fake_data->dxl_registers.at(id).voltage);
592  else if (_fake_data->stepper_registers.count(id))
593  voltage_list.emplace_back(_fake_data->stepper_registers.at(id).voltage);
594  else if (_fake_data->end_effector.id == id)
595  voltage_list.emplace_back(_fake_data->end_effector.voltage);
596  else
597  return COMM_RX_FAIL;
598 
599  auto result = countSet.insert(id);
600  if (!result.second)
601  return GROUP_SYNC_REDONDANT_ID; // redondant id
602  }
603  return COMM_SUCCESS;
604 }
605 
612 int MockStepperDriver::syncReadHwStatus(const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list)
613 {
614  data_list.clear();
615 
616  std::set<uint8_t> countSet;
617 
618  for (auto &id : id_list)
619  {
620  if (_fake_data->dxl_registers.count(id))
621  {
622  double voltage = _fake_data->dxl_registers.at(id).voltage;
623  uint8_t temperature = _fake_data->dxl_registers.at(id).temperature;
624  data_list.emplace_back(std::make_pair(voltage, temperature));
625  }
626  else if (_fake_data->stepper_registers.count(id))
627  {
628  double voltage = _fake_data->stepper_registers.at(id).voltage;
629  uint8_t temperature = _fake_data->stepper_registers.at(id).temperature;
630  data_list.emplace_back(std::make_pair(voltage, temperature));
631  }
632  else if (_fake_data->end_effector.id == id)
633  {
634  double voltage = _fake_data->end_effector.voltage;
635  uint8_t temperature = _fake_data->end_effector.temperature;
636  data_list.emplace_back(std::make_pair(voltage, temperature));
637  }
638  else
639  return COMM_RX_FAIL;
640 
641  auto result = countSet.insert(id);
642  if (!result.second)
643  return GROUP_SYNC_REDONDANT_ID; // redondant id
644  }
645  return COMM_SUCCESS;
646 }
647 
654 int MockStepperDriver::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
655 {
656  std::set<uint8_t> countSet;
657 
658  hw_error_list.clear();
659  for (auto &id : id_list)
660  {
661  hw_error_list.emplace_back(0);
662  auto result = countSet.insert(id);
663  if (!result.second)
664  return GROUP_SYNC_REDONDANT_ID; // redondant id
665  }
666  return COMM_SUCCESS;
667 }
668 
669 //*****************************
670 // AbstractStepperDriver interface
671 //*****************************
672 
673 int MockStepperDriver::readControlMode(uint8_t id, uint8_t &mode)
674 {
675  if (_fake_data->stepper_registers.count(id))
676  mode = _fake_data->stepper_registers.at(id).operating_mode;
677  else
678  return COMM_RX_FAIL;
679  return COMM_SUCCESS;
680 }
681 
682 int MockStepperDriver::writeControlMode(uint8_t id, uint8_t mode)
683 {
684  if (_fake_data->stepper_registers.count(id))
685  _fake_data->stepper_registers.at(id).operating_mode = mode;
686  else
687  return COMM_RX_FAIL;
688  return COMM_SUCCESS;
689 }
690 
697 int MockStepperDriver::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data)
698 {
699  int result = COMM_RX_FAIL;
700 
701  data.clear();
702  if (_fake_data->stepper_registers.count(id))
703  {
704  data.emplace_back(_fake_data->stepper_registers.at(id).v_start);
705  data.emplace_back(_fake_data->stepper_registers.at(id).a_1);
706  data.emplace_back(_fake_data->stepper_registers.at(id).v_1);
707  data.emplace_back(_fake_data->stepper_registers.at(id).a_max);
708  data.emplace_back(_fake_data->stepper_registers.at(id).v_max);
709  data.emplace_back(_fake_data->stepper_registers.at(id).d_max);
710  data.emplace_back(_fake_data->stepper_registers.at(id).d_1);
711  data.emplace_back(_fake_data->stepper_registers.at(id).v_stop);
712 
713  result = COMM_SUCCESS;
714  }
715 
716  return result;
717 }
718 
725 int MockStepperDriver::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data)
726 {
727  int result = COMM_RX_FAIL;
728 
729  if (_fake_data->stepper_registers.count(id))
730  {
731  _fake_data->stepper_registers.at(id).v_start = data.at(0);
732  _fake_data->stepper_registers.at(id).a_1 = data.at(1);
733  _fake_data->stepper_registers.at(id).v_1 = data.at(2);
734  _fake_data->stepper_registers.at(id).a_max = data.at(3);
735  _fake_data->stepper_registers.at(id).v_max = data.at(4);
736  _fake_data->stepper_registers.at(id).d_max = data.at(5);
737  _fake_data->stepper_registers.at(id).d_1 = data.at(6);
738  _fake_data->stepper_registers.at(id).v_stop = data.at(7);
739 
740  result = COMM_SUCCESS;
741  }
742 
743  return result;
744 }
745 
752 {
753  if (COMM_SUCCESS != ping(id))
754  return COMM_RX_FAIL;
755 
757  _fake_time = 2;
758  return COMM_SUCCESS;
759 }
760 
768 int MockStepperDriver::writeHomingSetup(uint8_t id, uint8_t /*direction*/, uint8_t /*stall_threshold*/) { return ping(id); }
769 
776 int MockStepperDriver::readHomingStatus(uint8_t id, uint8_t &status)
777 {
778  if (COMM_SUCCESS != ping(id))
779  return COMM_RX_FAIL;
780 
781  if (_fake_time)
782  {
783  _fake_time--;
784  }
785  else
787 
788  status = _calibration_status;
789  return COMM_SUCCESS;
790 }
791 
798 int MockStepperDriver::syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list)
799 {
800  if (_fake_time)
801  {
802  _fake_time--;
803  }
804  else // when calibration finished or at startup
806 
807  std::set<uint8_t> countSet;
808 
809  status_list.clear();
810  for (auto &id : id_list)
811  {
812  status_list.emplace_back(_calibration_status);
813  auto result = countSet.insert(id);
814  if (!result.second)
815  return GROUP_SYNC_REDONDANT_ID; // redondant id
816  }
817 
818  return COMM_SUCCESS;
819 }
820 
827 int MockStepperDriver::readFirmwareRunning(uint8_t id, bool &is_running)
828 {
829  if (COMM_SUCCESS != ping(id))
830  return COMM_RX_FAIL;
831 
832  is_running = true;
833  return COMM_SUCCESS;
834 }
835 
842 int MockStepperDriver::syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position)
843 {
844  std::set<uint8_t> countSet;
845 
846  abs_position.clear();
847  for (auto &id : id_list)
848  {
849  if (_fake_data->stepper_registers.count(id))
850  abs_position.emplace_back(_fake_data->stepper_registers.at(id).homing_abs_position);
851  else
852  return COMM_RX_FAIL;
853 
854  auto result = countSet.insert(id);
855  if (!result.second)
856  return GROUP_SYNC_REDONDANT_ID; // redondant id
857  }
858  return COMM_SUCCESS;
859 }
860 
867 int MockStepperDriver::syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position)
868 {
869  if (id_list.size() != abs_position.size())
870  return LEN_ID_DATA_NOT_SAME;
871 
872  std::set<uint8_t> countSet;
873 
874  for (size_t i = 0; i < id_list.size(); ++i)
875  {
876  if (_fake_data->stepper_registers.count(id_list.at(i)))
877  _fake_data->stepper_registers.at(id_list.at(i)).homing_abs_position = abs_position.at(i);
878  else
879  return COMM_TX_ERROR;
880 
881  auto result = countSet.insert(id_list.at(i));
882  if (!result.second)
883  return GROUP_SYNC_REDONDANT_ID; // redondant id
884  }
885  return COMM_SUCCESS;
886 }
887 
888 
889 float MockStepperDriver::velocityUnit() const { return 1.0; }
890 
891 
892 } // namespace ttl_driver
ttl_driver::MockStepperDriver::syncReadHomingStatus
int syncReadHomingStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list) override
MockStepperDriver::syncReadHomingStatus.
Definition: mock_stepper_driver.cpp:798
ttl_driver::MockStepperDriver::writeHomingSetup
int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) override
MockStepperDriver::writeHomingDirection.
Definition: mock_stepper_driver.cpp:768
ttl_driver::MockStepperDriver::syncWriteVelocityGoal
int syncWriteVelocityGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list) override
MockStepperDriver::syncWriteVelocityGoal.
Definition: mock_stepper_driver.cpp:310
ttl_driver::MockStepperDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
MockStepperDriver::writePositionGoal.
Definition: mock_stepper_driver.cpp:228
ttl_driver::MockStepperDriver::_fake_time
int _fake_time
Definition: mock_stepper_driver.hpp:121
ttl_driver::MockStepperDriver::syncWriteTorquePercentage
int syncWriteTorquePercentage(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list) override
MockStepperDriver::syncWriteTorquePercentage.
Definition: mock_stepper_driver.cpp:259
ttl_driver::MockStepperDriver::syncReadJointStatus
int syncReadJointStatus(const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 > > &data_array) override
StepperDriver::syncReadJointStatus.
Definition: mock_stepper_driver.cpp:457
ttl_driver::MockStepperDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
MockStepperDriver::readMinPosition.
Definition: mock_stepper_driver.cpp:182
ttl_driver::MockStepperDriver::syncReadVoltage
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockStepperDriver::syncReadVoltage.
Definition: mock_stepper_driver.cpp:554
ttl_driver::MockStepperDriver::_calibration_status
uint8_t _calibration_status
Definition: mock_stepper_driver.hpp:119
ttl_driver::MockStepperDriver::CALIBRATION_IN_PROGRESS
static constexpr int CALIBRATION_IN_PROGRESS
Definition: mock_stepper_driver.hpp:127
ttl_driver::MockStepperDriver::MockStepperDriver
MockStepperDriver(std::shared_ptr< FakeTtlData > data)
MockStepperDriver::MockStepperDriver.
Definition: mock_stepper_driver.cpp:39
ttl_driver::MockStepperDriver::syncWriteHomingAbsPosition
int syncWriteHomingAbsPosition(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position) override
MockStepperDriver::syncWriteHomingAbsPosition.
Definition: mock_stepper_driver.cpp:867
ttl_driver::MockStepperDriver::syncReadHwErrorStatus
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
MockStepperDriver::syncReadHwErrorStatus.
Definition: mock_stepper_driver.cpp:654
ttl_driver::MockStepperDriver::_fake_data
std::shared_ptr< FakeTtlData > _fake_data
Definition: mock_stepper_driver.hpp:116
mock_stepper_driver.hpp
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::MockStepperDriver::syncReadTemperature
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
MockStepperDriver::syncReadTemperature.
Definition: mock_stepper_driver.cpp:525
ttl_driver::MockStepperDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
MockStepperDriver::readVelocity.
Definition: mock_stepper_driver.cpp:348
ttl_driver::MockStepperDriver::writeVelocityProfile
int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data) override
MockStepperDriver::writeVelocityProfile.
Definition: mock_stepper_driver.cpp:725
ttl_driver::MockStepperDriver::syncReadHwStatus
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t > > &data_list) override
MockStepperDriver::syncReadHwStatus.
Definition: mock_stepper_driver.cpp:612
ttl_driver::MockStepperDriver::ping
int ping(uint8_t id) override
MockStepperDriver::ping.
Definition: mock_stepper_driver.cpp:78
ttl_driver::MockStepperDriver::str
std::string str() const override
MockStepperDriver::str.
Definition: mock_stepper_driver.cpp:68
ttl_driver::MockStepperDriver::syncReadHomingAbsPosition
int syncReadHomingAbsPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position) override
MockStepperDriver::syncReadHomingAbsPosition.
Definition: mock_stepper_driver.cpp:842
ttl_driver::MockStepperDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
MockStepperDriver::readPosition.
Definition: mock_stepper_driver.cpp:333
ttl_driver::MockStepperDriver::syncReadVelocity
int syncReadVelocity(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list) override
MockStepperDriver::syncReadVelocity.
Definition: mock_stepper_driver.cpp:430
ttl_driver::MockStepperDriver::scan
int scan(std::vector< uint8_t > &id_list) override
MockStepperDriver::scan.
Definition: mock_stepper_driver.cpp:115
ttl_driver::MockStepperDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
MockStepperDriver::writeTorquePercentage.
Definition: mock_stepper_driver.cpp:214
ttl_driver::MockStepperDriver::readHomingStatus
int readHomingStatus(uint8_t id, uint8_t &status) override
MockStepperDriver::readHomingStatus.
Definition: mock_stepper_driver.cpp:776
ttl_driver::MockStepperDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &mode) override
Definition: mock_stepper_driver.cpp:673
ttl_driver::MockStepperDriver::syncReadRawVoltage
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockStepperDriver::syncReadVoltage.
Definition: mock_stepper_driver.cpp:583
ttl_driver::MockStepperDriver::syncWritePositionGoal
int syncWritePositionGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list) override
MockStepperDriver::syncWritePositionGoal.
Definition: mock_stepper_driver.cpp:280
ttl_driver::MockStepperDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
MockStepperDriver::checkModelNumber.
Definition: mock_stepper_driver.cpp:103
ttl_driver::MockStepperDriver::CALIBRATION_SUCCESS
static constexpr int CALIBRATION_SUCCESS
Definition: mock_stepper_driver.hpp:128
ttl_driver::MockStepperDriver::GROUP_SYNC_REDONDANT_ID
static constexpr int GROUP_SYNC_REDONDANT_ID
Definition: mock_stepper_driver.hpp:123
ttl_driver::MockStepperDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
MockStepperDriver::readMaxPosition.
Definition: mock_stepper_driver.cpp:197
ttl_driver::MockStepperDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
MockStepperDriver::readTemperature.
Definition: mock_stepper_driver.cpp:361
ttl_driver::MockStepperDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t mode) override
Definition: mock_stepper_driver.cpp:682
ttl_driver::MockStepperDriver::syncReadFirmwareVersion
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
MockStepperDriver::syncReadFirmwareVersion.
Definition: mock_stepper_driver.cpp:498
ttl_driver::MockStepperDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
MockStepperDriver::readFirmwareVersion.
Definition: mock_stepper_driver.cpp:167
ttl_driver::MockStepperDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
MockStepperDriver::changeId.
Definition: mock_stepper_driver.cpp:135
ttl_driver::MockStepperDriver::readFirmwareRunning
int readFirmwareRunning(uint8_t id, bool &is_running) override
MockStepperDriver::readFirmwareRunning.
Definition: mock_stepper_driver.cpp:827
ttl_driver::MockStepperDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockStepperDriver::readHwErrorStatus.
Definition: mock_stepper_driver.cpp:391
ttl_driver::MockStepperDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
MockStepperDriver::writeVelocityGoal.
Definition: mock_stepper_driver.cpp:244
ttl_driver::MockStepperDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
MockStepperDriver::readVoltage.
Definition: mock_stepper_driver.cpp:376
ttl_driver::MockStepperDriver::getModelNumber
int getModelNumber(uint8_t id, uint16_t &model_number) override
MockStepperDriver::getModelNumber.
Definition: mock_stepper_driver.cpp:91
ttl_driver::MockStepperDriver::velocityUnit
float velocityUnit() const override
writeVelocityGoal: define the unit of the velocity in RPM
Definition: mock_stepper_driver.cpp:889
ttl_driver::MockStepperDriver::startHoming
int startHoming(uint8_t id) override
MockStepperDriver::startHoming.
Definition: mock_stepper_driver.cpp:751
ttl_driver::MockStepperDriver::init
bool init()
MockStepperDriver::init.
Definition: mock_stepper_driver.cpp:45
ttl_driver::MockStepperDriver::syncReadPosition
int syncReadPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list) override
MockStepperDriver::syncReadPosition.
Definition: mock_stepper_driver.cpp:403
ttl_driver::MockStepperDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
MockStepperDriver::readVelocityProfile.
Definition: mock_stepper_driver.cpp:697
ttl_driver::MockStepperDriver::LEN_ID_DATA_NOT_SAME
static constexpr int LEN_ID_DATA_NOT_SAME
Definition: mock_stepper_driver.hpp:124
ttl_driver::MockStepperDriver::_id_list
std::vector< uint8_t > _id_list
Definition: mock_stepper_driver.hpp:117
ttl_driver::MockStepperDriver::reboot
int reboot(uint8_t id) override
MockStepperDriver::reboot.
Definition: mock_stepper_driver.cpp:127


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