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 
104 {
105  uint16_t model_number = 0;
106  int ping_result = getModelNumber(id, model_number);
107 
108  return ping_result;
109 }
110 
116 int MockStepperDriver::scan(std::vector<uint8_t> &id_list)
117 {
118  // full id list using only for scan
119  id_list = _fake_data->full_id_list;
120  return COMM_SUCCESS;
121 }
122 
128 int MockStepperDriver::reboot(uint8_t id) { return ping(id); }
129 
136 int MockStepperDriver::changeId(uint8_t id, uint8_t new_id)
137 {
138  int result = COMM_TX_FAIL;
139  if (std::find(_id_list.begin(), _id_list.end(), id) != _id_list.end() &&
140  std::find(_fake_data->full_id_list.begin(), _fake_data->full_id_list.end(), id) != _fake_data->full_id_list.end())
141  {
142  _id_list.erase(std::remove(_id_list.begin(), _id_list.end(), id), _id_list.end());
143  _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());
144  _id_list.emplace_back(new_id);
145  _fake_data->full_id_list.emplace_back(new_id);
146 
147  result = COMM_SUCCESS;
148  }
149 
150  const auto it = _fake_data->stepper_registers.find(id);
151  if (it != _fake_data->stepper_registers.end())
152  {
153  std::swap(_fake_data->stepper_registers[new_id], it->second);
154  result = COMM_SUCCESS;
155  }
156  else
157  result = COMM_TX_FAIL;
158 
159  return result;
160 }
161 
168 int MockStepperDriver::readFirmwareVersion(uint8_t id, std::string &version)
169 {
170  if (_fake_data->stepper_registers.count(id))
171  version = _fake_data->stepper_registers.at(id).firmware;
172  else
173  return COMM_RX_FAIL;
174  return COMM_SUCCESS;
175 }
176 
183 int MockStepperDriver::readMinPosition(uint8_t id, uint32_t &pos)
184 {
185  if (_fake_data->stepper_registers.count(id))
186  pos = _fake_data->stepper_registers.at(id).min_position;
187  else
188  return COMM_RX_FAIL;
189  return COMM_SUCCESS;
190 }
191 
198 int MockStepperDriver::readMaxPosition(uint8_t id, uint32_t &pos)
199 {
200  if (_fake_data->stepper_registers.count(id))
201  pos = _fake_data->stepper_registers.at(id).max_position;
202  else
203  return COMM_RX_FAIL;
204  return COMM_SUCCESS;
205 }
206 
207 // ram write
208 
215 int MockStepperDriver::writeTorquePercentage(uint8_t id, uint8_t /*torque_percentage*/)
216 {
217  if (COMM_SUCCESS != ping(id))
218  return COMM_RX_FAIL;
219 
220  return COMM_SUCCESS;
221 }
222 
229 int MockStepperDriver::writePositionGoal(uint8_t id, uint32_t position)
230 {
231  if (_fake_data->stepper_registers.count(id))
232  _fake_data->stepper_registers.at(id).position = position;
233  else
234  return COMM_RX_FAIL;
235  return COMM_SUCCESS;
236 }
237 
238 // according to the registers, the data should be an int32_t ?
245 int MockStepperDriver::writeVelocityGoal(uint8_t id, uint32_t velocity)
246 {
247  if (_fake_data->stepper_registers.count(id))
248  _fake_data->stepper_registers.at(id).velocity = velocity;
249  else
250  return COMM_RX_FAIL;
251  return COMM_SUCCESS;
252 }
253 
260 int MockStepperDriver::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> & /*torque_percentage_list*/)
261 {
262  // Create a map to store the frequency of each element in vector
263  std::set<uint8_t> countSet;
264 
265  // Iterate over the vector and store the frequency of each element in map
266  for (auto &id : id_list)
267  {
268  auto result = countSet.insert(id);
269  if (!result.second)
270  return GROUP_SYNC_REDONDANT_ID; // redondant id
271  }
272  return COMM_SUCCESS;
273 }
274 
281 int MockStepperDriver::syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list)
282 {
283  if (id_list.size() != position_list.size())
284  return LEN_ID_DATA_NOT_SAME;
285 
286  // Create a map to store the frequency of each element in vector
287  std::set<uint8_t> countSet;
288 
289  for (size_t i = 0; i < id_list.size(); ++i)
290  {
291  if (_fake_data->dxl_registers.count(id_list.at(i)))
292  _fake_data->dxl_registers.at(id_list.at(i)).position = position_list.at(i);
293  else if (_fake_data->stepper_registers.count(id_list.at(i)))
294  _fake_data->stepper_registers.at(id_list.at(i)).position = position_list.at(i);
295  else
296  return COMM_TX_ERROR;
297 
298  auto result = countSet.insert(id_list.at(i));
299  if (!result.second)
300  return GROUP_SYNC_REDONDANT_ID; // redondant id
301  }
302  return COMM_SUCCESS;
303 }
304 
311 int MockStepperDriver::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> & /*velocity_list*/)
312 {
313  // Create a map to store the frequency of each element in vector
314  std::set<uint8_t> countSet;
315 
316  // Iterate over the vector and store the frequency of each element in map
317  for (auto &id : id_list)
318  {
319  auto result = countSet.insert(id);
320  if (!result.second)
321  return GROUP_SYNC_REDONDANT_ID; // redondant id
322  }
323  return COMM_SUCCESS;
324 }
325 
326 // ram read
327 
334 int MockStepperDriver::readPosition(uint8_t id, uint32_t &present_position)
335 {
336  if (_fake_data->stepper_registers.count(id))
337  present_position = _fake_data->stepper_registers.at(id).position;
338  else
339  return COMM_RX_FAIL;
340  return COMM_SUCCESS;
341 }
342 
349 int MockStepperDriver::readVelocity(uint8_t id, uint32_t &present_velocity)
350 {
351  if (_fake_data->stepper_registers.count(id))
352  present_velocity = _fake_data->stepper_registers.at(id).velocity;
353  return COMM_SUCCESS;
354 }
355 
362 int MockStepperDriver::readTemperature(uint8_t id, uint8_t &temperature)
363 {
364  if (_fake_data->stepper_registers.count(id))
365  temperature = _fake_data->stepper_registers.at(id).temperature;
366  else
367  return COMM_RX_FAIL;
368  return COMM_SUCCESS;
369 }
370 
377 int MockStepperDriver::readVoltage(uint8_t id, double &voltage)
378 {
379  if (_fake_data->stepper_registers.count(id))
380  voltage = _fake_data->stepper_registers.at(id).voltage;
381  else
382  return COMM_RX_FAIL;
383  return COMM_SUCCESS;
384 }
385 
392 int MockStepperDriver::readHwErrorStatus(uint8_t /*id*/, uint8_t &hardware_error_status)
393 {
394  hardware_error_status = 0;
395  return COMM_SUCCESS;
396 }
397 
404 int MockStepperDriver::syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
405 {
406  std::set<uint8_t> countSet;
407 
408  position_list.clear();
409  for (auto &id : id_list)
410  {
411  if (_fake_data->dxl_registers.count(id))
412  position_list.emplace_back(_fake_data->dxl_registers.at(id).position);
413  else if (_fake_data->stepper_registers.count(id))
414  position_list.emplace_back(_fake_data->stepper_registers.at(id).position);
415  else
416  return COMM_RX_FAIL;
417 
418  auto result = countSet.insert(id);
419  if (!result.second)
420  return GROUP_SYNC_REDONDANT_ID; // redondant id
421  }
422  return COMM_SUCCESS;
423 }
424 
431 int MockStepperDriver::syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
432 {
433  std::set<uint8_t> countSet;
434 
435  velocity_list.clear();
436  for (auto &id : id_list)
437  {
438  if (_fake_data->dxl_registers.count(id))
439  velocity_list.emplace_back(_fake_data->dxl_registers.at(id).velocity);
440  else if (_fake_data->stepper_registers.count(id))
441  velocity_list.emplace_back(_fake_data->stepper_registers.at(id).velocity);
442  else
443  return COMM_RX_FAIL;
444 
445  auto result = countSet.insert(id);
446  if (!result.second)
447  return GROUP_SYNC_REDONDANT_ID; // redondant id
448  }
449  return COMM_SUCCESS;
450 }
451 
458 int MockStepperDriver::syncReadJointStatus(const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2>> &data_array_list)
459 {
460  std::set<uint8_t> countSet;
461 
462  data_array_list.clear();
463  for (auto &id : id_list)
464  {
465  if (_fake_data->stepper_registers.count(id))
466  {
467  std::array<uint32_t, 2> blocks{};
468 
469  blocks.at(0) = _fake_data->stepper_registers.at(id).velocity;
470  blocks.at(1) = _fake_data->stepper_registers.at(id).position;
471 
472  data_array_list.emplace_back(blocks);
473  }
474  else if (_fake_data->dxl_registers.count(id))
475  {
476  std::array<uint32_t, 2> blocks{};
477 
478  blocks.at(0) = _fake_data->dxl_registers.at(id).velocity;
479  blocks.at(1) = _fake_data->dxl_registers.at(id).position;
480 
481  data_array_list.emplace_back(blocks);
482  }
483  else
484  return COMM_RX_FAIL;
485 
486  auto result = countSet.insert(id);
487  if (!result.second)
488  return GROUP_SYNC_REDONDANT_ID; // redondant id
489  }
490  return COMM_SUCCESS;
491 }
492 
499 int MockStepperDriver::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
500 {
501  std::set<uint8_t> countSet;
502 
503  firmware_list.clear();
504  for (auto &id : id_list)
505  {
506  if (_fake_data->dxl_registers.count(id))
507  firmware_list.emplace_back(_fake_data->dxl_registers.at(id).firmware);
508  else if (_fake_data->stepper_registers.count(id))
509  firmware_list.emplace_back(_fake_data->stepper_registers.at(id).firmware);
510  else
511  return COMM_RX_FAIL;
512 
513  auto result = countSet.insert(id);
514  if (!result.second)
515  return GROUP_SYNC_REDONDANT_ID; // redondant id
516  }
517  return COMM_SUCCESS;
518 }
519 
526 int MockStepperDriver::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
527 {
528  std::set<uint8_t> countSet;
529 
530  temperature_list.clear();
531  for (auto &id : id_list)
532  {
533  if (_fake_data->dxl_registers.count(id))
534  temperature_list.emplace_back(_fake_data->dxl_registers.at(id).temperature);
535  else if (_fake_data->stepper_registers.count(id))
536  temperature_list.emplace_back(_fake_data->stepper_registers.at(id).temperature);
537  else if (_fake_data->end_effector.id == id)
538  temperature_list.emplace_back(_fake_data->end_effector.temperature);
539  else
540  return COMM_RX_FAIL;
541 
542  auto result = countSet.insert(id);
543  if (!result.second)
544  return GROUP_SYNC_REDONDANT_ID; // redondant id
545  }
546  return COMM_SUCCESS;
547 }
548 
555 int MockStepperDriver::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
556 {
557  std::set<uint8_t> countSet;
558 
559  voltage_list.clear();
560  for (auto &id : id_list)
561  {
562  if (_fake_data->dxl_registers.count(id))
563  voltage_list.emplace_back(_fake_data->dxl_registers.at(id).voltage / 10);
564  else if (_fake_data->stepper_registers.count(id))
565  voltage_list.emplace_back(_fake_data->stepper_registers.at(id).voltage / 1000);
566  else if (_fake_data->end_effector.id == id)
567  voltage_list.emplace_back(_fake_data->end_effector.voltage / 1000);
568  else
569  return COMM_RX_FAIL;
570 
571  auto result = countSet.insert(id);
572  if (!result.second)
573  return GROUP_SYNC_REDONDANT_ID; // redondant id
574  }
575  return COMM_SUCCESS;
576 }
577 
584 int MockStepperDriver::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
585 {
586  std::set<uint8_t> countSet;
587 
588  voltage_list.clear();
589  for (auto &id : id_list)
590  {
591  if (_fake_data->dxl_registers.count(id))
592  voltage_list.emplace_back(_fake_data->dxl_registers.at(id).voltage);
593  else if (_fake_data->stepper_registers.count(id))
594  voltage_list.emplace_back(_fake_data->stepper_registers.at(id).voltage);
595  else if (_fake_data->end_effector.id == id)
596  voltage_list.emplace_back(_fake_data->end_effector.voltage);
597  else
598  return COMM_RX_FAIL;
599 
600  auto result = countSet.insert(id);
601  if (!result.second)
602  return GROUP_SYNC_REDONDANT_ID; // redondant id
603  }
604  return COMM_SUCCESS;
605 }
606 
613 int MockStepperDriver::syncReadHwStatus(const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list)
614 {
615  data_list.clear();
616 
617  std::set<uint8_t> countSet;
618 
619  for (auto &id : id_list)
620  {
621  if (_fake_data->dxl_registers.count(id))
622  {
623  double voltage = _fake_data->dxl_registers.at(id).voltage;
624  uint8_t temperature = _fake_data->dxl_registers.at(id).temperature;
625  data_list.emplace_back(std::make_pair(voltage, temperature));
626  }
627  else if (_fake_data->stepper_registers.count(id))
628  {
629  double voltage = _fake_data->stepper_registers.at(id).voltage;
630  uint8_t temperature = _fake_data->stepper_registers.at(id).temperature;
631  data_list.emplace_back(std::make_pair(voltage, temperature));
632  }
633  else if (_fake_data->end_effector.id == id)
634  {
635  double voltage = _fake_data->end_effector.voltage;
636  uint8_t temperature = _fake_data->end_effector.temperature;
637  data_list.emplace_back(std::make_pair(voltage, temperature));
638  }
639  else
640  return COMM_RX_FAIL;
641 
642  auto result = countSet.insert(id);
643  if (!result.second)
644  return GROUP_SYNC_REDONDANT_ID; // redondant id
645  }
646  return COMM_SUCCESS;
647 }
648 
655 int MockStepperDriver::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
656 {
657  std::set<uint8_t> countSet;
658 
659  hw_error_list.clear();
660  for (auto &id : id_list)
661  {
662  hw_error_list.emplace_back(0);
663  auto result = countSet.insert(id);
664  if (!result.second)
665  return GROUP_SYNC_REDONDANT_ID; // redondant id
666  }
667  return COMM_SUCCESS;
668 }
669 
670 //*****************************
671 // AbstractStepperDriver interface
672 //*****************************
673 
674 int MockStepperDriver::readControlMode(uint8_t id, uint8_t &mode)
675 {
676  if (_fake_data->stepper_registers.count(id))
677  mode = _fake_data->stepper_registers.at(id).operating_mode;
678  else
679  return COMM_RX_FAIL;
680  return COMM_SUCCESS;
681 }
682 
683 int MockStepperDriver::writeControlMode(uint8_t id, uint8_t mode)
684 {
685  if (_fake_data->stepper_registers.count(id))
686  _fake_data->stepper_registers.at(id).operating_mode = mode;
687  else
688  return COMM_RX_FAIL;
689  return COMM_SUCCESS;
690 }
691 
698 int MockStepperDriver::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data)
699 {
700  int result = COMM_RX_FAIL;
701 
702  data.clear();
703  if (_fake_data->stepper_registers.count(id))
704  {
705  data.emplace_back(_fake_data->stepper_registers.at(id).v_start);
706  data.emplace_back(_fake_data->stepper_registers.at(id).a_1);
707  data.emplace_back(_fake_data->stepper_registers.at(id).v_1);
708  data.emplace_back(_fake_data->stepper_registers.at(id).a_max);
709  data.emplace_back(_fake_data->stepper_registers.at(id).v_max);
710  data.emplace_back(_fake_data->stepper_registers.at(id).d_max);
711  data.emplace_back(_fake_data->stepper_registers.at(id).d_1);
712  data.emplace_back(_fake_data->stepper_registers.at(id).v_stop);
713 
714  result = COMM_SUCCESS;
715  }
716 
717  return result;
718 }
719 
726 int MockStepperDriver::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data)
727 {
728  int result = COMM_RX_FAIL;
729 
730  if (_fake_data->stepper_registers.count(id))
731  {
732  _fake_data->stepper_registers.at(id).v_start = data.at(0);
733  _fake_data->stepper_registers.at(id).a_1 = data.at(1);
734  _fake_data->stepper_registers.at(id).v_1 = data.at(2);
735  _fake_data->stepper_registers.at(id).a_max = data.at(3);
736  _fake_data->stepper_registers.at(id).v_max = data.at(4);
737  _fake_data->stepper_registers.at(id).d_max = data.at(5);
738  _fake_data->stepper_registers.at(id).d_1 = data.at(6);
739  _fake_data->stepper_registers.at(id).v_stop = data.at(7);
740 
741  result = COMM_SUCCESS;
742  }
743 
744  return result;
745 }
746 
753 {
754  if (COMM_SUCCESS != ping(id))
755  return COMM_RX_FAIL;
756 
758  _fake_time = 2;
759  return COMM_SUCCESS;
760 }
761 
769 int MockStepperDriver::writeHomingSetup(uint8_t id, uint8_t /*direction*/, uint8_t /*stall_threshold*/) { return ping(id); }
770 
777 int MockStepperDriver::readHomingStatus(uint8_t id, uint8_t &status)
778 {
779  if (COMM_SUCCESS != ping(id))
780  return COMM_RX_FAIL;
781 
782  if (_fake_time)
783  {
784  _fake_time--;
785  }
786  else
788 
789  status = _calibration_status;
790  return COMM_SUCCESS;
791 }
792 
799 int MockStepperDriver::syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list)
800 {
801  if (_fake_time)
802  {
803  _fake_time--;
804  }
805  else // when calibration finished or at startup
807 
808  std::set<uint8_t> countSet;
809 
810  status_list.clear();
811  for (auto &id : id_list)
812  {
813  status_list.emplace_back(_calibration_status);
814  auto result = countSet.insert(id);
815  if (!result.second)
816  return GROUP_SYNC_REDONDANT_ID; // redondant id
817  }
818 
819  return COMM_SUCCESS;
820 }
821 
828 int MockStepperDriver::readFirmwareRunning(uint8_t id, bool &is_running)
829 {
830  if (COMM_SUCCESS != ping(id))
831  return COMM_RX_FAIL;
832 
833  is_running = true;
834  return COMM_SUCCESS;
835 }
836 
843 int MockStepperDriver::syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position)
844 {
845  std::set<uint8_t> countSet;
846 
847  abs_position.clear();
848  for (auto &id : id_list)
849  {
850  if (_fake_data->stepper_registers.count(id))
851  abs_position.emplace_back(_fake_data->stepper_registers.at(id).homing_abs_position);
852  else
853  return COMM_RX_FAIL;
854 
855  auto result = countSet.insert(id);
856  if (!result.second)
857  return GROUP_SYNC_REDONDANT_ID; // redondant id
858  }
859  return COMM_SUCCESS;
860 }
861 
868 int MockStepperDriver::syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &abs_position)
869 {
870  if (id_list.size() != abs_position.size())
871  return LEN_ID_DATA_NOT_SAME;
872 
873  std::set<uint8_t> countSet;
874 
875  for (size_t i = 0; i < id_list.size(); ++i)
876  {
877  if (_fake_data->stepper_registers.count(id_list.at(i)))
878  _fake_data->stepper_registers.at(id_list.at(i)).homing_abs_position = abs_position.at(i);
879  else
880  return COMM_TX_ERROR;
881 
882  auto result = countSet.insert(id_list.at(i));
883  if (!result.second)
884  return GROUP_SYNC_REDONDANT_ID; // redondant id
885  }
886  return COMM_SUCCESS;
887 }
888 
889 
890 float MockStepperDriver::velocityUnit() const { return 1.0; }
891 
892 
893 } // 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:799
ttl_driver::MockStepperDriver::writeHomingSetup
int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) override
MockStepperDriver::writeHomingDirection.
Definition: mock_stepper_driver.cpp:769
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:311
ttl_driver::MockStepperDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
MockStepperDriver::writePositionGoal.
Definition: mock_stepper_driver.cpp:229
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:260
ttl_driver::MockStepperDriver::checkModelNumber
int checkModelNumber(uint8_t id) override
MockStepperDriver::checkModelNumber.
Definition: mock_stepper_driver.cpp:103
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:458
ttl_driver::MockStepperDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
MockStepperDriver::readMinPosition.
Definition: mock_stepper_driver.cpp:183
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:555
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:868
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:655
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:526
ttl_driver::MockStepperDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
MockStepperDriver::readVelocity.
Definition: mock_stepper_driver.cpp:349
ttl_driver::MockStepperDriver::writeVelocityProfile
int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data) override
MockStepperDriver::writeVelocityProfile.
Definition: mock_stepper_driver.cpp:726
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:613
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:843
ttl_driver::MockStepperDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
MockStepperDriver::readPosition.
Definition: mock_stepper_driver.cpp:334
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:431
ttl_driver::MockStepperDriver::scan
int scan(std::vector< uint8_t > &id_list) override
MockStepperDriver::scan.
Definition: mock_stepper_driver.cpp:116
ttl_driver::MockStepperDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
MockStepperDriver::writeTorquePercentage.
Definition: mock_stepper_driver.cpp:215
ttl_driver::MockStepperDriver::readHomingStatus
int readHomingStatus(uint8_t id, uint8_t &status) override
MockStepperDriver::readHomingStatus.
Definition: mock_stepper_driver.cpp:777
ttl_driver::MockStepperDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &mode) override
Definition: mock_stepper_driver.cpp:674
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:584
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:281
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:198
ttl_driver::MockStepperDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
MockStepperDriver::readTemperature.
Definition: mock_stepper_driver.cpp:362
ttl_driver::MockStepperDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t mode) override
Definition: mock_stepper_driver.cpp:683
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:499
ttl_driver::MockStepperDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
MockStepperDriver::readFirmwareVersion.
Definition: mock_stepper_driver.cpp:168
ttl_driver::MockStepperDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
MockStepperDriver::changeId.
Definition: mock_stepper_driver.cpp:136
ttl_driver::MockStepperDriver::readFirmwareRunning
int readFirmwareRunning(uint8_t id, bool &is_running) override
MockStepperDriver::readFirmwareRunning.
Definition: mock_stepper_driver.cpp:828
ttl_driver::MockStepperDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockStepperDriver::readHwErrorStatus.
Definition: mock_stepper_driver.cpp:392
ttl_driver::MockStepperDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
MockStepperDriver::writeVelocityGoal.
Definition: mock_stepper_driver.cpp:245
ttl_driver::MockStepperDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
MockStepperDriver::readVoltage.
Definition: mock_stepper_driver.cpp:377
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:890
ttl_driver::MockStepperDriver::startHoming
int startHoming(uint8_t id) override
MockStepperDriver::startHoming.
Definition: mock_stepper_driver.cpp:752
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:404
ttl_driver::MockStepperDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
MockStepperDriver::readVelocityProfile.
Definition: mock_stepper_driver.cpp:698
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:128


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