Go to the documentation of this file.
17 #ifndef MOCK_STEPPER_DRIVER_HPP
18 #define MOCK_STEPPER_DRIVER_HPP
27 #include "common/model/stepper_calibration_status_enum.hpp"
41 std::string
str()
const override;
47 int ping(uint8_t
id)
override;
49 uint16_t& model_number)
override;
50 int scan(std::vector<uint8_t>& id_list)
override;
51 int reboot(uint8_t
id)
override;
54 int changeId(uint8_t
id, uint8_t new_id)
override;
67 int syncWriteTorquePercentage(
const std::vector<uint8_t> &id_list,
const std::vector<uint8_t> &torque_percentage_list)
override;
68 int syncWritePositionGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &position_list)
override;
69 int syncWriteVelocityGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &velocity_list)
override;
74 int readVoltage(uint8_t
id,
double &voltage)
override;
77 int readPosition(uint8_t
id, uint32_t &present_position)
override;
78 int readVelocity(uint8_t
id, uint32_t &present_velocity)
override;
80 int syncReadPosition(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
override;
81 int syncReadVelocity(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
override;
82 int syncReadJointStatus(
const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2> >& data_array)
override;
84 int syncReadFirmwareVersion(
const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
override;
85 int syncReadTemperature(
const std::vector<uint8_t> &id_list, std::vector<uint8_t>& temperature_list)
override;
86 int syncReadVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
87 int syncReadRawVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
88 int syncReadHwStatus(
const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t> >& data_list)
override;
90 int syncReadHwErrorStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
override;
101 int writeHomingSetup(uint8_t
id, uint8_t direction, uint8_t stall_threshold)
override;
104 int syncReadHomingStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list)
override;
135 #endif // MOCK_STEPPER_DRIVER_HPP
int syncReadHomingStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list) override
MockStepperDriver::syncReadHomingStatus.
int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold) override
MockStepperDriver::writeHomingDirection.
int syncWriteVelocityGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list) override
MockStepperDriver::syncWriteVelocityGoal.
int writePositionGoal(uint8_t id, uint32_t position) override
MockStepperDriver::writePositionGoal.
int syncWriteTorquePercentage(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list) override
MockStepperDriver::syncWriteTorquePercentage.
int checkModelNumber(uint8_t id) override
MockStepperDriver::checkModelNumber.
int syncReadJointStatus(const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 > > &data_array) override
StepperDriver::syncReadJointStatus.
int readMinPosition(uint8_t id, uint32_t &min_pos) override
MockStepperDriver::readMinPosition.
int syncReadVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockStepperDriver::syncReadVoltage.
uint8_t _calibration_status
static constexpr int CALIBRATION_IN_PROGRESS
MockStepperDriver(std::shared_ptr< FakeTtlData > data)
MockStepperDriver::MockStepperDriver.
int syncWriteHomingAbsPosition(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position) override
MockStepperDriver::syncWriteHomingAbsPosition.
int syncReadHwErrorStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
MockStepperDriver::syncReadHwErrorStatus.
std::shared_ptr< FakeTtlData > _fake_data
static constexpr int CALIBRATION_IDLE
int syncReadTemperature(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
MockStepperDriver::syncReadTemperature.
int readVelocity(uint8_t id, uint32_t &present_velocity) override
MockStepperDriver::readVelocity.
int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data) override
MockStepperDriver::writeVelocityProfile.
int syncReadHwStatus(const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t > > &data_list) override
MockStepperDriver::syncReadHwStatus.
int ping(uint8_t id) override
MockStepperDriver::ping.
std::string str() const override
MockStepperDriver::str.
int syncReadHomingAbsPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position) override
MockStepperDriver::syncReadHomingAbsPosition.
int readPosition(uint8_t id, uint32_t &present_position) override
MockStepperDriver::readPosition.
int syncReadVelocity(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list) override
MockStepperDriver::syncReadVelocity.
int scan(std::vector< uint8_t > &id_list) override
MockStepperDriver::scan.
int writeTorquePercentage(uint8_t id, uint8_t torque_percentage) override
MockStepperDriver::writeTorquePercentage.
int readHomingStatus(uint8_t id, uint8_t &status) override
MockStepperDriver::readHomingStatus.
int readControlMode(uint8_t id, uint8_t &mode) override
int syncReadRawVoltage(const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
MockStepperDriver::syncReadVoltage.
int syncWritePositionGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list) override
MockStepperDriver::syncWritePositionGoal.
static constexpr int CALIBRATION_ERROR
static constexpr int CALIBRATION_SUCCESS
static constexpr int GROUP_SYNC_REDONDANT_ID
int readMaxPosition(uint8_t id, uint32_t &max_pos) override
MockStepperDriver::readMaxPosition.
int readTemperature(uint8_t id, uint8_t &temperature) override
MockStepperDriver::readTemperature.
int writeControlMode(uint8_t id, uint8_t mode) override
int syncReadFirmwareVersion(const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
MockStepperDriver::syncReadFirmwareVersion.
int readFirmwareVersion(uint8_t id, std::string &version) override
MockStepperDriver::readFirmwareVersion.
int changeId(uint8_t id, uint8_t new_id) override
MockStepperDriver::changeId.
int readFirmwareRunning(uint8_t id, bool &is_running) override
MockStepperDriver::readFirmwareRunning.
int readHwErrorStatus(uint8_t id, uint8_t &hardware_error_status) override
MockStepperDriver::readHwErrorStatus.
int writeVelocityGoal(uint8_t id, uint32_t velocity) override
MockStepperDriver::writeVelocityGoal.
int readVoltage(uint8_t id, double &voltage) override
MockStepperDriver::readVoltage.
int getModelNumber(uint8_t id, uint16_t &model_number) override
MockStepperDriver::getModelNumber.
float velocityUnit() const override
writeVelocityGoal: define the unit of the velocity in RPM
int startHoming(uint8_t id) override
MockStepperDriver::startHoming.
bool init()
MockStepperDriver::init.
int syncReadPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list) override
MockStepperDriver::syncReadPosition.
int readVelocityProfile(uint8_t id, std::vector< uint32_t > &data_list) override
MockStepperDriver::readVelocityProfile.
static constexpr int LEN_ID_DATA_NOT_SAME
std::vector< uint8_t > _id_list
int reboot(uint8_t id) override
MockStepperDriver::reboot.
ttl_driver
Author(s): Clement Cocquempot
autogenerated on Wed May 21 2025 08:30:14