Go to the documentation of this file.
69 model_number =
_fake_data->end_effector.model_number;
82 uint16_t model_number = 0;
85 if (ping_result == COMM_SUCCESS)
122 if (COMM_SUCCESS !=
ping(
id))
139 if (COMM_SUCCESS !=
ping(
id))
142 temperature =
_fake_data->end_effector.temperature;
154 if (COMM_SUCCESS !=
ping(
id))
169 if (COMM_SUCCESS !=
ping(
id))
172 hardware_error_status = 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);
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);
213 voltage_list.clear();
214 for (
size_t i = 0; i < id_list.size(); i++)
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));
243 for (
size_t i = 0; i < id_list.size(); i++)
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));
260 hw_error_list.clear();
261 hw_error_list.emplace_back(0);
275 if (COMM_SUCCESS !=
ping(
id))
290 if (COMM_SUCCESS !=
ping(
id))
305 if (COMM_SUCCESS !=
ping(
id))
322 if (COMM_SUCCESS !=
ping(
id))
342 if (COMM_SUCCESS !=
ping(
id))
357 if (COMM_SUCCESS !=
ping(
id))
372 if (COMM_SUCCESS !=
ping(
id))
387 if (COMM_SUCCESS !=
ping(
id))
402 if (COMM_SUCCESS !=
ping(
id))
415 if (COMM_SUCCESS !=
ping(
id))
428 if (COMM_SUCCESS !=
ping(
id))
443 if (COMM_SUCCESS !=
ping(
id))
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 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 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