mock_dxl_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 <cstdint>
20 #include <cstdio>
21 #include <map>
22 #include <memory>
23 #include <set>
24 #include <string>
25 #include <type_traits>
26 #include <utility>
27 #include <vector>
28 
29 namespace ttl_driver
30 {
31 
35 MockDxlDriver::MockDxlDriver(std::shared_ptr<FakeTtlData> data) : _fake_data(std::move(data))
36 {
37  // retrieve list of ids
38  for (auto const &imap : _fake_data->dxl_registers)
39  _id_list.emplace_back(imap.first);
40 }
41 
46 std::string MockDxlDriver::str() const
47 {
48  return "Mock Dynamixel Driver (OK)";
49 }
50 
51 //*****************************
52 // AbstractTtlDriver interface
53 //*****************************
54 
60 int MockDxlDriver::ping(uint8_t id)
61 {
62  if (std::find(_fake_data->full_id_list.begin(), _fake_data->full_id_list.end(), id) != _fake_data->full_id_list.end())
63  return COMM_SUCCESS;
64  return COMM_TX_FAIL;
65 }
66 
73 int MockDxlDriver::getModelNumber(uint8_t id, uint16_t &model_number)
74 {
75  if (_fake_data->dxl_registers.count(id))
76  model_number = _fake_data->dxl_registers.at(id).model_number;
77  else
78  return COMM_RX_FAIL;
79  return COMM_SUCCESS;
80 }
81 
87 int MockDxlDriver::checkModelNumber(uint8_t id, uint16_t &model_number)
88 {
89  int ping_result = getModelNumber(id, model_number);
90 
91  if (ping_result == COMM_SUCCESS)
92  {
93  if (model_number)
94  {
96  }
97  }
98 
99  return ping_result;
100 }
101 
107 int MockDxlDriver::scan(std::vector<uint8_t> &id_list)
108 {
109  id_list = _fake_data->full_id_list;
110  return COMM_SUCCESS;
111 }
112 
118 int MockDxlDriver::reboot(uint8_t id)
119 {
120  return ping(id);
121 }
122 
127 std::string MockDxlDriver::interpretErrorState(uint32_t /*hw_state*/) const
128 {
129  return "";
130 }
131 
140 int MockDxlDriver::readCustom(uint16_t address, uint8_t data_len, uint8_t id, uint32_t &data)
141 {
142  (void)address; // unused
143  (void)data_len; // unused
144  (void)id; // unused
145  (void)data; // unused
146 
147  return COMM_SUCCESS;
148 }
149 
158 int MockDxlDriver::writeCustom(uint16_t address, uint8_t data_len, uint8_t id, uint32_t data)
159 {
160  (void)address; // unused
161  (void)data_len; // unused
162  (void)id; // unused
163  (void)data; // unused
164 
165  return COMM_SUCCESS;
166 }
167 
174 int MockDxlDriver::changeId(uint8_t id, uint8_t new_id)
175 {
176  if (id == new_id)
177  {
178  return COMM_SUCCESS;
179  }
180 
181  if (id != 0)
182  {
183  auto it = _fake_data->dxl_registers.find(id);
184 
185  if (it == _fake_data->dxl_registers.end())
186  {
187  return COMM_TX_FAIL;
188  }
189 
190  if (new_id != 0)
191  {
192  auto node = _fake_data->dxl_registers.extract(it);
193  node.key() = new_id;
194  _fake_data->dxl_registers.insert(std::move(node));
195  }
196  else
197  {
198  _fake_data->dxl_registers.erase(it);
199  }
200  }
201 
202  _fake_data->updateFullIdList();
203  scan(_id_list);
204 
205  return COMM_SUCCESS;
206 }
207 
214 int MockDxlDriver::writeStartupConfiguration(uint8_t id, uint8_t value)
215 {
216  (void)id; // unused
217  (void)value; // unused
218 
219  return COMM_SUCCESS;
220 }
221 
228 int MockDxlDriver::writeTemperatureLimit(uint8_t id, uint8_t temperature_limit)
229 {
230  (void)id; // unused
231  (void)temperature_limit; // unused
232 
233  return COMM_SUCCESS;
234 }
235 
242 int MockDxlDriver::writeShutdownConfiguration(uint8_t id, uint8_t configuration)
243 {
244  (void)id; // unused
245  (void)configuration; // unused
246 
247  return COMM_SUCCESS;
248 }
249 
256 int MockDxlDriver::readFirmwareVersion(uint8_t id, std::string &version)
257 {
258  if (_fake_data->dxl_registers.count(id))
259  version = _fake_data->dxl_registers.at(id).firmware;
260  else
261  return COMM_RX_FAIL;
262  return COMM_SUCCESS;
263 }
264 
271 int MockDxlDriver::readMinPosition(uint8_t id, uint32_t &pos)
272 {
273  if (_fake_data->dxl_registers.count(id))
274  pos = _fake_data->dxl_registers.at(id).min_position;
275  else
276  return COMM_RX_FAIL;
277  return COMM_SUCCESS;
278 }
279 
286 int MockDxlDriver::readMaxPosition(uint8_t id, uint32_t &pos)
287 {
288  if (_fake_data->dxl_registers.count(id))
289  pos = _fake_data->dxl_registers.at(id).max_position;
290  else
291  return COMM_RX_FAIL;
292  return COMM_SUCCESS;
293 }
294 
295 // ram write
296 
303 int MockDxlDriver::writeTorquePercentage(uint8_t id, uint8_t torque_enable)
304 {
305  if (_fake_data->dxl_registers.count(id))
306  _fake_data->dxl_registers.at(id).torque = torque_enable;
307  else if (_fake_data->stepper_registers.count(id))
308  _fake_data->stepper_registers.at(id).torque = torque_enable;
309  else
310  return COMM_TX_ERROR;
311 
312  return COMM_SUCCESS;
313 }
314 
321 int MockDxlDriver::writePositionGoal(uint8_t id, uint32_t position)
322 {
323  if (_fake_data->dxl_registers.count(id))
324  _fake_data->dxl_registers.at(id).position = position;
325  else
326  return COMM_RX_FAIL;
327  return COMM_SUCCESS;
328 }
329 
336 int MockDxlDriver::writeVelocityGoal(uint8_t id, uint32_t velocity)
337 {
338  if (_fake_data->dxl_registers.count(id))
339  _fake_data->dxl_registers.at(id).velocity = velocity;
340  else
341  return COMM_RX_FAIL;
342  return COMM_SUCCESS;
343 }
344 
351 int MockDxlDriver::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list)
352 {
353  (void)data_list;
354  int res = COMM_RX_FAIL;
355  if (_fake_data->dxl_registers.count(id))
356  {
357  res = COMM_SUCCESS;
358  }
359 
360  return res;
361 }
362 
369 int MockDxlDriver::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list,
370  const std::vector<uint8_t> &torque_percentage_list)
371 {
372  // Create a map to store the frequency of each element in vector
373  std::set<uint8_t> countSet;
374  // Iterate over the vector and store the frequency of each element in map
375  for (size_t i = 0; i < id_list.size(); i++)
376  {
377  auto result = countSet.insert(id_list.at(i));
378  if (!result.second)
379  return GROUP_SYNC_REDONDANT_ID; // redondant id
380  writeTorquePercentage(id_list.at(i), torque_percentage_list.at(i));
381  }
382  return COMM_SUCCESS;
383 }
384 
391 int MockDxlDriver::syncWritePositionGoal(const std::vector<uint8_t> &id_list,
392  const std::vector<uint32_t> &position_list)
393 {
394  if (id_list.size() != position_list.size())
395  return LEN_ID_DATA_NOT_SAME;
396 
397  // Create a map to store the frequency of each element in id_list. It helps find out which ID is redondant
398  std::set<uint8_t> countSet;
399  for (size_t i = 0; i < id_list.size(); i++)
400  {
401  if (_fake_data->dxl_registers.count(id_list.at(i)))
402  _fake_data->dxl_registers.at(id_list.at(i)).position = position_list.at(i);
403  else if (_fake_data->stepper_registers.count(id_list.at(i)))
404  _fake_data->stepper_registers.at(id_list.at(i)).position = position_list.at(i);
405  else
406  return COMM_TX_ERROR;
407  // write goal position as the current position
408 
409  auto result = countSet.insert(id_list[i]);
410  if (!result.second)
411  return GROUP_SYNC_REDONDANT_ID; // redondant id
412  }
413  return COMM_SUCCESS;
414 }
415 
422 int MockDxlDriver::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list,
423  const std::vector<uint32_t> &velocity_list)
424 {
425  if (id_list.size() != velocity_list.size())
426  return LEN_ID_DATA_NOT_SAME;
427 
428  // Create a map to store the frequency of each element in id_list. It helps find out which ID is redondant
429  std::set<uint8_t> countSet;
430  for (size_t i = 0; i < id_list.size(); i++)
431  {
432  if (!_fake_data->dxl_registers.count(id_list.at(i)))
433  return COMM_TX_ERROR;
434  // write goal position as the current position
435  _fake_data->dxl_registers.at(id_list.at(i)).velocity = velocity_list.at(i);
436 
437  auto result = countSet.insert(id_list[i]);
438  if (!result.second)
439  return GROUP_SYNC_REDONDANT_ID; // redondant id
440  }
441  return COMM_SUCCESS;
442 }
443 
444 int MockDxlDriver::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list)
445 {
446  data_list.clear();
447  if (_fake_data->dxl_registers.count(id))
448  return COMM_RX_FAIL;
449 
450  data_list.emplace_back(0);
451  data_list.emplace_back(0);
452 
453  return COMM_SUCCESS;
454 }
455 
456 // ram read
457 
464 int MockDxlDriver::readPosition(uint8_t id, uint32_t &present_position)
465 {
466  if (_fake_data->dxl_registers.count(id))
467  present_position = _fake_data->dxl_registers.at(id).position;
468  else
469  return COMM_RX_FAIL;
470  return COMM_SUCCESS;
471 }
472 
479 int MockDxlDriver::readVelocity(uint8_t id, uint32_t &present_velocity)
480 {
481  if (_fake_data->dxl_registers.count(id))
482  present_velocity = _fake_data->dxl_registers.at(id).velocity;
483  return COMM_SUCCESS;
484 }
485 
492 int MockDxlDriver::readTemperature(uint8_t id, uint8_t &temperature)
493 {
494  if (_fake_data->dxl_registers.count(id))
495  temperature = _fake_data->dxl_registers.at(id).temperature;
496  else
497  return COMM_RX_FAIL;
498  return COMM_SUCCESS;
499 }
500 
507 int MockDxlDriver::readVoltage(uint8_t id, double &voltage)
508 {
509  if (_fake_data->dxl_registers.count(id))
510  voltage = _fake_data->dxl_registers.at(id).voltage;
511  else
512  return COMM_RX_FAIL;
513  return COMM_SUCCESS;
514 }
515 
522 int MockDxlDriver::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
523 {
524  if (_fake_data->dxl_registers.count(id))
525  return COMM_RX_FAIL;
526 
527  hardware_error_status = 0;
528  return COMM_SUCCESS;
529 }
530 
537 int MockDxlDriver::syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
538 {
539  std::set<uint8_t> countSet;
540  for (auto &id : id_list)
541  {
542  if (_fake_data->dxl_registers.count(id))
543  position_list.emplace_back(_fake_data->dxl_registers.at(id).position);
544  else if (_fake_data->stepper_registers.count(id))
545  position_list.emplace_back(_fake_data->stepper_registers.at(id).position);
546  else
547  return COMM_RX_FAIL;
548 
549  auto result = countSet.insert(id);
550  if (!result.second)
551  return GROUP_SYNC_REDONDANT_ID; // redondant id
552  }
553  return COMM_SUCCESS;
554 }
555 
562 int MockDxlDriver::syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
563 {
564  std::set<uint8_t> countSet;
565  for (auto &id : id_list)
566  {
567  if (_fake_data->dxl_registers.count(id))
568  velocity_list.emplace_back(_fake_data->dxl_registers.at(id).velocity);
569  else if (_fake_data->stepper_registers.count(id))
570  velocity_list.emplace_back(_fake_data->stepper_registers.at(id).velocity);
571  else
572  return COMM_TX_ERROR;
573  auto result = countSet.insert(id);
574  if (!result.second)
575  return GROUP_SYNC_REDONDANT_ID; // redondant id
576  }
577 
578  return COMM_SUCCESS;
579 }
580 
587 int MockDxlDriver::syncReadJointStatus(const std::vector<uint8_t> &id_list,
588  std::vector<std::array<uint32_t, 2>> &data_array_list)
589 {
590  std::set<uint8_t> countSet;
591  data_array_list.clear();
592  for (auto &id : id_list)
593  {
594  if (_fake_data->dxl_registers.count(id))
595  {
596  std::array<uint32_t, 2> blocks{};
597 
598  blocks.at(0) = _fake_data->dxl_registers.at(id).velocity;
599  blocks.at(1) = _fake_data->dxl_registers.at(id).position;
600 
601  data_array_list.emplace_back(blocks);
602  }
603  else if (_fake_data->stepper_registers.count(id))
604  {
605  std::array<uint32_t, 2> blocks{};
606 
607  blocks.at(0) = _fake_data->stepper_registers.at(id).velocity;
608  blocks.at(1) = _fake_data->stepper_registers.at(id).position;
609 
610  data_array_list.emplace_back(blocks);
611  }
612  else
613  return COMM_RX_FAIL;
614  auto result = countSet.insert(id);
615  if (!result.second)
616  return GROUP_SYNC_REDONDANT_ID; // redondant id
617  }
618  return COMM_SUCCESS;
619 }
620 
627 int MockDxlDriver::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
628 {
629  std::set<uint8_t> countSet;
630  for (auto &id : id_list)
631  {
632  if (!_fake_data->dxl_registers.count(id))
633  return COMM_TX_ERROR;
634 
635  firmware_list.emplace_back(_fake_data->dxl_registers.at(id).firmware);
636 
637  auto result = countSet.insert(id);
638  if (!result.second)
639  return GROUP_SYNC_REDONDANT_ID; // redondant id
640  }
641  return COMM_SUCCESS;
642 }
643 
650 int MockDxlDriver::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
651 {
652  std::set<uint8_t> countSet;
653  for (auto &id : id_list)
654  {
655  if (!_fake_data->dxl_registers.count(id))
656  return COMM_TX_ERROR;
657 
658  temperature_list.emplace_back(_fake_data->dxl_registers.at(id).temperature);
659 
660  auto result = countSet.insert(id);
661  if (!result.second)
662  return GROUP_SYNC_REDONDANT_ID; // redondant id
663  }
664  return COMM_SUCCESS;
665 }
666 
673 int MockDxlDriver::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
674 {
675  std::set<uint8_t> countSet;
676  for (auto &id : id_list)
677  {
678  if (!_fake_data->dxl_registers.count(id))
679  return COMM_TX_ERROR;
680 
681  voltage_list.emplace_back(_fake_data->dxl_registers.at(id).voltage);
682 
683  auto result = countSet.insert(id);
684  if (!result.second)
685  return GROUP_SYNC_REDONDANT_ID; // redondant id
686  }
687  return COMM_SUCCESS;
688 }
689 
696 int MockDxlDriver::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
697 {
698  return syncReadVoltage(id_list, voltage_list);
699 }
700 
707 int MockDxlDriver::syncReadHwStatus(const std::vector<uint8_t> &id_list,
708  std::vector<std::pair<double, uint8_t>> &data_list)
709 {
710  data_list.clear();
711 
712  std::set<uint8_t> countSet;
713 
714  for (auto &id : id_list)
715  {
716  if (_fake_data->dxl_registers.count(id))
717  {
718  double voltage = _fake_data->dxl_registers.at(id).voltage;
719  uint8_t temperature = _fake_data->dxl_registers.at(id).temperature;
720  data_list.emplace_back(std::make_pair(voltage, temperature));
721  }
722  else
723  return COMM_RX_FAIL;
724 
725  auto result = countSet.insert(id);
726  if (!result.second)
727  return GROUP_SYNC_REDONDANT_ID; // redondant id
728  }
729  return COMM_SUCCESS;
730 }
731 
738 int MockDxlDriver::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
739 {
740  std::set<uint8_t> countSet;
741  for (auto &id : id_list)
742  {
743  hw_error_list.emplace_back(0);
744  auto result = countSet.insert(id);
745  if (!result.second)
746  return GROUP_SYNC_REDONDANT_ID; // redondant id
747  }
748  return COMM_SUCCESS;
749 }
750 
757 int MockDxlDriver::readPID(uint8_t id, std::vector<uint16_t> &data)
758 {
759  int result = COMM_RX_FAIL;
760 
761  data.clear();
762  if (_fake_data->dxl_registers.count(id))
763  {
764  data.emplace_back(_fake_data->dxl_registers.at(id).position_p_gain);
765  data.emplace_back(_fake_data->dxl_registers.at(id).position_i_gain);
766  data.emplace_back(_fake_data->dxl_registers.at(id).position_d_gain);
767  data.emplace_back(_fake_data->dxl_registers.at(id).velocity_p_gain);
768  data.emplace_back(_fake_data->dxl_registers.at(id).velocity_i_gain);
769  data.emplace_back(_fake_data->dxl_registers.at(id).ff1_gain);
770  data.emplace_back(_fake_data->dxl_registers.at(id).ff2_gain);
771 
772  result = COMM_SUCCESS;
773  }
774 
775  return result;
776 }
777 
784 int MockDxlDriver::writePID(uint8_t id, const std::vector<uint16_t> &data)
785 {
786  int result = COMM_RX_FAIL;
787 
788  if (_fake_data->dxl_registers.count(id))
789  {
790  _fake_data->dxl_registers.at(id).position_p_gain = data.at(0);
791  _fake_data->dxl_registers.at(id).position_i_gain = data.at(1);
792  _fake_data->dxl_registers.at(id).position_d_gain = data.at(2);
793  _fake_data->dxl_registers.at(id).velocity_p_gain = data.at(3);
794  _fake_data->dxl_registers.at(id).velocity_i_gain = data.at(4);
795  _fake_data->dxl_registers.at(id).ff1_gain = data.at(5);
796  _fake_data->dxl_registers.at(id).ff2_gain = data.at(6);
797 
798  result = COMM_SUCCESS;
799  }
800 
801  return result;
802 }
803 
810 int MockDxlDriver::writeControlMode(uint8_t id, uint8_t data)
811 {
812  (void)data; // unused
813 
814  if (!_fake_data->dxl_registers.count(id))
815  return COMM_TX_ERROR;
816 
817  return COMM_SUCCESS;
818 }
819 
826 int MockDxlDriver::readControlMode(uint8_t id, uint8_t &data)
827 {
828  (void)data; // unused
829 
830  if (!_fake_data->dxl_registers.count(id))
831  return COMM_TX_ERROR;
832 
833  return COMM_SUCCESS;
834 }
835 
836 //*****************************
837 // AbstractDxlDriver interface
838 //*****************************
845 int MockDxlDriver::writeLed(uint8_t id, uint8_t led_value)
846 {
847  (void)led_value; // unused
848 
849  if (!_fake_data->dxl_registers.count(id))
850  return COMM_TX_ERROR;
851 
852  return COMM_SUCCESS;
853 }
854 
861 int MockDxlDriver::syncWriteLed(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &led_list)
862 {
863  (void)led_list; // unused
864 
865  std::set<uint8_t> countSet;
866  for (auto &id : id_list)
867  {
868  if (!_fake_data->dxl_registers.count(id))
869  return COMM_TX_ERROR;
870  auto result = countSet.insert(id);
871  if (!result.second)
872  return GROUP_SYNC_REDONDANT_ID; // redondant id
873  }
874  return COMM_SUCCESS;
875 }
876 
883 int MockDxlDriver::writeTorqueGoal(uint8_t id, uint16_t torque)
884 {
885  (void)torque; // unused
886 
887  if (!_fake_data->dxl_registers.count(id))
888  return COMM_TX_ERROR;
889 
890  return COMM_SUCCESS;
891 }
892 
899 int MockDxlDriver::syncWriteTorqueGoal(const std::vector<uint8_t> &id_list, const std::vector<uint16_t> &torque_list)
900 {
901  (void)torque_list; // unused
902 
903  std::set<uint8_t> countSet;
904  for (auto &id : id_list)
905  {
906  if (!_fake_data->dxl_registers.count(id))
907  return COMM_TX_ERROR;
908 
909  auto result = countSet.insert(id);
910 
911  if (!result.second)
912  return GROUP_SYNC_REDONDANT_ID; // redondant id
913  }
914  return COMM_SUCCESS;
915 }
916 
923 int MockDxlDriver::readLoad(uint8_t id, uint16_t &present_load)
924 {
925  (void)present_load; // unused
926 
927  if (_fake_data->dxl_registers.count(id))
928  return COMM_SUCCESS;
929  return COMM_RX_FAIL;
930 }
931 
938 int MockDxlDriver::readMoving(uint8_t id, uint8_t &status)
939 {
940  (void)status; // unused
941 
942  if (_fake_data->dxl_registers.count(id))
943  return COMM_SUCCESS;
944  return COMM_RX_FAIL;
945 }
946 
953 int MockDxlDriver::syncReadLoad(const std::vector<uint8_t> &id_list, std::vector<uint16_t> &load_list)
954 {
955  load_list = {};
956  for (size_t i = 0; i < id_list.size(); i++)
957  load_list.emplace_back(0);
958  return COMM_SUCCESS;
959 }
960 
966 std::string MockDxlDriver::interpretFirmwareVersion(uint32_t fw_version) const
967 {
968  return std::to_string(fw_version);
969 }
970 
971 } // namespace ttl_driver
ttl_driver::MockDxlDriver::syncReadTemperature
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
MockDxlDriver::syncReadTemperature.
Definition: mock_dxl_driver.cpp:650
ttl_driver::MockDxlDriver::MockDxlDriver
MockDxlDriver(std::shared_ptr< FakeTtlData > data)
MockDxlDriver::MockDxlDriver.
Definition: mock_dxl_driver.cpp:35
mock_dxl_driver.hpp
ttl_driver::MockDxlDriver::writeTemperatureLimit
int writeTemperatureLimit(uint8_t id, uint8_t temperature_limit) override
MockDxlDriver::writeTemperatureLimit.
Definition: mock_dxl_driver.cpp:228
ttl_driver::MockDxlDriver::interpretFirmwareVersion
std::string interpretFirmwareVersion(uint32_t fw_version) const override
MockDxlDriver::interpretFirmwareVersion.
Definition: mock_dxl_driver.cpp:966
ttl_driver::MockDxlDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
Definition: mock_dxl_driver.cpp:444
ttl_driver::MockDxlDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
MockDxlDriver::writeTorquePercentage.
Definition: mock_dxl_driver.cpp:303
ttl_driver::MockDxlDriver::scan
int scan(std::vector< uint8_t > &id_list) override
MockDxlDriver::scan.
Definition: mock_dxl_driver.cpp:107
ttl_driver::MockDxlDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
MockDxlDriver::readTemperature.
Definition: mock_dxl_driver.cpp:492
ttl_driver::MockDxlDriver::readLoad
int readLoad(uint8_t id, uint16_t &present_load) override
MockDxlDriver::readLoad.
Definition: mock_dxl_driver.cpp:923
ttl_driver::MockDxlDriver::syncReadHwErrorStatus
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
MockDxlDriver::syncReadHwErrorStatus.
Definition: mock_dxl_driver.cpp:738
ttl_driver::MockDxlDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t data) override
MockDxlDriver::writeControlMode.
Definition: mock_dxl_driver.cpp:810
ttl_driver::MockDxlDriver::writeShutdownConfiguration
int writeShutdownConfiguration(uint8_t id, uint8_t configuration) override
MockDxlDriver::writeShutdownConfiguration.
Definition: mock_dxl_driver.cpp:242
ttl_driver::MockDxlDriver::reboot
int reboot(uint8_t id) override
MockDxlDriver::reboot.
Definition: mock_dxl_driver.cpp:118
ttl_driver::MockDxlDriver::writePID
int writePID(uint8_t id, const std::vector< uint16_t > &data) override
MockDxlDriver::writePID.
Definition: mock_dxl_driver.cpp:784
ttl_driver::MockDxlDriver::syncReadVoltage
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockDxlDriver::syncReadVoltage.
Definition: mock_dxl_driver.cpp:673
ttl_driver::MockDxlDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
MockDxlDriver::writePositionGoal.
Definition: mock_dxl_driver.cpp:321
ttl_driver::MockDxlDriver::syncReadFirmwareVersion
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
MockDxlDriver::syncReadFirmwareVersion.
Definition: mock_dxl_driver.cpp:627
ttl_driver::MockDxlDriver::syncReadPosition
int syncReadPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list) override
MockDxlDriver::syncReadPosition.
Definition: mock_dxl_driver.cpp:537
ttl_driver::MockDxlDriver::syncWriteTorquePercentage
int syncWriteTorquePercentage(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list) override
MockDxlDriver::syncWriteTorquePercentage.
Definition: mock_dxl_driver.cpp:369
ttl_driver::MockDxlDriver::syncReadJointStatus
int syncReadJointStatus(const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 >> &data_array_list) override
MockDxlDriver::syncReadJointStatus.
Definition: mock_dxl_driver.cpp:587
ttl_driver::MockDxlDriver::syncWriteTorqueGoal
int syncWriteTorqueGoal(const std::vector< uint8_t > &id_list, const std::vector< uint16_t > &torque_list) override
MockDxlDriver::syncWriteTorqueGoal.
Definition: mock_dxl_driver.cpp:899
ttl_driver::MockDxlDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
MockDxlDriver::checkModelNumber.
Definition: mock_dxl_driver.cpp:87
ttl_driver::MockDxlDriver::str
std::string str() const override
MockDxlDriver::str.
Definition: mock_dxl_driver.cpp:46
ttl_driver::MockDxlDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
MockDxlDriver::writeVelocityGoal.
Definition: mock_dxl_driver.cpp:336
ttl_driver::MockDxlDriver::syncWriteVelocityGoal
int syncWriteVelocityGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list) override
MockDxlDriver::syncWriteVelocityGoal.
Definition: mock_dxl_driver.cpp:422
ttl_driver::MockDxlDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
MockDxlDriver::readMinPosition.
Definition: mock_dxl_driver.cpp:271
ttl_driver::MockDxlDriver::GROUP_SYNC_REDONDANT_ID
static constexpr int GROUP_SYNC_REDONDANT_ID
Definition: mock_dxl_driver.hpp:127
ttl_driver::MockDxlDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
MockDxlDriver::readMaxPosition.
Definition: mock_dxl_driver.cpp:286
ttl_driver::MockDxlDriver::writeCustom
int writeCustom(uint16_t address, uint8_t data_len, uint8_t id, uint32_t data) override
MockDxlDriver::writeCustom.
Definition: mock_dxl_driver.cpp:158
ttl_driver::MockDxlDriver::interpretErrorState
std::string interpretErrorState(uint32_t hw_state) const override
MockDxlDriver::interpretErrorState.
Definition: mock_dxl_driver.cpp:127
ttl_driver::MockDxlDriver::readCustom
int readCustom(uint16_t address, uint8_t data_len, uint8_t id, uint32_t &data) override
MockDxlDriver::readCustom.
Definition: mock_dxl_driver.cpp:140
ttl_driver::MockDxlDriver::writeLed
int writeLed(uint8_t id, uint8_t led_value) override
MockDxlDriver::writeLed.
Definition: mock_dxl_driver.cpp:845
ttl_driver::MockDxlDriver::_id_list
std::vector< uint8_t > _id_list
Definition: mock_dxl_driver.hpp:125
ttl_driver::MockDxlDriver::ping
int ping(uint8_t id) override
MockDxlDriver::ping.
Definition: mock_dxl_driver.cpp:60
ttl_driver::MockDxlDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
MockDxlDriver::changeId.
Definition: mock_dxl_driver.cpp:174
ttl_driver::MockDxlDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockDxlDriver::readHwErrorStatus.
Definition: mock_dxl_driver.cpp:522
ttl_driver::MockDxlDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
MockDxlDriver::readVoltage.
Definition: mock_dxl_driver.cpp:507
ttl_driver::MockDxlDriver::writeStartupConfiguration
int writeStartupConfiguration(uint8_t id, uint8_t value) override
MockDxlDriver::writeStartupConfiguration.
Definition: mock_dxl_driver.cpp:214
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::MockDxlDriver::writeVelocityProfile
int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data_list) override
MockDxlDriver::writeVelocityProfile.
Definition: mock_dxl_driver.cpp:351
ttl_driver::MockDxlDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
MockDxlDriver::readFirmwareVersion.
Definition: mock_dxl_driver.cpp:256
ttl_driver::AbstractTtlDriver::PING_WRONG_MODEL_NUMBER
static constexpr int PING_WRONG_MODEL_NUMBER
Definition: abstract_ttl_driver.hpp:100
ttl_driver::MockDxlDriver::LEN_ID_DATA_NOT_SAME
static constexpr int LEN_ID_DATA_NOT_SAME
Definition: mock_dxl_driver.hpp:128
ttl_driver::MockDxlDriver::readPID
int readPID(uint8_t id, std::vector< uint16_t > &data) override
MockDxlDriver::readPID.
Definition: mock_dxl_driver.cpp:757
ttl_driver::MockDxlDriver::syncReadLoad
int syncReadLoad(const std::vector< uint8_t > &id_list, std::vector< uint16_t > &load_list) override
MockDxlDriver::syncReadLoad.
Definition: mock_dxl_driver.cpp:953
ttl_driver::MockDxlDriver::syncReadHwStatus
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t >> &data_list) override
MockDxlDriver::syncReadHwStatus.
Definition: mock_dxl_driver.cpp:707
ttl_driver::MockDxlDriver::_fake_data
std::shared_ptr< FakeTtlData > _fake_data
Definition: mock_dxl_driver.hpp:124
ttl_driver::MockDxlDriver::syncWriteLed
int syncWriteLed(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &led_list) override
MockDxlDriver::syncWriteLed.
Definition: mock_dxl_driver.cpp:861
ttl_driver::MockDxlDriver::writeTorqueGoal
int writeTorqueGoal(uint8_t id, uint16_t torque) override
MockDxlDriver::writeTorqueGoal.
Definition: mock_dxl_driver.cpp:883
ttl_driver::MockDxlDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
MockDxlDriver::readPosition.
Definition: mock_dxl_driver.cpp:464
ttl_driver::MockDxlDriver::syncReadRawVoltage
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockDxlDriver::syncReadRawVoltage.
Definition: mock_dxl_driver.cpp:696
ttl_driver::MockDxlDriver::syncReadVelocity
int syncReadVelocity(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list) override
MockDxlDriver::syncReadVelocity.
Definition: mock_dxl_driver.cpp:562
ttl_driver::MockDxlDriver::getModelNumber
int getModelNumber(uint8_t id, uint16_t &model_number) override
MockDxlDriver::getModelNumber.
Definition: mock_dxl_driver.cpp:73
ttl_driver::MockDxlDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &data) override
MockDxlDriver::readControlMode.
Definition: mock_dxl_driver.cpp:826
ttl_driver::MockDxlDriver::syncWritePositionGoal
int syncWritePositionGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list) override
MockDxlDriver::syncWritePositionGoal get position goal and write it as the current position of each j...
Definition: mock_dxl_driver.cpp:391
ttl_driver::MockDxlDriver::readMoving
int readMoving(uint8_t id, uint8_t &status) override
MockDxlDriver::readMoving.
Definition: mock_dxl_driver.cpp:938
ttl_driver::MockDxlDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
MockDxlDriver::readVelocity.
Definition: mock_dxl_driver.cpp:479


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