17 #ifndef ABSTRACT_MOTOR_DRIVER_HPP
18 #define ABSTRACT_MOTOR_DRIVER_HPP
25 #include "dynamixel_sdk/dynamixel_sdk.h"
26 #include "common/common_defs.hpp"
27 #include "common/model/hardware_type_enum.hpp"
43 std::shared_ptr<dynamixel::PacketHandler> packetHandler);
47 std::string
str()
const override;
53 virtual int changeId(uint8_t
id, uint8_t new_id) = 0;
68 virtual int syncWriteTorquePercentage(
const std::vector<uint8_t>& id_list,
const std::vector<uint8_t>& torque_percentage_list) = 0;
69 virtual int syncWritePositionGoal(
const std::vector<uint8_t>& id_list,
const std::vector<uint32_t>& position_list) = 0;
70 virtual int syncWriteVelocityGoal(
const std::vector<uint8_t>& id_list,
const std::vector<uint32_t>& velocity_list) = 0;
76 virtual int readPosition(uint8_t
id, uint32_t& present_position) = 0;
77 virtual int readVelocity(uint8_t
id, uint32_t& present_velocity) = 0;
79 virtual int syncReadPosition(
const std::vector<uint8_t>& id_list, std::vector<uint32_t>& position_list) = 0;
80 virtual int syncReadVelocity(
const std::vector<uint8_t> &id_list, std::vector<uint32_t>& velocity_list) = 0;
81 virtual int syncReadJointStatus(
const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2> >& data_array_list) = 0;
86 #endif // ABSTRACT_MOTOR_DRIVER_HPP