17 #ifndef END_EFFECTOR_DRIVER_HPP
18 #define END_EFFECTOR_DRIVER_HPP
30 #include "common/model/end_effector_command_type_enum.hpp"
31 #include "common/model/end_effector_state.hpp"
33 using ::common::model::EEndEffectorCommandType;
41 template <
typename reg_type = EndEffectorReg>
46 std::shared_ptr<dynamixel::PacketHandler> packetHandler);
52 std::string
str()
const override;
58 int readVoltage(uint8_t
id,
double &voltage)
override;
61 int syncReadFirmwareVersion(
const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
override;
62 int syncReadTemperature(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
override;
63 int syncReadVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
64 int syncReadRawVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
66 std::vector<std::pair<double, uint8_t> > &data_list)
override;
68 int syncReadHwErrorStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
override;
76 int syncReadButtonsStatus(
const uint8_t &
id, std::vector<common::model::EActionType> &action_list)
override;
97 template <
typename reg_type>
99 std::shared_ptr<dynamixel::PacketHandler> packetHandler)
112 template <
typename reg_type>
115 return common::model::HardwareTypeEnum(reg_type::motor_type).toString() +
" : " +
124 template <
typename reg_type>
127 int ping_result = getModelNumber(
id, model_number);
129 if (ping_result == COMM_SUCCESS)
131 if (model_number && model_number != reg_type::MODEL_NUMBER)
133 return PING_WRONG_MODEL_NUMBER;
146 template <
typename reg_type>
149 int res = COMM_RX_FAIL;
151 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
152 version = interpretFirmwareVersion(data);
164 template <
typename reg_type>
167 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
176 template <
typename reg_type>
179 uint16_t voltage_mV = 0;
180 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
181 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
191 template <
typename reg_type>
194 hardware_error_status = 0;
195 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
204 template <
typename reg_type>
206 std::vector<std::string> &firmware_list)
209 firmware_list.clear();
210 std::vector<uint32_t> data_list{};
211 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
212 for (
auto const &data : data_list)
213 firmware_list.emplace_back(interpretFirmwareVersion(data));
223 template <
typename reg_type>
225 std::vector<uint8_t> &temperature_list)
227 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list,
237 template <
typename reg_type>
240 voltage_list.clear();
241 std::vector<uint16_t> v_read;
242 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
243 for (
auto const &v : v_read)
244 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
254 template <
typename reg_type>
256 std::vector<double> &voltage_list)
258 voltage_list.clear();
259 std::vector<uint16_t> v_read;
260 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
261 for (
auto const &v : v_read)
262 voltage_list.emplace_back(
static_cast<double>(v));
272 template <
typename reg_type>
274 std::vector<std::pair<double, uint8_t> > &data_list)
278 std::vector<std::array<uint8_t, 3> > raw_data;
279 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
281 for (
auto const &data : raw_data)
284 auto voltage =
static_cast<double>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
287 uint8_t temperature = data.at(2);
289 data_list.emplace_back(std::make_pair(voltage, temperature));
301 template <
typename reg_type>
303 std::vector<uint8_t> &hw_error_list)
305 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
316 template <
typename reg_type>
320 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_0_STATUS,
id, status);
321 action = interpretActionValue(status);
331 template <
typename reg_type>
335 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_1_STATUS,
id, status);
336 action = interpretActionValue(status);
346 template <
typename reg_type>
350 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_2_STATUS,
id, status);
351 action = interpretActionValue(status);
361 template <
typename reg_type>
363 std::vector<common::model::EActionType> &action_list)
365 std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3> > data_array_list;
367 res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_BUTTON_0_STATUS, {
id },
369 if (res == COMM_SUCCESS && data_array_list.size() == 1)
371 for (
auto data : data_array_list.at(0))
373 action_list.push_back(interpretActionValue(data));
386 template <
typename reg_type>
389 return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X,
id, x_value);
398 template <
typename reg_type>
401 return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y,
id, y_value);
410 template <
typename reg_type>
413 return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z,
id, z_value);
422 template <
typename reg_type>
427 int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS,
id, value);
428 if (COMM_SUCCESS == res)
430 status = (value > 0) ?
true :
false;
441 template <
typename reg_type>
445 int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_IN,
id, value);
446 in = (value > 0) ?
true :
false;
456 template <
typename reg_type>
459 return COMM_TX_ERROR;
468 template <
typename reg_type>
471 return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUT,
id,
static_cast<uint8_t
>(out));
480 template <
typename reg_type>
483 return write<typename reg_type::TYPE_COLLISION_THRESHOLD>(reg_type::ADDR_COLLISION_THRESHOLD,
id,
484 static_cast<uint8_t
>(thresh));
493 template <
typename reg_type>
496 std::cout <<
"writeCollisionThreshAlgo2 not implemented for end effector" << std::endl;
503 #endif // EndEffectorDriver