Go to the documentation of this file.
17 #ifndef ABSTRACT_STEPPER_DRIVER_HPP
18 #define ABSTRACT_STEPPER_DRIVER_HPP
27 #include "common/model/single_motor_cmd.hpp"
28 #include "common/model/synchronize_motor_cmd.hpp"
29 #include "common/model/stepper_calibration_status_enum.hpp"
39 std::shared_ptr<dynamixel::PacketHandler> packetHandler);
43 std::string
str()
const override;
45 int writeSingleCmd(
const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd)
override;
46 int writeSyncCmd(
int type,
const std::vector<uint8_t> &ids,
const std::vector<uint32_t> ¶ms)
override;
60 virtual int writeHomingSetup(uint8_t
id, uint8_t direction, uint8_t stall_threshold) = 0;
65 virtual int syncReadHomingStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list) = 0;
86 #endif // ABSTRACT_STEPPER_DRIVER_HPP
virtual common::model::EStepperCalibrationStatus interpretHomingData(uint8_t status) const
AbstractStepperDriver::interpretHomingData.
std::string interpretErrorState(uint32_t hw_state) const override
AbstractStepperDriver::interpretErrorState.
virtual int factoryCalibration(const uint8_t id, const uint32_t &command)
AbstractStepperDriver::factoryCalibration.
virtual int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)=0
std::string str() const override
AbstractStepperDriver::str.
virtual int syncReadHomingStatus(const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list)=0
virtual int syncWriteHomingAbsPosition(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position)=0
int writeSingleCmd(const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override
AbstractStepperDriver::writeSingleCmd.
AbstractStepperDriver()=default
std::string interpretFirmwareVersion(uint32_t fw_version) const override
AbstractStepperDriver::interpretFirmwareVersion.
virtual int readHomingStatus(uint8_t id, uint8_t &status)=0
virtual float velocityUnit() const =0
writeVelocityGoal: define the unit of the velocity in RPM
virtual int readFirmwareRunning(uint8_t id, bool &is_running)=0
int writeSyncCmd(int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > ¶ms) override
AbstractStepperDriver::writeSyncCmd.
int readConveyorVelocity(uint8_t id, int32_t &velocity, int32_t &direction)
Returns the velocity of the conveyor in percentage.
virtual int syncReadHomingAbsPosition(const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position)=0
virtual int startHoming(uint8_t id)=0
ttl_driver
Author(s): Clement Cocquempot
autogenerated on Wed May 21 2025 08:30:14