Go to the documentation of this file.
17 #ifndef ABSTRACT_END_EFFECTOR_DRIVER_HPP
18 #define ABSTRACT_END_EFFECTOR_DRIVER_HPP
27 #include "dynamixel_sdk/dynamixel_sdk.h"
28 #include "common/common_defs.hpp"
29 #include "common/model/hardware_type_enum.hpp"
30 #include "common/model/single_motor_cmd.hpp"
31 #include "common/model/abstract_synchronize_motor_cmd.hpp"
33 #include "common/model/action_type_enum.hpp"
47 std::shared_ptr<dynamixel::PacketHandler> packetHandler);
50 virtual int readButton0Status(uint8_t
id, common::model::EActionType& action) = 0;
51 virtual int readButton1Status(uint8_t
id, common::model::EActionType& action) = 0;
52 virtual int readButton2Status(uint8_t
id, common::model::EActionType& action) = 0;
53 virtual int syncReadButtonsStatus(
const uint8_t&
id, std::vector<common::model::EActionType>& action_list) = 0;
73 std::string
str()
const override;
78 int writeSingleCmd(
const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd)
override;
79 int writeSyncCmd(
int type,
const std::vector<uint8_t> &ids,
const std::vector<uint32_t> ¶ms)
override;
84 #endif // ABSTRACT_END_EFFECTOR_DRIVER_HPP
std::string interpretErrorState(uint32_t hw_state) const override
MockEndEffectorDriver::interpretErrorState.
virtual int writeCollisionThresh(uint8_t id, int thresh)=0
The AbstractTtlDriver class.
std::string interpretFirmwareVersion(uint32_t fw_version) const override
MockEndEffectorDriver::interpretFirmawreVersion.
virtual int readButton1Status(uint8_t id, common::model::EActionType &action)=0
common::model::EActionType interpretActionValue(uint32_t value) const
MockEndEffectorDriver::interpretActionValue.
virtual int syncReadButtonsStatus(const uint8_t &id, std::vector< common::model::EActionType > &action_list)=0
virtual int readDigitalInput(uint8_t id, bool &in)=0
std::string str() const override
AbstractEndEffectorDriver::str : build a string describing the object. For debug purpose only.
virtual int readButton2Status(uint8_t id, common::model::EActionType &action)=0
virtual int writeCollisionThreshAlgo2(uint8_t id, int thresh)=0
AbstractEndEffectorDriver()=default
int writeSingleCmd(const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override
MockEndEffectorDriver::writeSingleCmd.
virtual int readButton0Status(uint8_t id, common::model::EActionType &action)=0
virtual int readAccelerometerZValue(uint8_t id, uint32_t &z_value)=0
The AbstractEndEffectorDriver class.
virtual int readAccelerometerYValue(uint8_t id, uint32_t &y_value)=0
int writeSyncCmd(int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > ¶ms) override
MockEndEffectorDriver::writeSyncCmd.
virtual int readCollisionStatus(uint8_t id, bool &status)=0
virtual int readAccelerometerXValue(uint8_t id, uint32_t &x_value)=0
virtual int writeDigitalOutput(uint8_t id, bool out)=0
ttl_driver
Author(s): Clement Cocquempot
autogenerated on Wed May 21 2025 08:30:14