Go to the documentation of this file.
69 model_number =
_fake_data->end_effector.model_number;
84 if (ping_result == COMM_SUCCESS)
121 if (COMM_SUCCESS !=
ping(
id))
138 if (COMM_SUCCESS !=
ping(
id))
141 temperature =
_fake_data->end_effector.temperature;
153 if (COMM_SUCCESS !=
ping(
id))
168 if (COMM_SUCCESS !=
ping(
id))
171 hardware_error_status = 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);
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);
212 voltage_list.clear();
213 for (
size_t i = 0; i < id_list.size(); i++)
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));
242 for (
size_t i = 0; i < id_list.size(); i++)
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));
259 hw_error_list.clear();
260 hw_error_list.emplace_back(0);
274 if (COMM_SUCCESS !=
ping(
id))
289 if (COMM_SUCCESS !=
ping(
id))
304 if (COMM_SUCCESS !=
ping(
id))
321 if (COMM_SUCCESS !=
ping(
id))
341 if (COMM_SUCCESS !=
ping(
id))
356 if (COMM_SUCCESS !=
ping(
id))
371 if (COMM_SUCCESS !=
ping(
id))
386 if (COMM_SUCCESS !=
ping(
id))
401 if (COMM_SUCCESS !=
ping(
id))
414 if (COMM_SUCCESS !=
ping(
id))
427 if (COMM_SUCCESS !=
ping(
id))
442 if (COMM_SUCCESS !=
ping(
id))
457 if (COMM_SUCCESS !=
ping(
id))
460 _fake_data->end_effector.digital_output = out;
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.
static constexpr common::model::EHardwareType motor_type
int scan(std::vector< uint8_t > &id_list) override
MockEndEffectorDriver::scan.
int getModelNumber(uint8_t id, uint16_t &model_number) override
MockEndEffectorDriver::getModelNumber.
common::model::EActionType interpretActionValue(uint32_t value) const
MockEndEffectorDriver::interpretActionValue.
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.
std::string str() const override
AbstractEndEffectorDriver::str : build a string describing the object. For debug purpose only.
MockEndEffectorDriver(std::shared_ptr< FakeTtlData > data)
MockEndEffectorDriver::EndEffectorDriver.
static constexpr int VOLTAGE_CONVERSION
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.
int checkModelNumber(uint8_t id, uint16_t &model_number) override
MockEndEffectorDriver::checkModelNumber.
int writeCollisionThresh(uint8_t id, int thresh) override
MockEndEffectorDriver::writeCollisionThresh.
static constexpr int PING_WRONG_MODEL_NUMBER
int readAccelerometerZValue(uint8_t id, uint32_t &z_value) override
MockEndEffectorDriver::readAccelerometerZValue.
int readTemperature(uint8_t id, uint8_t &temperature) override
MockEndEffectorDriver::readTemperature.
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 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 writeDigitalInput(uint8_t id, bool in) override
MockEndEffectorDriver::writeDigitalInput stores the digital input value in the 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 Tue Jan 13 2026 12:43:08