mock_stepper_driver.hpp
Go to the documentation of this file.
1 /*
2 mock_stepper_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_STEPPER_DRIVER_HPP
18 #define MOCK_STEPPER_DRIVER_HPP
19 
20 #include <memory>
21 #include <vector>
22 #include <string>
23 #include <iostream>
24 #include <sstream>
25 
27 #include "common/model/stepper_calibration_status_enum.hpp"
29 
30 namespace ttl_driver
31 {
32 
37 {
38 public:
39  MockStepperDriver(std::shared_ptr<FakeTtlData> data);
40 
41  std::string str() const override;
42 
43  // AbstractTtlDriver interface : we cannot define them globally in AbstractTtlDriver
44  // as it is needed here for polymorphism (AbstractTtlDriver cannot be a template class and does not
45  // have access to reg_type). So it seems like a duplicate of DxlDriver
46 public:
47  int ping(uint8_t id) override;
48  int getModelNumber(uint8_t id, uint16_t &model_number) override;
49  int scan(std::vector<uint8_t> &id_list) override;
50  int reboot(uint8_t id) override;
51 
52  // eeprom write
53  int changeId(uint8_t id, uint8_t new_id) override;
54 
55  // eeprom read
56  int checkModelNumber(uint8_t id, uint16_t &model_number) override;
57  int readFirmwareVersion(uint8_t id, std::string &version) override;
58  int readMinPosition(uint8_t id, uint32_t &min_pos) override;
59  int readMaxPosition(uint8_t id, uint32_t &max_pos) override;
60 
61  // ram write
62  int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override;
63  int writePositionGoal(uint8_t id, uint32_t position) override;
64  int writeVelocityGoal(uint8_t id, uint32_t velocity) override;
65 
66  int syncWriteTorquePercentage(const std::vector<uint8_t> &id_list,
67  const std::vector<uint8_t> &torque_percentage_list) override;
68  int syncWritePositionGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &position_list) override;
69  int syncWriteVelocityGoal(const std::vector<uint8_t> &id_list, const std::vector<uint32_t> &velocity_list) override;
70 
71  // ram read
72 
73  int readTemperature(uint8_t id, uint8_t &temperature) override;
74  int readVoltage(uint8_t id, double &voltage) override;
75  int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override;
76 
77  int readPosition(uint8_t id, uint32_t &present_position) override;
78  int readVelocity(uint8_t id, uint32_t &present_velocity) override;
79 
80  int syncReadPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list) override;
81  int syncReadVelocity(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list) override;
82  int syncReadJointStatus(const std::vector<uint8_t> &id_list,
83  std::vector<std::array<uint32_t, 2> > &data_array) override;
84 
85  int syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list) override;
86  int syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list) override;
87  int syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
88  int syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list) override;
89  int syncReadHwStatus(const std::vector<uint8_t> &id_list,
90  std::vector<std::pair<double, uint8_t> > &data_list) override;
91 
92  int syncReadHwErrorStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list) override;
93 
94  // AbstractStepperDriver interface
95 public:
96  int readControlMode(uint8_t id, uint8_t &mode) override;
97  int writeControlMode(uint8_t id, uint8_t mode) override;
98 
99  int readVelocityProfile(uint8_t id, std::vector<uint32_t> &data_list) override;
100  int writeVelocityProfile(uint8_t id, const std::vector<uint32_t> &data) override;
101 
102  int startHoming(uint8_t id) override;
103  int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) override;
104 
105  int readHomingStatus(uint8_t id, uint8_t &status) override;
106  int syncReadHomingStatus(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list) override;
107 
108  int readFirmwareRunning(uint8_t id, bool &is_running) override;
109 
110  int syncReadHomingAbsPosition(const std::vector<uint8_t> &id_list, std::vector<uint32_t> &abs_position) override;
111  int syncWriteHomingAbsPosition(const std::vector<uint8_t> &id_list,
112  const std::vector<uint32_t> &abs_position) override;
113 
114  float velocityUnit() const override;
115 
116 private:
117  bool init();
118 
119  std::shared_ptr<FakeTtlData> _fake_data;
120  std::vector<uint8_t> _id_list;
121 
123  // fake time for calibration
124  int _fake_time{ 0 };
125 
126  static constexpr int GROUP_SYNC_REDONDANT_ID = 10;
127  static constexpr int LEN_ID_DATA_NOT_SAME = 20;
128 
129  static constexpr int CALIBRATION_IDLE = 0;
130  static constexpr int CALIBRATION_IN_PROGRESS = 1;
131  static constexpr int CALIBRATION_SUCCESS = 2;
132  static constexpr int CALIBRATION_ERROR = 3;
133 };
134 
135 } // namespace ttl_driver
136 #endif // MOCK_STEPPER_DRIVER_HPP
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:817
ttl_driver::MockStepperDriver::writeHomingSetup
int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) override
MockStepperDriver::writeHomingDirection.
Definition: mock_stepper_driver.cpp:784
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:322
ttl_driver::MockStepperDriver::writePositionGoal
int writePositionGoal(uint8_t id, uint32_t position) override
MockStepperDriver::writePositionGoal.
Definition: mock_stepper_driver.cpp:238
ttl_driver::MockStepperDriver::_fake_time
int _fake_time
Definition: mock_stepper_driver.hpp:124
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:269
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:470
ttl_driver::MockStepperDriver::readMinPosition
int readMinPosition(uint8_t id, uint32_t &min_pos) override
MockStepperDriver::readMinPosition.
Definition: mock_stepper_driver.cpp:192
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:569
ttl_driver::MockStepperDriver::_calibration_status
uint8_t _calibration_status
Definition: mock_stepper_driver.hpp:122
ttl_driver::MockStepperDriver::CALIBRATION_IN_PROGRESS
static constexpr int CALIBRATION_IN_PROGRESS
Definition: mock_stepper_driver.hpp:130
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:887
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:670
ttl_driver::MockStepperDriver::_fake_data
std::shared_ptr< FakeTtlData > _fake_data
Definition: mock_stepper_driver.hpp:119
abstract_stepper_driver.hpp
ttl_driver::MockStepperDriver::CALIBRATION_IDLE
static constexpr int CALIBRATION_IDLE
Definition: mock_stepper_driver.hpp:129
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:540
ttl_driver::MockStepperDriver::readVelocity
int readVelocity(uint8_t id, uint32_t &present_velocity) override
MockStepperDriver::readVelocity.
Definition: mock_stepper_driver.cpp:361
ttl_driver::MockStepperDriver::writeVelocityProfile
int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data) override
MockStepperDriver::writeVelocityProfile.
Definition: mock_stepper_driver.cpp:741
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:627
ttl_driver::MockStepperDriver::ping
int ping(uint8_t id) override
MockStepperDriver::ping.
Definition: mock_stepper_driver.cpp:84
ttl_driver::MockStepperDriver::str
std::string str() const override
MockStepperDriver::str.
Definition: mock_stepper_driver.cpp:71
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:861
ttl_driver::MockStepperDriver::readPosition
int readPosition(uint8_t id, uint32_t &present_position) override
MockStepperDriver::readPosition.
Definition: mock_stepper_driver.cpp:346
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:443
ttl_driver::MockStepperDriver
The StepperDriver class.
Definition: mock_stepper_driver.hpp:36
ttl_driver::MockStepperDriver::scan
int scan(std::vector< uint8_t > &id_list) override
MockStepperDriver::scan.
Definition: mock_stepper_driver.cpp:121
ttl_driver::AbstractStepperDriver
Definition: abstract_stepper_driver.hpp:34
ttl_driver::MockStepperDriver::writeTorquePercentage
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
MockStepperDriver::writeTorquePercentage.
Definition: mock_stepper_driver.cpp:224
ttl_driver::MockStepperDriver::readHomingStatus
int readHomingStatus(uint8_t id, uint8_t &status) override
MockStepperDriver::readHomingStatus.
Definition: mock_stepper_driver.cpp:795
ttl_driver::MockStepperDriver::readControlMode
int readControlMode(uint8_t id, uint8_t &mode) override
Definition: mock_stepper_driver.cpp:689
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:598
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:291
ttl_driver::MockStepperDriver::CALIBRATION_ERROR
static constexpr int CALIBRATION_ERROR
Definition: mock_stepper_driver.hpp:132
ttl_driver::MockStepperDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
MockStepperDriver::checkModelNumber.
Definition: mock_stepper_driver.cpp:109
ttl_driver::MockStepperDriver::CALIBRATION_SUCCESS
static constexpr int CALIBRATION_SUCCESS
Definition: mock_stepper_driver.hpp:131
ttl_driver::MockStepperDriver::GROUP_SYNC_REDONDANT_ID
static constexpr int GROUP_SYNC_REDONDANT_ID
Definition: mock_stepper_driver.hpp:126
ttl_driver::MockStepperDriver::readMaxPosition
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
MockStepperDriver::readMaxPosition.
Definition: mock_stepper_driver.cpp:207
ttl_driver::MockStepperDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
MockStepperDriver::readTemperature.
Definition: mock_stepper_driver.cpp:374
ttl_driver::MockStepperDriver::writeControlMode
int writeControlMode(uint8_t id, uint8_t mode) override
Definition: mock_stepper_driver.cpp:698
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:512
ttl_driver::MockStepperDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
MockStepperDriver::readFirmwareVersion.
Definition: mock_stepper_driver.cpp:177
ttl_driver::MockStepperDriver::changeId
int changeId(uint8_t id, uint8_t new_id) override
MockStepperDriver::changeId.
Definition: mock_stepper_driver.cpp:144
ttl_driver::MockStepperDriver::readFirmwareRunning
int readFirmwareRunning(uint8_t id, bool &is_running) override
MockStepperDriver::readFirmwareRunning.
Definition: mock_stepper_driver.cpp:846
ttl_driver::MockStepperDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockStepperDriver::readHwErrorStatus.
Definition: mock_stepper_driver.cpp:404
ttl_driver::MockStepperDriver::writeVelocityGoal
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
MockStepperDriver::writeVelocityGoal.
Definition: mock_stepper_driver.cpp:254
ttl_driver::MockStepperDriver::readVoltage
int readVoltage(uint8_t id, double &voltage) override
MockStepperDriver::readVoltage.
Definition: mock_stepper_driver.cpp:389
ttl_driver::MockStepperDriver::getModelNumber
int getModelNumber(uint8_t id, uint16_t &model_number) override
MockStepperDriver::getModelNumber.
Definition: mock_stepper_driver.cpp:97
ttl_driver::MockStepperDriver::velocityUnit
float velocityUnit() const override
writeVelocityGoal: define the unit of the velocity in RPM
Definition: mock_stepper_driver.cpp:909
ttl_driver::MockStepperDriver::startHoming
int startHoming(uint8_t id) override
MockStepperDriver::startHoming.
Definition: mock_stepper_driver.cpp:767
ttl_driver::MockStepperDriver::init
bool init()
MockStepperDriver::init.
Definition: mock_stepper_driver.cpp:48
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:416
ttl_driver::MockStepperDriver::readVelocityProfile
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
MockStepperDriver::readVelocityProfile.
Definition: mock_stepper_driver.cpp:713
ttl_driver::MockStepperDriver::LEN_ID_DATA_NOT_SAME
static constexpr int LEN_ID_DATA_NOT_SAME
Definition: mock_stepper_driver.hpp:127
ttl_driver::MockStepperDriver::_id_list
std::vector< uint8_t > _id_list
Definition: mock_stepper_driver.hpp:120
ttl_driver::MockStepperDriver::reboot
int reboot(uint8_t id) override
MockStepperDriver::reboot.
Definition: mock_stepper_driver.cpp:133
fake_ttl_data.hpp


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