mock_dxl_driver.hpp
Go to the documentation of this file.
1 /*
2 mock_dxl_driver.hpp
3 Copyright (C) 2020 Niryo
4 All rights reserved.
5 This program is free software: you can redistribute it and/or modify
6 it under the terms of the GNU General Public License as published by
7 the Free Software Foundation, either version 3 of the License, or
8 (at your option) any later version.
9 This program is distributed in the hope that it will be useful,
10 but WITHOUT ANY WARRANTY; without even the implied warranty of
11 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 GNU General Public License for more details.
13 You should have received a copy of the GNU General Public License
14 along with this program. If not, see <http:// www.gnu.org/licenses/>.
15 */
16 
17 #ifndef MOCK_DXL_DRIVER_HPP
18 #define MOCK_DXL_DRIVER_HPP
19 
20 #include <memory>
21 #include <vector>
22 #include <string>
23 #include <iostream>
24 #include <sstream>
25 #include <cassert>
26 
27 #include "abstract_dxl_driver.hpp"
28 #include "common/common_defs.hpp"
30 
31 namespace ttl_driver
32 {
33 
38  {
39  public:
40  MockDxlDriver(std::shared_ptr<FakeTtlData> data);
41 
42  std::string str() const override;
43 
44  // AbstractTtlDriver interface : we cannot define them globally in AbstractTtlDriver
45  // as it is needed here for polymorphism (AbstractTtlDriver cannot be a template class and does not
46  // have access to reg_type). So it seems like a duplicate of StepperDriver
47  public:
48  int ping(uint8_t id) override;
49  int getModelNumber(uint8_t id,
50  uint16_t &model_number) override;
51  int scan(std::vector<uint8_t> &id_list) override;
52  int reboot(uint8_t id) override;
53 
54  std::string interpretErrorState(uint32_t hw_state) const override;
55 
56  int readCustom(uint16_t address, uint8_t data_len, uint8_t id, uint32_t &data) override;
57  int writeCustom(uint16_t address, uint8_t data_len, uint8_t id, uint32_t data) override;
58 
59  // eeprom write
60  int changeId(uint8_t id, uint8_t new_id) override;
61  int writeStartupConfiguration(uint8_t id, uint8_t value) override;
62  int writeTemperatureLimit(uint8_t id, uint8_t temperature_limit) override;
63  int writeShutdownConfiguration(uint8_t id, uint8_t configuration) override;
64 
65  // eeprom read
66  int checkModelNumber(uint8_t id) override;
67  int readFirmwareVersion(uint8_t id, std::string &version) override;
68  int readMinPosition(uint8_t id, uint32_t &min_pos) override;
69  int readMaxPosition(uint8_t id, uint32_t &max_pos) override;
70 
71  // ram write
72  int writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data_list) override;
73 
74  int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override;
75  int writePositionGoal(uint8_t id, uint32_t position) override;
76  int writeVelocityGoal(uint8_t id, uint32_t velocity) override;
77 
78  int syncWriteTorquePercentage(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &torque_percentage_list) override;
79  int syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list) override;
80  int syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list) override;
81 
82  // ram read
83  int readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list) override;
84 
85  int readPosition(uint8_t id, uint32_t &present_position) override;
86  int readVelocity(uint8_t id, uint32_t &present_velocity) override;
87  int readTemperature(uint8_t id, uint8_t &temperature) override;
88  int readVoltage(uint8_t id, double &voltage) override;
89  int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override;
90 
91  int syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list) override;
92  int syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list) override;
93  int syncReadJointStatus(const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2>> &data_array_list) override;
94 
95  int syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list) override;
96  int syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list) override;
97  int syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
98  int syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
99  int syncReadHwStatus(const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list) override;
100 
101  int syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list) override;
102 
103  // AbstractDxlDriver interface
104  public:
105  int readPID(uint8_t id, std::vector<uint16_t> &data) override;
106  int writePID(uint8_t id, const std::vector<uint16_t> &data) override;
107 
108  int writeControlMode(uint8_t id, uint8_t data) override;
109  int readControlMode(uint8_t id, uint8_t &data) override;
110 
111  int writeLed(uint8_t id, uint8_t led_value) override;
112  int syncWriteLed(const std::vector<uint8_t> &id_list, const std::vector<uint8_t> &led_list) override;
113  int writeTorqueGoal(uint8_t id, uint16_t torque) override;
114  int syncWriteTorqueGoal(const std::vector<uint8_t> &id_list, const std::vector<uint16_t> &torque_list) override;
115 
116  int readLoad(uint8_t id, uint16_t &present_load) override;
117  int syncReadLoad(const std::vector<uint8_t> &id_list, std::vector<uint16_t> &load_list) override;
118 
119  int readMoving(uint8_t id, uint8_t &status) override;
120 
121  private:
122  std::shared_ptr<FakeTtlData> _fake_data;
123  std::vector<uint8_t> _id_list;
124 
125  static constexpr int GROUP_SYNC_REDONDANT_ID = 10;
126  static constexpr int LEN_ID_DATA_NOT_SAME = 20;
127 
128  // AbstractTtlDriver interface
129  protected:
130  std::string interpretFirmwareVersion(uint32_t fw_version) const override;
131  };
132 
133 } // DynamixelDriver
134 
135 #endif // MOCK_DXL_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:612
ttl_driver::MockDxlDriver::MockDxlDriver
MockDxlDriver(std::shared_ptr< FakeTtlData > data)
MockDxlDriver::MockDxlDriver.
Definition: mock_dxl_driver.cpp:35
ttl_driver::MockDxlDriver::writeTemperatureLimit
int writeTemperatureLimit(uint8_t id, uint8_t temperature_limit) override
MockDxlDriver::writeTemperatureLimit.
Definition: mock_dxl_driver.cpp:194
ttl_driver::MockDxlDriver::interpretFirmwareVersion
std::string interpretFirmwareVersion(uint32_t fw_version) const override
MockDxlDriver::interpretFirmwareVersion.
Definition: mock_dxl_driver.cpp:924
ttl_driver::MockDxlDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
Definition: mock_dxl_driver.cpp:407
ttl_driver::MockDxlDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
MockDxlDriver::writeTorquePercentage.
Definition: mock_dxl_driver.cpp:269
ttl_driver::MockDxlDriver::scan
int scan(std::vector< uint8_t > &id_list) override
MockDxlDriver::scan.
Definition: mock_dxl_driver.cpp:105
ttl_driver::MockDxlDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
MockDxlDriver::readTemperature.
Definition: mock_dxl_driver.cpp:455
ttl_driver::MockDxlDriver::readLoad
int readLoad(uint8_t id, uint16_t &present_load) override
MockDxlDriver::readLoad.
Definition: mock_dxl_driver.cpp:881
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:696
ttl_driver::MockDxlDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t data) override
MockDxlDriver::writeControlMode.
Definition: mock_dxl_driver.cpp:768
ttl_driver::MockDxlDriver::writeShutdownConfiguration
int writeShutdownConfiguration(uint8_t id, uint8_t configuration) override
MockDxlDriver::writeShutdownConfiguration.
Definition: mock_dxl_driver.cpp:208
ttl_driver::MockDxlDriver::reboot
int reboot(uint8_t id) override
MockDxlDriver::reboot.
Definition: mock_dxl_driver.cpp:116
ttl_driver::MockDxlDriver::writePID
int writePID(uint8_t id, const std::vector< uint16_t > &data) override
MockDxlDriver::writePID.
Definition: mock_dxl_driver.cpp:742
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:635
ttl_driver::MockDxlDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
MockDxlDriver::writePositionGoal.
Definition: mock_dxl_driver.cpp:287
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:589
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:500
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:335
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:550
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:857
ttl_driver::AbstractDxlDriver
Definition: abstract_dxl_driver.hpp:33
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:302
ttl_driver::MockDxlDriver
The DxlDriver class.
Definition: mock_dxl_driver.hpp:37
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:386
ttl_driver::MockDxlDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
MockDxlDriver::readMinPosition.
Definition: mock_dxl_driver.cpp:237
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:252
abstract_dxl_driver.hpp
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:150
ttl_driver::MockDxlDriver::interpretErrorState
std::string interpretErrorState(uint32_t hw_state) const override
MockDxlDriver::interpretErrorState.
Definition: mock_dxl_driver.cpp:122
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:132
ttl_driver::MockDxlDriver::writeLed
int writeLed(uint8_t id, uint8_t led_value) override
MockDxlDriver::writeLed.
Definition: mock_dxl_driver.cpp:803
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:166
ttl_driver::MockDxlDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockDxlDriver::readHwErrorStatus.
Definition: mock_dxl_driver.cpp:485
ttl_driver::MockDxlDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
MockDxlDriver::readVoltage.
Definition: mock_dxl_driver.cpp:470
ttl_driver::MockDxlDriver::writeStartupConfiguration
int writeStartupConfiguration(uint8_t id, uint8_t value) override
MockDxlDriver::writeStartupConfiguration.
Definition: mock_dxl_driver.cpp:180
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:317
ttl_driver::MockDxlDriver::checkModelNumber
int checkModelNumber(uint8_t id) override
MockDxlDriver::checkModelNumber.
Definition: mock_dxl_driver.cpp:84
ttl_driver::MockDxlDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
MockDxlDriver::readFirmwareVersion.
Definition: mock_dxl_driver.cpp:222
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:715
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:911
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:666
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:819
ttl_driver::MockDxlDriver::writeTorqueGoal
int writeTorqueGoal(uint8_t id, uint16_t torque) override
MockDxlDriver::writeTorqueGoal.
Definition: mock_dxl_driver.cpp:841
ttl_driver::MockDxlDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
MockDxlDriver::readPosition.
Definition: mock_dxl_driver.cpp:427
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:658
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:525
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:784
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:356
ttl_driver::MockDxlDriver::readMoving
int readMoving(uint8_t id, uint8_t &status) override
MockDxlDriver::readMoving.
Definition: mock_dxl_driver.cpp:896
ttl_driver::MockDxlDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
MockDxlDriver::readVelocity.
Definition: mock_dxl_driver.cpp:442
fake_ttl_data.hpp


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