17 #ifndef ABSTRACT_DXL_DRIVER_HPP
18 #define ABSTRACT_DXL_DRIVER_HPP
27 #include "common/model/single_motor_cmd.hpp"
28 #include "common/model/synchronize_motor_cmd.hpp"
38 std::shared_ptr<dynamixel::PacketHandler> packetHandler);
42 std::string
str()
const override;
44 int writeSingleCmd(
const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd)
override;
45 int writeSyncCmd(
int type,
const std::vector<uint8_t> &ids,
const std::vector<uint32_t> ¶ms)
override;
56 virtual int readLoad(uint8_t
id, uint16_t &present_load) = 0;
57 virtual int syncReadLoad(
const std::vector<uint8_t> &id_list, std::vector<uint16_t> &load_list) = 0;
59 virtual int readPID(uint8_t
id, std::vector<uint16_t> &data) = 0;
61 virtual int readMoving(uint8_t
id, uint8_t &status) = 0;
64 virtual int writePID(uint8_t
id,
const std::vector<uint16_t> &data) = 0;
66 virtual int writeLed(uint8_t
id, uint8_t led_value) = 0;
67 virtual int syncWriteLed(
const std::vector<uint8_t> &id_list,
const std::vector<uint8_t> &led_list) = 0;
70 virtual int syncWriteTorqueGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint16_t> &torque_list) = 0;
75 #endif // ABSTRACT_DXL_DRIVER_HPP