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 { return "Mock Dynamixel Driver (OK)"; }
47 
48 //*****************************
49 // AbstractTtlDriver interface
50 //*****************************
51 
57 int MockDxlDriver::ping(uint8_t id)
58 {
59  if (std::find(_fake_data->full_id_list.begin(), _fake_data->full_id_list.end(), id) != _fake_data->full_id_list.end())
60  return COMM_SUCCESS;
61  return COMM_TX_FAIL;
62 }
63 
70 int MockDxlDriver::getModelNumber(uint8_t id, uint16_t &model_number)
71 {
72  if (_fake_data->dxl_registers.count(id))
73  model_number = _fake_data->dxl_registers.at(id).model_number;
74  else
75  return COMM_RX_FAIL;
76  return COMM_SUCCESS;
77 }
78 
84 int MockDxlDriver::checkModelNumber(uint8_t id, uint16_t& model_number)
85 {
86  int ping_result = getModelNumber(id, model_number);
87 
88  if (ping_result == COMM_SUCCESS)
89  {
90  if (model_number)
91  {
93  }
94  }
95 
96  return ping_result;
97 }
98 
104 int MockDxlDriver::scan(std::vector<uint8_t> &id_list)
105 {
106  id_list = _fake_data->full_id_list;
107  return COMM_SUCCESS;
108 }
109 
115 int MockDxlDriver::reboot(uint8_t id) { return ping(id); }
116 
121 std::string MockDxlDriver::interpretErrorState(uint32_t /*hw_state*/) const { return ""; }
122 
131 int MockDxlDriver::readCustom(uint16_t address, uint8_t data_len, uint8_t id, uint32_t &data)
132 {
133  (void)address; // unused
134  (void)data_len; // unused
135  (void)id; // unused
136  (void)data; // unused
137 
138  return COMM_SUCCESS;
139 }
140 
149 int MockDxlDriver::writeCustom(uint16_t address, uint8_t data_len, uint8_t id, uint32_t data)
150 {
151  (void)address; // unused
152  (void)data_len; // unused
153  (void)id; // unused
154  (void)data; // unused
155 
156  return COMM_SUCCESS;
157 }
158 
165 int MockDxlDriver::changeId(uint8_t id, uint8_t new_id)
166 {
167  (void)id; // unused
168  (void)new_id; // unused
169 
170  return COMM_TX_FAIL;
171 }
172 
179 int MockDxlDriver::writeStartupConfiguration(uint8_t id, uint8_t value)
180 {
181  (void)id; // unused
182  (void)value; // unused
183 
184  return COMM_SUCCESS;
185 }
186 
193 int MockDxlDriver::writeTemperatureLimit(uint8_t id, uint8_t temperature_limit)
194 {
195  (void)id; // unused
196  (void)temperature_limit; // unused
197 
198  return COMM_SUCCESS;
199 }
200 
207 int MockDxlDriver::writeShutdownConfiguration(uint8_t id, uint8_t configuration)
208 {
209  (void)id; // unused
210  (void)configuration; // unused
211 
212  return COMM_SUCCESS;
213 }
214 
221 int MockDxlDriver::readFirmwareVersion(uint8_t id, std::string &version)
222 {
223  if (_fake_data->dxl_registers.count(id))
224  version = _fake_data->dxl_registers.at(id).firmware;
225  else
226  return COMM_RX_FAIL;
227  return COMM_SUCCESS;
228 }
229 
236 int MockDxlDriver::readMinPosition(uint8_t id, uint32_t &pos)
237 {
238  if (_fake_data->dxl_registers.count(id))
239  pos = _fake_data->dxl_registers.at(id).min_position;
240  else
241  return COMM_RX_FAIL;
242  return COMM_SUCCESS;
243 }
244 
251 int MockDxlDriver::readMaxPosition(uint8_t id, uint32_t &pos)
252 {
253  if (_fake_data->dxl_registers.count(id))
254  pos = _fake_data->dxl_registers.at(id).max_position;
255  else
256  return COMM_RX_FAIL;
257  return COMM_SUCCESS;
258 }
259 
260 // ram write
261 
268 int MockDxlDriver::writeTorquePercentage(uint8_t id, uint8_t torque_enable)
269 {
270  if (_fake_data->dxl_registers.count(id))
271  _fake_data->dxl_registers.at(id).torque = torque_enable;
272  else if (_fake_data->stepper_registers.count(id))
273  _fake_data->stepper_registers.at(id).torque = torque_enable;
274  else
275  return COMM_TX_ERROR;
276 
277  return COMM_SUCCESS;
278 }
279 
286 int MockDxlDriver::writePositionGoal(uint8_t id, uint32_t position)
287 {
288  if (_fake_data->dxl_registers.count(id))
289  _fake_data->dxl_registers.at(id).position = position;
290  else
291  return COMM_RX_FAIL;
292  return COMM_SUCCESS;
293 }
294 
301 int MockDxlDriver::writeVelocityGoal(uint8_t id, uint32_t velocity)
302 {
303  if (_fake_data->dxl_registers.count(id))
304  _fake_data->dxl_registers.at(id).velocity = velocity;
305  else
306  return COMM_RX_FAIL;
307  return COMM_SUCCESS;
308 }
309 
316 int MockDxlDriver::writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list)
317 {
318  (void)data_list;
319  int res = COMM_RX_FAIL;
320  if (_fake_data->dxl_registers.count(id))
321  {
322  res = COMM_SUCCESS;
323  }
324 
325  return res;
326 }
327 
334 int MockDxlDriver::syncWriteTorquePercentage(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &torque_percentage_list)
335 {
336  // Create a map to store the frequency of each element in vector
337  std::set<uint8_t> countSet;
338  // Iterate over the vector and store the frequency of each element in map
339  for (size_t i = 0; i < id_list.size(); i++)
340  {
341  auto result = countSet.insert(id_list.at(i));
342  if (!result.second)
343  return GROUP_SYNC_REDONDANT_ID; // redondant id
344  writeTorquePercentage(id_list.at(i), torque_percentage_list.at(i));
345  }
346  return COMM_SUCCESS;
347 }
348 
355 int MockDxlDriver::syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list)
356 {
357  if (id_list.size() != position_list.size())
358  return LEN_ID_DATA_NOT_SAME;
359 
360  // Create a map to store the frequency of each element in id_list. It helps find out which ID is redondant
361  std::set<uint8_t> countSet;
362  for (size_t i = 0; i < id_list.size(); i++)
363  {
364  if (_fake_data->dxl_registers.count(id_list.at(i)))
365  _fake_data->dxl_registers.at(id_list.at(i)).position = position_list.at(i);
366  else if (_fake_data->stepper_registers.count(id_list.at(i)))
367  _fake_data->stepper_registers.at(id_list.at(i)).position = position_list.at(i);
368  else
369  return COMM_TX_ERROR;
370  // write goal position as the current position
371 
372  auto result = countSet.insert(id_list[i]);
373  if (!result.second)
374  return GROUP_SYNC_REDONDANT_ID; // redondant id
375  }
376  return COMM_SUCCESS;
377 }
378 
385 int MockDxlDriver::syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list)
386 {
387  if (id_list.size() != velocity_list.size())
388  return LEN_ID_DATA_NOT_SAME;
389 
390  // Create a map to store the frequency of each element in id_list. It helps find out which ID is redondant
391  std::set<uint8_t> countSet;
392  for (size_t i = 0; i < id_list.size(); i++)
393  {
394  if (!_fake_data->dxl_registers.count(id_list.at(i)))
395  return COMM_TX_ERROR;
396  // write goal position as the current position
397  _fake_data->dxl_registers.at(id_list.at(i)).velocity = velocity_list.at(i);
398 
399  auto result = countSet.insert(id_list[i]);
400  if (!result.second)
401  return GROUP_SYNC_REDONDANT_ID; // redondant id
402  }
403  return COMM_SUCCESS;
404 }
405 
406 int MockDxlDriver::readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list)
407 {
408  data_list.clear();
409  if (_fake_data->dxl_registers.count(id))
410  return COMM_RX_FAIL;
411 
412  data_list.emplace_back(0);
413  data_list.emplace_back(0);
414 
415  return COMM_SUCCESS;
416 }
417 
418 // ram read
419 
426 int MockDxlDriver::readPosition(uint8_t id, uint32_t &present_position)
427 {
428  if (_fake_data->dxl_registers.count(id))
429  present_position = _fake_data->dxl_registers.at(id).position;
430  else
431  return COMM_RX_FAIL;
432  return COMM_SUCCESS;
433 }
434 
441 int MockDxlDriver::readVelocity(uint8_t id, uint32_t &present_velocity)
442 {
443  if (_fake_data->dxl_registers.count(id))
444  present_velocity = _fake_data->dxl_registers.at(id).velocity;
445  return COMM_SUCCESS;
446 }
447 
454 int MockDxlDriver::readTemperature(uint8_t id, uint8_t &temperature)
455 {
456  if (_fake_data->dxl_registers.count(id))
457  temperature = _fake_data->dxl_registers.at(id).temperature;
458  else
459  return COMM_RX_FAIL;
460  return COMM_SUCCESS;
461 }
462 
469 int MockDxlDriver::readVoltage(uint8_t id, double &voltage)
470 {
471  if (_fake_data->dxl_registers.count(id))
472  voltage = _fake_data->dxl_registers.at(id).voltage;
473  else
474  return COMM_RX_FAIL;
475  return COMM_SUCCESS;
476 }
477 
484 int MockDxlDriver::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
485 {
486  if (_fake_data->dxl_registers.count(id))
487  return COMM_RX_FAIL;
488 
489  hardware_error_status = 0;
490  return COMM_SUCCESS;
491 }
492 
499 int MockDxlDriver::syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
500 {
501  std::set<uint8_t> countSet;
502  for (auto &id : id_list)
503  {
504  if (_fake_data->dxl_registers.count(id))
505  position_list.emplace_back(_fake_data->dxl_registers.at(id).position);
506  else if (_fake_data->stepper_registers.count(id))
507  position_list.emplace_back(_fake_data->stepper_registers.at(id).position);
508  else
509  return COMM_RX_FAIL;
510 
511  auto result = countSet.insert(id);
512  if (!result.second)
513  return GROUP_SYNC_REDONDANT_ID; // redondant id
514  }
515  return COMM_SUCCESS;
516 }
517 
524 int MockDxlDriver::syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
525 {
526  std::set<uint8_t> countSet;
527  for (auto &id : id_list)
528  {
529  if (_fake_data->dxl_registers.count(id))
530  velocity_list.emplace_back(_fake_data->dxl_registers.at(id).velocity);
531  else if (_fake_data->stepper_registers.count(id))
532  velocity_list.emplace_back(_fake_data->stepper_registers.at(id).velocity);
533  else
534  return COMM_TX_ERROR;
535  auto result = countSet.insert(id);
536  if (!result.second)
537  return GROUP_SYNC_REDONDANT_ID; // redondant id
538  }
539 
540  return COMM_SUCCESS;
541 }
542 
549 int MockDxlDriver::syncReadJointStatus(const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2>> &data_array_list)
550 {
551  std::set<uint8_t> countSet;
552  data_array_list.clear();
553  for (auto &id : id_list)
554  {
555  if (_fake_data->dxl_registers.count(id))
556  {
557  std::array<uint32_t, 2> blocks{};
558 
559  blocks.at(0) = _fake_data->dxl_registers.at(id).velocity;
560  blocks.at(1) = _fake_data->dxl_registers.at(id).position;
561 
562  data_array_list.emplace_back(blocks);
563  }
564  else if (_fake_data->stepper_registers.count(id))
565  {
566  std::array<uint32_t, 2> blocks{};
567 
568  blocks.at(0) = _fake_data->stepper_registers.at(id).velocity;
569  blocks.at(1) = _fake_data->stepper_registers.at(id).position;
570 
571  data_array_list.emplace_back(blocks);
572  }
573  else
574  return COMM_RX_FAIL;
575  auto result = countSet.insert(id);
576  if (!result.second)
577  return GROUP_SYNC_REDONDANT_ID; // redondant id
578  }
579  return COMM_SUCCESS;
580 }
581 
588 int MockDxlDriver::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
589 {
590  std::set<uint8_t> countSet;
591  for (auto &id : id_list)
592  {
593  if (!_fake_data->dxl_registers.count(id))
594  return COMM_TX_ERROR;
595 
596  firmware_list.emplace_back(_fake_data->dxl_registers.at(id).firmware);
597 
598  auto result = countSet.insert(id);
599  if (!result.second)
600  return GROUP_SYNC_REDONDANT_ID; // redondant id
601  }
602  return COMM_SUCCESS;
603 }
604 
611 int MockDxlDriver::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
612 {
613  std::set<uint8_t> countSet;
614  for (auto &id : id_list)
615  {
616  if (!_fake_data->dxl_registers.count(id))
617  return COMM_TX_ERROR;
618 
619  temperature_list.emplace_back(_fake_data->dxl_registers.at(id).temperature);
620 
621  auto result = countSet.insert(id);
622  if (!result.second)
623  return GROUP_SYNC_REDONDANT_ID; // redondant id
624  }
625  return COMM_SUCCESS;
626 }
627 
634 int MockDxlDriver::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
635 {
636  std::set<uint8_t> countSet;
637  for (auto &id : id_list)
638  {
639  if (!_fake_data->dxl_registers.count(id))
640  return COMM_TX_ERROR;
641 
642  voltage_list.emplace_back(_fake_data->dxl_registers.at(id).voltage);
643 
644  auto result = countSet.insert(id);
645  if (!result.second)
646  return GROUP_SYNC_REDONDANT_ID; // redondant id
647  }
648  return COMM_SUCCESS;
649 }
650 
657 int MockDxlDriver::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) { return syncReadVoltage(id_list, voltage_list); }
658 
665 int MockDxlDriver::syncReadHwStatus(const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list)
666 {
667  data_list.clear();
668 
669  std::set<uint8_t> countSet;
670 
671  for (auto &id : id_list)
672  {
673  if (_fake_data->dxl_registers.count(id))
674  {
675  double voltage = _fake_data->dxl_registers.at(id).voltage;
676  uint8_t temperature = _fake_data->dxl_registers.at(id).temperature;
677  data_list.emplace_back(std::make_pair(voltage, temperature));
678  }
679  else
680  return COMM_RX_FAIL;
681 
682  auto result = countSet.insert(id);
683  if (!result.second)
684  return GROUP_SYNC_REDONDANT_ID; // redondant id
685  }
686  return COMM_SUCCESS;
687 }
688 
695 int MockDxlDriver::syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
696 {
697  std::set<uint8_t> countSet;
698  for (auto &id : id_list)
699  {
700  hw_error_list.emplace_back(0);
701  auto result = countSet.insert(id);
702  if (!result.second)
703  return GROUP_SYNC_REDONDANT_ID; // redondant id
704  }
705  return COMM_SUCCESS;
706 }
707 
714 int MockDxlDriver::readPID(uint8_t id, std::vector<uint16_t> &data)
715 {
716  int result = COMM_RX_FAIL;
717 
718  data.clear();
719  if (_fake_data->dxl_registers.count(id))
720  {
721  data.emplace_back(_fake_data->dxl_registers.at(id).position_p_gain);
722  data.emplace_back(_fake_data->dxl_registers.at(id).position_i_gain);
723  data.emplace_back(_fake_data->dxl_registers.at(id).position_d_gain);
724  data.emplace_back(_fake_data->dxl_registers.at(id).velocity_p_gain);
725  data.emplace_back(_fake_data->dxl_registers.at(id).velocity_i_gain);
726  data.emplace_back(_fake_data->dxl_registers.at(id).ff1_gain);
727  data.emplace_back(_fake_data->dxl_registers.at(id).ff2_gain);
728 
729  result = COMM_SUCCESS;
730  }
731 
732  return result;
733 }
734 
741 int MockDxlDriver::writePID(uint8_t id, const std::vector<uint16_t> &data)
742 {
743  int result = COMM_RX_FAIL;
744 
745  if (_fake_data->dxl_registers.count(id))
746  {
747  _fake_data->dxl_registers.at(id).position_p_gain = data.at(0);
748  _fake_data->dxl_registers.at(id).position_i_gain = data.at(1);
749  _fake_data->dxl_registers.at(id).position_d_gain = data.at(2);
750  _fake_data->dxl_registers.at(id).velocity_p_gain = data.at(3);
751  _fake_data->dxl_registers.at(id).velocity_i_gain = data.at(4);
752  _fake_data->dxl_registers.at(id).ff1_gain = data.at(5);
753  _fake_data->dxl_registers.at(id).ff2_gain = data.at(6);
754 
755  result = COMM_SUCCESS;
756  }
757 
758  return result;
759 }
760 
767 int MockDxlDriver::writeControlMode(uint8_t id, uint8_t data)
768 {
769  (void)data; // unused
770 
771  if (!_fake_data->dxl_registers.count(id))
772  return COMM_TX_ERROR;
773 
774  return COMM_SUCCESS;
775 }
776 
783 int MockDxlDriver::readControlMode(uint8_t id, uint8_t &data)
784 {
785  (void)data; // unused
786 
787  if (!_fake_data->dxl_registers.count(id))
788  return COMM_TX_ERROR;
789 
790  return COMM_SUCCESS;
791 }
792 
793 //*****************************
794 // AbstractDxlDriver interface
795 //*****************************
802 int MockDxlDriver::writeLed(uint8_t id, uint8_t led_value)
803 {
804  (void)led_value; // unused
805 
806  if (!_fake_data->dxl_registers.count(id))
807  return COMM_TX_ERROR;
808 
809  return COMM_SUCCESS;
810 }
811 
818 int MockDxlDriver::syncWriteLed(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &led_list)
819 {
820  (void)led_list; // unused
821 
822  std::set<uint8_t> countSet;
823  for (auto &id : id_list)
824  {
825  if (!_fake_data->dxl_registers.count(id))
826  return COMM_TX_ERROR;
827  auto result = countSet.insert(id);
828  if (!result.second)
829  return GROUP_SYNC_REDONDANT_ID; // redondant id
830  }
831  return COMM_SUCCESS;
832 }
833 
840 int MockDxlDriver::writeTorqueGoal(uint8_t id, uint16_t torque)
841 {
842  (void)torque; // unused
843 
844  if (!_fake_data->dxl_registers.count(id))
845  return COMM_TX_ERROR;
846 
847  return COMM_SUCCESS;
848 }
849 
856 int MockDxlDriver::syncWriteTorqueGoal(const std::vector<uint8_t> &id_list, const std::vector<uint16_t> &torque_list)
857 {
858  (void)torque_list; // unused
859 
860  std::set<uint8_t> countSet;
861  for (auto &id : id_list)
862  {
863  if (!_fake_data->dxl_registers.count(id))
864  return COMM_TX_ERROR;
865 
866  auto result = countSet.insert(id);
867 
868  if (!result.second)
869  return GROUP_SYNC_REDONDANT_ID; // redondant id
870  }
871  return COMM_SUCCESS;
872 }
873 
880 int MockDxlDriver::readLoad(uint8_t id, uint16_t &present_load)
881 {
882  (void)present_load; // unused
883 
884  if (_fake_data->dxl_registers.count(id))
885  return COMM_SUCCESS;
886  return COMM_RX_FAIL;
887 }
888 
895 int MockDxlDriver::readMoving(uint8_t id, uint8_t &status)
896 {
897  (void)status; // unused
898 
899  if (_fake_data->dxl_registers.count(id))
900  return COMM_SUCCESS;
901  return COMM_RX_FAIL;
902 }
903 
910 int MockDxlDriver::syncReadLoad(const std::vector<uint8_t> &id_list, std::vector<uint16_t> &load_list)
911 {
912  load_list = {};
913  for (size_t i = 0; i < id_list.size(); i++)
914  load_list.emplace_back(0);
915  return COMM_SUCCESS;
916 }
917 
923 std::string MockDxlDriver::interpretFirmwareVersion(uint32_t fw_version) const { return std::to_string(fw_version); }
924 
925 } // 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:611
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:193
ttl_driver::MockDxlDriver::interpretFirmwareVersion
std::string interpretFirmwareVersion(uint32_t fw_version) const override
MockDxlDriver::interpretFirmwareVersion.
Definition: mock_dxl_driver.cpp:923
ttl_driver::MockDxlDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
Definition: mock_dxl_driver.cpp:406
ttl_driver::MockDxlDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
MockDxlDriver::writeTorquePercentage.
Definition: mock_dxl_driver.cpp:268
ttl_driver::MockDxlDriver::scan
int scan(std::vector< uint8_t > &id_list) override
MockDxlDriver::scan.
Definition: mock_dxl_driver.cpp:104
ttl_driver::MockDxlDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
MockDxlDriver::readTemperature.
Definition: mock_dxl_driver.cpp:454
ttl_driver::MockDxlDriver::readLoad
int readLoad(uint8_t id, uint16_t &present_load) override
MockDxlDriver::readLoad.
Definition: mock_dxl_driver.cpp:880
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:695
ttl_driver::MockDxlDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t data) override
MockDxlDriver::writeControlMode.
Definition: mock_dxl_driver.cpp:767
ttl_driver::MockDxlDriver::writeShutdownConfiguration
int writeShutdownConfiguration(uint8_t id, uint8_t configuration) override
MockDxlDriver::writeShutdownConfiguration.
Definition: mock_dxl_driver.cpp:207
ttl_driver::MockDxlDriver::reboot
int reboot(uint8_t id) override
MockDxlDriver::reboot.
Definition: mock_dxl_driver.cpp:115
ttl_driver::MockDxlDriver::writePID
int writePID(uint8_t id, const std::vector< uint16_t > &data) override
MockDxlDriver::writePID.
Definition: mock_dxl_driver.cpp:741
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:634
ttl_driver::MockDxlDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
MockDxlDriver::writePositionGoal.
Definition: mock_dxl_driver.cpp:286
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:588
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:499
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:334
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:549
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:856
ttl_driver::MockDxlDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
MockDxlDriver::checkModelNumber.
Definition: mock_dxl_driver.cpp:84
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:301
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:385
ttl_driver::MockDxlDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
MockDxlDriver::readMinPosition.
Definition: mock_dxl_driver.cpp:236
ttl_driver::MockDxlDriver::GROUP_SYNC_REDONDANT_ID
static constexpr int GROUP_SYNC_REDONDANT_ID
Definition: mock_dxl_driver.hpp:125
ttl_driver::MockDxlDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
MockDxlDriver::readMaxPosition.
Definition: mock_dxl_driver.cpp:251
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:149
ttl_driver::MockDxlDriver::interpretErrorState
std::string interpretErrorState(uint32_t hw_state) const override
MockDxlDriver::interpretErrorState.
Definition: mock_dxl_driver.cpp:121
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:131
ttl_driver::MockDxlDriver::writeLed
int writeLed(uint8_t id, uint8_t led_value) override
MockDxlDriver::writeLed.
Definition: mock_dxl_driver.cpp:802
ttl_driver::MockDxlDriver::_id_list
std::vector< uint8_t > _id_list
Definition: mock_dxl_driver.hpp:123
ttl_driver::MockDxlDriver::ping
int ping(uint8_t id) override
MockDxlDriver::ping.
Definition: mock_dxl_driver.cpp:57
ttl_driver::MockDxlDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
MockDxlDriver::changeId.
Definition: mock_dxl_driver.cpp:165
ttl_driver::MockDxlDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockDxlDriver::readHwErrorStatus.
Definition: mock_dxl_driver.cpp:484
ttl_driver::MockDxlDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
MockDxlDriver::readVoltage.
Definition: mock_dxl_driver.cpp:469
ttl_driver::MockDxlDriver::writeStartupConfiguration
int writeStartupConfiguration(uint8_t id, uint8_t value) override
MockDxlDriver::writeStartupConfiguration.
Definition: mock_dxl_driver.cpp:179
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:316
ttl_driver::MockDxlDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
MockDxlDriver::readFirmwareVersion.
Definition: mock_dxl_driver.cpp:221
ttl_driver::AbstractTtlDriver::PING_WRONG_MODEL_NUMBER
static constexpr int PING_WRONG_MODEL_NUMBER
Definition: abstract_ttl_driver.hpp:101
ttl_driver::MockDxlDriver::LEN_ID_DATA_NOT_SAME
static constexpr int LEN_ID_DATA_NOT_SAME
Definition: mock_dxl_driver.hpp:126
ttl_driver::MockDxlDriver::readPID
int readPID(uint8_t id, std::vector< uint16_t > &data) override
MockDxlDriver::readPID.
Definition: mock_dxl_driver.cpp:714
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:910
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:665
ttl_driver::MockDxlDriver::_fake_data
std::shared_ptr< FakeTtlData > _fake_data
Definition: mock_dxl_driver.hpp:122
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:818
ttl_driver::MockDxlDriver::writeTorqueGoal
int writeTorqueGoal(uint8_t id, uint16_t torque) override
MockDxlDriver::writeTorqueGoal.
Definition: mock_dxl_driver.cpp:840
ttl_driver::MockDxlDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
MockDxlDriver::readPosition.
Definition: mock_dxl_driver.cpp:426
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:657
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:524
ttl_driver::MockDxlDriver::getModelNumber
int getModelNumber(uint8_t id, uint16_t &model_number) override
MockDxlDriver::getModelNumber.
Definition: mock_dxl_driver.cpp:70
ttl_driver::MockDxlDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &data) override
MockDxlDriver::readControlMode.
Definition: mock_dxl_driver.cpp:783
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:355
ttl_driver::MockDxlDriver::readMoving
int readMoving(uint8_t id, uint8_t &status) override
MockDxlDriver::readMoving.
Definition: mock_dxl_driver.cpp:895
ttl_driver::MockDxlDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
MockDxlDriver::readVelocity.
Definition: mock_dxl_driver.cpp:441


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