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 
80 int MockEndEffectorDriver::checkModelNumber(uint8_t id, uint16_t& model_number)
81 {
82  int ping_result = getModelNumber(id, model_number);
83 
84  if (ping_result == COMM_SUCCESS)
85  {
86  if (model_number)
87  {
89  }
90  }
91 
92  return ping_result;
93 }
94 
100 int MockEndEffectorDriver::scan(std::vector<uint8_t> &id_list)
101 {
102  id_list = _fake_data->full_id_list;
103  return COMM_SUCCESS;
104 }
105 
111 int MockEndEffectorDriver::reboot(uint8_t id) { return ping(id); }
112 
119 int MockEndEffectorDriver::readFirmwareVersion(uint8_t id, std::string &version)
120 {
121  if (COMM_SUCCESS != ping(id))
122  return COMM_RX_FAIL;
123 
124  version = _fake_data->end_effector.firmware;
125  return COMM_SUCCESS;
126 }
127 
128 // ram read
129 
136 int MockEndEffectorDriver::readTemperature(uint8_t id, uint8_t &temperature)
137 {
138  if (COMM_SUCCESS != ping(id))
139  return COMM_RX_FAIL;
140 
141  temperature = _fake_data->end_effector.temperature;
142  return COMM_SUCCESS;
143 }
144 
151 int MockEndEffectorDriver::readVoltage(uint8_t id, double &voltage)
152 {
153  if (COMM_SUCCESS != ping(id))
154  return COMM_RX_FAIL;
155 
156  voltage = static_cast<double>(voltage) / EndEffectorReg::VOLTAGE_CONVERSION;
157  return COMM_SUCCESS;
158 }
159 
166 int MockEndEffectorDriver::readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status)
167 {
168  if (COMM_SUCCESS != ping(id))
169  return COMM_RX_FAIL;
170 
171  hardware_error_status = 0;
172  return COMM_SUCCESS;
173 }
174 
181 int MockEndEffectorDriver::syncReadFirmwareVersion(const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
182 {
183  int res = 0;
184  firmware_list.clear();
185  for (size_t i = 0; i < id_list.size(); i++)
186  firmware_list.emplace_back(_fake_data->end_effector.firmware);
187  return res;
188 }
189 
196 int MockEndEffectorDriver::syncReadTemperature(const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
197 {
198  temperature_list.clear();
199  for (size_t i = 0; i < id_list.size(); i++)
200  temperature_list.emplace_back(_fake_data->end_effector.temperature);
201  return COMM_SUCCESS;
202 }
203 
210 int MockEndEffectorDriver::syncReadVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
211 {
212  voltage_list.clear();
213  for (size_t i = 0; i < id_list.size(); i++)
214  voltage_list.emplace_back(static_cast<double>(_fake_data->end_effector.voltage) / EndEffectorReg::VOLTAGE_CONVERSION);
215  return COMM_SUCCESS;
216 }
217 
224 int MockEndEffectorDriver::syncReadRawVoltage(const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
225 {
226  voltage_list.clear();
227  for (size_t i = 0; i < id_list.size(); i++)
228  voltage_list.emplace_back(static_cast<double>(_fake_data->end_effector.voltage));
229  return COMM_SUCCESS;
230 }
231 
238 int MockEndEffectorDriver::syncReadHwStatus(const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list)
239 {
240  data_list.clear();
241 
242  for (size_t i = 0; i < id_list.size(); i++)
243  {
244  double voltage = _fake_data->end_effector.voltage;
245  uint8_t temperature = _fake_data->end_effector.temperature;
246  data_list.emplace_back(std::make_pair(voltage, temperature));
247  }
248  return COMM_SUCCESS;
249 }
250 
257 int MockEndEffectorDriver::syncReadHwErrorStatus(const std::vector<uint8_t> & /*id_list*/, std::vector<uint8_t> &hw_error_list)
258 {
259  hw_error_list.clear();
260  hw_error_list.emplace_back(0);
261  return COMM_SUCCESS;
262 }
263 
264 // buttons status
265 
272 int MockEndEffectorDriver::readButton0Status(uint8_t id, common::model::EActionType &action)
273 {
274  if (COMM_SUCCESS != ping(id))
275  return COMM_RX_FAIL;
276 
277  action = interpretActionValue(_fake_data->end_effector.button0_action);
278  return COMM_SUCCESS;
279 }
280 
287 int MockEndEffectorDriver::readButton1Status(uint8_t id, common::model::EActionType &action)
288 {
289  if (COMM_SUCCESS != ping(id))
290  return COMM_RX_FAIL;
291 
292  action = interpretActionValue(_fake_data->end_effector.button1_action);
293  return COMM_SUCCESS;
294 }
295 
302 int MockEndEffectorDriver::readButton2Status(uint8_t id, common::model::EActionType &action)
303 {
304  if (COMM_SUCCESS != ping(id))
305  return COMM_RX_FAIL;
306 
307  action = interpretActionValue(_fake_data->end_effector.button2_action);
308  return COMM_SUCCESS;
309 }
310 
317 int MockEndEffectorDriver::syncReadButtonsStatus(const uint8_t &id, std::vector<common::model::EActionType> &action_list)
318 {
319  action_list.clear();
320 
321  if (COMM_SUCCESS != ping(id))
322  return COMM_RX_FAIL;
323 
324  action_list.emplace_back(interpretActionValue(_fake_data->end_effector.button0_action));
325  action_list.emplace_back(interpretActionValue(_fake_data->end_effector.button1_action));
326  action_list.emplace_back(interpretActionValue(_fake_data->end_effector.button2_action));
327 
328  return COMM_SUCCESS;
329 }
330 
331 // accelerometers and collision
332 
339 int MockEndEffectorDriver::readAccelerometerXValue(uint8_t id, uint32_t &x_value)
340 {
341  if (COMM_SUCCESS != ping(id))
342  return COMM_RX_FAIL;
343 
344  x_value = _fake_data->end_effector.x_value;
345  return COMM_SUCCESS;
346 }
347 
354 int MockEndEffectorDriver::readAccelerometerYValue(uint8_t id, uint32_t &y_value)
355 {
356  if (COMM_SUCCESS != ping(id))
357  return COMM_RX_FAIL;
358 
359  y_value = _fake_data->end_effector.y_value;
360  return COMM_SUCCESS;
361 }
362 
369 int MockEndEffectorDriver::readAccelerometerZValue(uint8_t id, uint32_t &z_value)
370 {
371  if (COMM_SUCCESS != ping(id))
372  return COMM_RX_FAIL;
373 
374  z_value = _fake_data->end_effector.z_value;
375  return COMM_SUCCESS;
376 }
377 
384 int MockEndEffectorDriver::readCollisionStatus(uint8_t id, bool &status)
385 {
386  if (COMM_SUCCESS != ping(id))
387  return COMM_RX_FAIL;
388 
389  status = false;
390  return COMM_SUCCESS;
391 }
392 
400 {
401  if (COMM_SUCCESS != ping(id))
402  return COMM_RX_FAIL;
403  return COMM_SUCCESS;
404 }
405 
413 {
414  if (COMM_SUCCESS != ping(id))
415  return COMM_RX_FAIL;
416  return COMM_SUCCESS;
417 }
418 
426 {
427  if (COMM_SUCCESS != ping(id))
428  return COMM_RX_FAIL;
429 
430  in = _fake_data->end_effector.digital_input;
431  return COMM_SUCCESS;
432 }
433 
441 {
442  if (COMM_SUCCESS != ping(id))
443  return COMM_RX_FAIL;
444 
445  _fake_data->end_effector.digital_input = in;
446  return COMM_SUCCESS;
447 }
448 
456 {
457  if (COMM_SUCCESS != ping(id))
458  return COMM_RX_FAIL;
459 
460  _fake_data->end_effector.digital_output = out;
461  return COMM_SUCCESS;
462 }
463 
464 } // 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:339
ttl_driver::MockEndEffectorDriver::readCollisionStatus
int readCollisionStatus(uint8_t id, bool &status) override
MockEndEffectorDriver::readCollisionStatus.
Definition: mock_end_effector_driver.cpp:384
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:111
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:238
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:100
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:412
ttl_driver::MockEndEffectorDriver::readButton2Status
int readButton2Status(uint8_t id, common::model::EActionType &action) override
MockEndEffectorDriver::readButton2Status.
Definition: mock_end_effector_driver.cpp:302
ttl_driver::MockEndEffectorDriver::readDigitalInput
int readDigitalInput(uint8_t id, bool &in) override
MockEndEffectorDriver::readDigitalInput.
Definition: mock_end_effector_driver.cpp:425
ttl_driver::MockEndEffectorDriver::readButton1Status
int readButton1Status(uint8_t id, common::model::EActionType &action) override
MockEndEffectorDriver::readButton1Status.
Definition: mock_end_effector_driver.cpp:287
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:181
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:257
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:317
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:455
ttl_driver::MockEndEffectorDriver::checkModelNumber
int checkModelNumber(uint8_t id, uint16_t &model_number) override
MockEndEffectorDriver::checkModelNumber.
Definition: mock_end_effector_driver.cpp:80
ttl_driver::MockEndEffectorDriver::writeCollisionThresh
int writeCollisionThresh(uint8_t id, int thresh) override
MockEndEffectorDriver::writeCollisionThresh.
Definition: mock_end_effector_driver.cpp:399
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:369
ttl_driver::MockEndEffectorDriver::readTemperature
int readTemperature(uint8_t id, uint8_t &temperature) override
MockEndEffectorDriver::readTemperature.
Definition: mock_end_effector_driver.cpp:136
ttl_driver::MockEndEffectorDriver::readFirmwareVersion
int readFirmwareVersion(uint8_t id, std::string &version) override
MockEndEffectorDriver::readFirmwareVersion.
Definition: mock_end_effector_driver.cpp:119
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:224
ttl_driver::MockEndEffectorDriver::readHwErrorStatus
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockEndEffectorDriver::readHwErrorStatus.
Definition: mock_end_effector_driver.cpp:166
ttl_driver::MockEndEffectorDriver::readAccelerometerYValue
int readAccelerometerYValue(uint8_t id, uint32_t &y_value) override
MockEndEffectorDriver::readAccelerometerYValue.
Definition: mock_end_effector_driver.cpp:354
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:272
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:196
ttl_driver::MockEndEffectorDriver::_fake_data
std::shared_ptr< FakeTtlData > _fake_data
Definition: mock_end_effector_driver.hpp:94
ttl_driver::MockEndEffectorDriver::writeDigitalInput
int writeDigitalInput(uint8_t id, bool in) override
MockEndEffectorDriver::writeDigitalInput stores the digital input value in the fake data.
Definition: mock_end_effector_driver.cpp:440
ttl_driver::MockEndEffectorDriver::readVoltage
int readVoltage(uint8_t id, double &_voltage) override
MockEndEffectorDriver::readVoltage.
Definition: mock_end_effector_driver.cpp:151
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:210


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