Go to the documentation of this file.
17 #ifndef MOCK_END_EFFECTOR_DRIVER_HPP
18 #define MOCK_END_EFFECTOR_DRIVER_HPP
31 #include "common/model/action_type_enum.hpp"
33 #include "common/model/end_effector_command_type_enum.hpp"
34 #include "common/model/end_effector_state.hpp"
51 std::string
str()
const override;
57 int readVoltage(uint8_t
id,
double &_voltage)
override;
60 int syncReadFirmwareVersion(
const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
override;
61 int syncReadTemperature(
const std::vector<uint8_t> &id_list, std::vector<uint8_t>& temperature_list)
override;
62 int syncReadVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
63 int syncReadRawVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
64 int syncReadHwStatus(
const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t> >& data_list)
override;
66 int syncReadHwErrorStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
override;
69 int ping(uint8_t
id)
override;
71 uint16_t& model_number)
override;
72 int scan(std::vector<uint8_t> &id_list)
override;
73 int reboot(uint8_t
id)
override;
79 int syncReadButtonsStatus(
const uint8_t&
id, std::vector<common::model::EActionType>& action_list)
override;
98 #endif // MockEndEffectorDriver
int readAccelerometerXValue(uint8_t id, uint32_t &x_value) override
MockEndEffectorDriver::readAccelerometerXValue.
int readCollisionStatus(uint8_t id, bool &status) override
MockEndEffectorDriver::readCollisionStatus.
std::string str() const override
MockEndEffectorDriver::str.
int reboot(uint8_t id) override
MockEndEffectorDriver::reboot.
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t > > &data_list) override
MockEndEffectorDriver::syncReadHwStatus.
int scan(std::vector< uint8_t > &id_list) override
MockEndEffectorDriver::scan.
int getModelNumber(uint8_t id, uint16_t &model_number) override
MockEndEffectorDriver::getModelNumber.
int writeCollisionThreshAlgo2(uint8_t id, int thresh) override
MockEndEffectorDriver::writeCollisionThreshAlgo2.
int readButton2Status(uint8_t id, common::model::EActionType &action) override
MockEndEffectorDriver::readButton2Status.
int readDigitalInput(uint8_t id, bool &in) override
MockEndEffectorDriver::readDigitalInput.
int readButton1Status(uint8_t id, common::model::EActionType &action) override
MockEndEffectorDriver::readButton1Status.
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
MockEndEffectorDriver::syncReadFirmwareVersion.
MockEndEffectorDriver(std::shared_ptr< FakeTtlData > data)
MockEndEffectorDriver::EndEffectorDriver.
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
MockEndEffectorDriver::syncReadHwErrorStatus.
int syncReadButtonsStatus(const uint8_t &id, std::vector< common::model::EActionType > &action_list) override
MockEndEffectorDriver::syncReadButtonsStatus.
int writeDigitalOutput(uint8_t id, bool out) override
MockEndEffectorDriver::writeDigitalOutput.
The MockEndEffectorDriver class.
int writeCollisionThresh(uint8_t id, int thresh) override
MockEndEffectorDriver::writeCollisionThresh.
int readAccelerometerZValue(uint8_t id, uint32_t &z_value) override
MockEndEffectorDriver::readAccelerometerZValue.
int readTemperature(uint8_t id, uint8_t &temperature) override
MockEndEffectorDriver::readTemperature.
The AbstractEndEffectorDriver class.
int readFirmwareVersion(uint8_t id, std::string &version) override
MockEndEffectorDriver::readFirmwareVersion.
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockEndEffectorDriver::syncReadRawVoltage.
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockEndEffectorDriver::readHwErrorStatus.
int checkModelNumber(uint8_t id) override
MockEndEffectorDriver::checkModelNumber.
int readAccelerometerYValue(uint8_t id, uint32_t &y_value) override
MockEndEffectorDriver::readAccelerometerYValue.
int ping(uint8_t id) override
MockEndEffectorDriver::ping.
int readButton0Status(uint8_t id, common::model::EActionType &action) override
MockEndEffectorDriver::readButton0Status.
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
MockEndEffectorDriver::syncReadTemperature.
std::shared_ptr< FakeTtlData > _fake_data
int readVoltage(uint8_t id, double &_voltage) override
MockEndEffectorDriver::readVoltage.
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockEndEffectorDriver::syncReadVoltage.
ttl_driver
Author(s): Clement Cocquempot
autogenerated on Wed May 21 2025 08:30:14