mock_end_effector_driver.cpp
Go to the documentation of this file.
1 /*
2 mock_end_effector_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 
20 #include <cstddef>
21 #include <memory>
22 #include <string>
23 #include <utility>
24 #include <vector>
25 
26 namespace ttl_driver
27 {
28 // definition of methods
29 
33 MockEndEffectorDriver::MockEndEffectorDriver(std::shared_ptr<FakeTtlData> data) : _fake_data(std::move(data)) {}
34 
35 //*****************************
36 // AbstractTtlDriver interface
37 //*****************************
38 
43 std::string MockEndEffectorDriver::str() const
44 {
45  return common::model::HardwareTypeEnum(EndEffectorReg::motor_type).toString() + " : " + ttl_driver::AbstractEndEffectorDriver::str();
46 }
47 
54 {
55  if (std::find(_fake_data->full_id_list.begin(), _fake_data->full_id_list.end(), id) != _fake_data->full_id_list.end())
56  return COMM_SUCCESS;
57  return COMM_TX_FAIL;
58 }
59 
66 int MockEndEffectorDriver::getModelNumber(uint8_t id, uint16_t &model_number)
67 {
68  if (_fake_data->end_effector.id == id)
69  model_number = _fake_data->end_effector.model_number;
70  else
71  return COMM_RX_FAIL;
72  return COMM_SUCCESS;
73 }
74 
81 {
82  uint16_t model_number = 0;
83  int ping_result = getModelNumber(id, model_number);
84 
85  if (ping_result == COMM_SUCCESS)
86  {
87  if (model_number)
88  {
90  }
91  }
92 
93  return ping_result;
94 }
95 
101 int MockEndEffectorDriver::scan(std::vector<uint8_t> &id_list)
102 {
103  id_list = _fake_data->full_id_list;
104  return COMM_SUCCESS;
105 }
106 
112 int MockEndEffectorDriver::reboot(uint8_t id) { return ping(id); }
113 
120 int MockEndEffectorDriver::readFirmwareVersion(uint8_t id, std::string &version)
121 {
122  if (COMM_SUCCESS != ping(id))
123  return COMM_RX_FAIL;
124 
125  version = _fake_data->end_effector.firmware;
126  return COMM_SUCCESS;
127 }
128 
129 // ram read
130 
137 int MockEndEffectorDriver::readTemperature(uint8_t id, uint8_t &temperature)
138 {
139  if (COMM_SUCCESS != ping(id))
140  return COMM_RX_FAIL;
141 
142  temperature = _fake_data->end_effector.temperature;
143  return COMM_SUCCESS;
144 }
145 
152 int MockEndEffectorDriver::readVoltage(uint8_t id, double &voltage)
153 {
154  if (COMM_SUCCESS != ping(id))
155  return COMM_RX_FAIL;
156 
157  voltage = static_cast<double>(voltage) / EndEffectorReg::VOLTAGE_CONVERSION;
158  return COMM_SUCCESS;
159 }
160 
167 int MockEndEffectorDriver::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
168 {
169  if (COMM_SUCCESS != ping(id))
170  return COMM_RX_FAIL;
171 
172  hardware_error_status = 0;
173  return COMM_SUCCESS;
174 }
175 
182 int MockEndEffectorDriver::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
183 {
184  int res = 0;
185  firmware_list.clear();
186  for (size_t i = 0; i < id_list.size(); i++)
187  firmware_list.emplace_back(_fake_data->end_effector.firmware);
188  return res;
189 }
190 
197 int MockEndEffectorDriver::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
198 {
199  temperature_list.clear();
200  for (size_t i = 0; i < id_list.size(); i++)
201  temperature_list.emplace_back(_fake_data->end_effector.temperature);
202  return COMM_SUCCESS;
203 }
204 
211 int MockEndEffectorDriver::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
212 {
213  voltage_list.clear();
214  for (size_t i = 0; i < id_list.size(); i++)
215  voltage_list.emplace_back(static_cast<double>(_fake_data->end_effector.voltage) / EndEffectorReg::VOLTAGE_CONVERSION);
216  return COMM_SUCCESS;
217 }
218 
225 int MockEndEffectorDriver::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
226 {
227  voltage_list.clear();
228  for (size_t i = 0; i < id_list.size(); i++)
229  voltage_list.emplace_back(static_cast<double>(_fake_data->end_effector.voltage));
230  return COMM_SUCCESS;
231 }
232 
239 int MockEndEffectorDriver::syncReadHwStatus(const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list)
240 {
241  data_list.clear();
242 
243  for (size_t i = 0; i < id_list.size(); i++)
244  {
245  double voltage = _fake_data->end_effector.voltage;
246  uint8_t temperature = _fake_data->end_effector.temperature;
247  data_list.emplace_back(std::make_pair(voltage, temperature));
248  }
249  return COMM_SUCCESS;
250 }
251 
258 int MockEndEffectorDriver::syncReadHwErrorStatus(const std::vector<uint8_t> & /*id_list*/, std::vector<uint8_t> &hw_error_list)
259 {
260  hw_error_list.clear();
261  hw_error_list.emplace_back(0);
262  return COMM_SUCCESS;
263 }
264 
265 // buttons status
266 
273 int MockEndEffectorDriver::readButton0Status(uint8_t id, common::model::EActionType &action)
274 {
275  if (COMM_SUCCESS != ping(id))
276  return COMM_RX_FAIL;
277 
278  action = interpretActionValue(_fake_data->end_effector.button0_action);
279  return COMM_SUCCESS;
280 }
281 
288 int MockEndEffectorDriver::readButton1Status(uint8_t id, common::model::EActionType &action)
289 {
290  if (COMM_SUCCESS != ping(id))
291  return COMM_RX_FAIL;
292 
293  action = interpretActionValue(_fake_data->end_effector.button1_action);
294  return COMM_SUCCESS;
295 }
296 
303 int MockEndEffectorDriver::readButton2Status(uint8_t id, common::model::EActionType &action)
304 {
305  if (COMM_SUCCESS != ping(id))
306  return COMM_RX_FAIL;
307 
308  action = interpretActionValue(_fake_data->end_effector.button2_action);
309  return COMM_SUCCESS;
310 }
311 
318 int MockEndEffectorDriver::syncReadButtonsStatus(const uint8_t &id, std::vector<common::model::EActionType> &action_list)
319 {
320  action_list.clear();
321 
322  if (COMM_SUCCESS != ping(id))
323  return COMM_RX_FAIL;
324 
325  action_list.emplace_back(interpretActionValue(_fake_data->end_effector.button0_action));
326  action_list.emplace_back(interpretActionValue(_fake_data->end_effector.button1_action));
327  action_list.emplace_back(interpretActionValue(_fake_data->end_effector.button2_action));
328 
329  return COMM_SUCCESS;
330 }
331 
332 // accelerometers and collision
333 
340 int MockEndEffectorDriver::readAccelerometerXValue(uint8_t id, uint32_t &x_value)
341 {
342  if (COMM_SUCCESS != ping(id))
343  return COMM_RX_FAIL;
344 
345  x_value = _fake_data->end_effector.x_value;
346  return COMM_SUCCESS;
347 }
348 
355 int MockEndEffectorDriver::readAccelerometerYValue(uint8_t id, uint32_t &y_value)
356 {
357  if (COMM_SUCCESS != ping(id))
358  return COMM_RX_FAIL;
359 
360  y_value = _fake_data->end_effector.y_value;
361  return COMM_SUCCESS;
362 }
363 
370 int MockEndEffectorDriver::readAccelerometerZValue(uint8_t id, uint32_t &z_value)
371 {
372  if (COMM_SUCCESS != ping(id))
373  return COMM_RX_FAIL;
374 
375  z_value = _fake_data->end_effector.z_value;
376  return COMM_SUCCESS;
377 }
378 
385 int MockEndEffectorDriver::readCollisionStatus(uint8_t id, bool &status)
386 {
387  if (COMM_SUCCESS != ping(id))
388  return COMM_RX_FAIL;
389 
390  status = false;
391  return COMM_SUCCESS;
392 }
393 
401 {
402  if (COMM_SUCCESS != ping(id))
403  return COMM_RX_FAIL;
404  return COMM_SUCCESS;
405 }
406 
414 {
415  if (COMM_SUCCESS != ping(id))
416  return COMM_RX_FAIL;
417  return COMM_SUCCESS;
418 }
419 
427 {
428  if (COMM_SUCCESS != ping(id))
429  return COMM_RX_FAIL;
430 
431  in = _fake_data->end_effector.digitalInput;
432  return COMM_SUCCESS;
433 }
434 
442 {
443  if (COMM_SUCCESS != ping(id))
444  return COMM_RX_FAIL;
445 
446  _fake_data->end_effector.DigitalOutput = out;
447  return COMM_SUCCESS;
448 }
449 
450 } // namespace ttl_driver
ttl_driver::MockEndEffectorDriver::readAccelerometerXValue
int readAccelerometerXValue(uint8_t id, uint32_t &x_value) override
MockEndEffectorDriver::readAccelerometerXValue.
Definition: mock_end_effector_driver.cpp:340
ttl_driver::MockEndEffectorDriver::readCollisionStatus
int readCollisionStatus(uint8_t id, bool &status) override
MockEndEffectorDriver::readCollisionStatus.
Definition: mock_end_effector_driver.cpp:385
ttl_driver::MockEndEffectorDriver::str
std::string str() const override
MockEndEffectorDriver::str.
Definition: mock_end_effector_driver.cpp:43
ttl_driver::MockEndEffectorDriver::reboot
int reboot(uint8_t id) override
MockEndEffectorDriver::reboot.
Definition: mock_end_effector_driver.cpp:112
ttl_driver::MockEndEffectorDriver::syncReadHwStatus
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t > > &data_list) override
MockEndEffectorDriver::syncReadHwStatus.
Definition: mock_end_effector_driver.cpp:239
ttl_driver::EndEffectorReg::motor_type
static constexpr common::model::EHardwareType motor_type
Definition: end_effector_reg.hpp:27
ttl_driver::MockEndEffectorDriver::scan
int scan(std::vector< uint8_t > &id_list) override
MockEndEffectorDriver::scan.
Definition: mock_end_effector_driver.cpp:101
mock_end_effector_driver.hpp
ttl_driver::MockEndEffectorDriver::getModelNumber
int getModelNumber(uint8_t id, uint16_t &model_number) override
MockEndEffectorDriver::getModelNumber.
Definition: mock_end_effector_driver.cpp:66
ttl_driver::AbstractEndEffectorDriver::interpretActionValue
common::model::EActionType interpretActionValue(uint32_t value) const
MockEndEffectorDriver::interpretActionValue.
Definition: abstract_end_effector_driver.cpp:103
end_effector_reg.hpp
ttl_driver::MockEndEffectorDriver::writeCollisionThreshAlgo2
int writeCollisionThreshAlgo2(uint8_t id, int thresh) override
MockEndEffectorDriver::writeCollisionThreshAlgo2.
Definition: mock_end_effector_driver.cpp:413
ttl_driver::MockEndEffectorDriver::readButton2Status
int readButton2Status(uint8_t id, common::model::EActionType &action) override
MockEndEffectorDriver::readButton2Status.
Definition: mock_end_effector_driver.cpp:303
ttl_driver::MockEndEffectorDriver::readDigitalInput
int readDigitalInput(uint8_t id, bool &in) override
MockEndEffectorDriver::readDigitalInput.
Definition: mock_end_effector_driver.cpp:426
ttl_driver::MockEndEffectorDriver::readButton1Status
int readButton1Status(uint8_t id, common::model::EActionType &action) override
MockEndEffectorDriver::readButton1Status.
Definition: mock_end_effector_driver.cpp:288
ttl_driver::MockEndEffectorDriver::syncReadFirmwareVersion
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
MockEndEffectorDriver::syncReadFirmwareVersion.
Definition: mock_end_effector_driver.cpp:182
ttl_driver::AbstractEndEffectorDriver::str
std::string str() const override
AbstractEndEffectorDriver::str : build a string describing the object. For debug purpose only.
Definition: abstract_end_effector_driver.cpp:48
ttl_driver::MockEndEffectorDriver::MockEndEffectorDriver
MockEndEffectorDriver(std::shared_ptr< FakeTtlData > data)
MockEndEffectorDriver::EndEffectorDriver.
Definition: mock_end_effector_driver.cpp:33
ttl_driver::EndEffectorReg::VOLTAGE_CONVERSION
static constexpr int VOLTAGE_CONVERSION
Definition: end_effector_reg.hpp:31
ttl_driver::MockEndEffectorDriver::syncReadHwErrorStatus
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
MockEndEffectorDriver::syncReadHwErrorStatus.
Definition: mock_end_effector_driver.cpp:258
ttl_driver::MockEndEffectorDriver::syncReadButtonsStatus
int syncReadButtonsStatus(const uint8_t &id, std::vector< common::model::EActionType > &action_list) override
MockEndEffectorDriver::syncReadButtonsStatus.
Definition: mock_end_effector_driver.cpp:318
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::MockEndEffectorDriver::writeDigitalOutput
int writeDigitalOutput(uint8_t id, bool out) override
MockEndEffectorDriver::writeDigitalOutput.
Definition: mock_end_effector_driver.cpp:441
ttl_driver::MockEndEffectorDriver::writeCollisionThresh
int writeCollisionThresh(uint8_t id, int thresh) override
MockEndEffectorDriver::writeCollisionThresh.
Definition: mock_end_effector_driver.cpp:400
ttl_driver::AbstractTtlDriver::PING_WRONG_MODEL_NUMBER
static constexpr int PING_WRONG_MODEL_NUMBER
Definition: abstract_ttl_driver.hpp:101
ttl_driver::MockEndEffectorDriver::readAccelerometerZValue
int readAccelerometerZValue(uint8_t id, uint32_t &z_value) override
MockEndEffectorDriver::readAccelerometerZValue.
Definition: mock_end_effector_driver.cpp:370
ttl_driver::MockEndEffectorDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
MockEndEffectorDriver::readTemperature.
Definition: mock_end_effector_driver.cpp:137
ttl_driver::MockEndEffectorDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
MockEndEffectorDriver::readFirmwareVersion.
Definition: mock_end_effector_driver.cpp:120
ttl_driver::MockEndEffectorDriver::syncReadRawVoltage
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockEndEffectorDriver::syncReadRawVoltage.
Definition: mock_end_effector_driver.cpp:225
ttl_driver::MockEndEffectorDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockEndEffectorDriver::readHwErrorStatus.
Definition: mock_end_effector_driver.cpp:167
ttl_driver::MockEndEffectorDriver::checkModelNumber
int checkModelNumber(uint8_t id) override
MockEndEffectorDriver::checkModelNumber.
Definition: mock_end_effector_driver.cpp:80
ttl_driver::MockEndEffectorDriver::readAccelerometerYValue
int readAccelerometerYValue(uint8_t id, uint32_t &y_value) override
MockEndEffectorDriver::readAccelerometerYValue.
Definition: mock_end_effector_driver.cpp:355
ttl_driver::MockEndEffectorDriver::ping
int ping(uint8_t id) override
MockEndEffectorDriver::ping.
Definition: mock_end_effector_driver.cpp:53
ttl_driver::MockEndEffectorDriver::readButton0Status
int readButton0Status(uint8_t id, common::model::EActionType &action) override
MockEndEffectorDriver::readButton0Status.
Definition: mock_end_effector_driver.cpp:273
ttl_driver::MockEndEffectorDriver::syncReadTemperature
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
MockEndEffectorDriver::syncReadTemperature.
Definition: mock_end_effector_driver.cpp:197
ttl_driver::MockEndEffectorDriver::_fake_data
std::shared_ptr< FakeTtlData > _fake_data
Definition: mock_end_effector_driver.hpp:93
ttl_driver::MockEndEffectorDriver::readVoltage
int readVoltage(uint8_t id, double &_voltage) override
MockEndEffectorDriver::readVoltage.
Definition: mock_end_effector_driver.cpp:152
ttl_driver::MockEndEffectorDriver::syncReadVoltage
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockEndEffectorDriver::syncReadVoltage.
Definition: mock_end_effector_driver.cpp:211


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