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;
65 int syncReadHwStatus(
const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t> >& data_list)
override;
67 int syncReadHwErrorStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
override;
75 int syncReadButtonsStatus(
const uint8_t&
id, std::vector<common::model::EActionType>& action_list)
override;
96 template<
typename reg_type>
98 std::shared_ptr<dynamixel::PacketHandler> packetHandler) :
100 std::move(packetHandler))
111 template<
typename reg_type>
122 template<
typename reg_type>
125 uint16_t model_number = 0;
126 int ping_result = getModelNumber(
id, model_number);
128 if (ping_result == COMM_SUCCESS)
130 if (model_number && model_number != reg_type::MODEL_NUMBER)
132 return PING_WRONG_MODEL_NUMBER;
145 template<
typename reg_type>
148 int res = COMM_RX_FAIL;
150 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
151 version = interpretFirmwareVersion(data);
163 template<
typename reg_type>
166 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
175 template<
typename reg_type>
178 uint16_t voltage_mV = 0;
179 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
180 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
190 template<
typename reg_type>
193 hardware_error_status = 0;
194 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
203 template<
typename reg_type>
207 firmware_list.clear();
208 std::vector<uint32_t> data_list{};
209 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
210 for(
auto const& data : data_list)
211 firmware_list.emplace_back(interpretFirmwareVersion(data));
221 template<
typename reg_type>
224 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
233 template<
typename reg_type>
236 voltage_list.clear();
237 std::vector<uint16_t> v_read;
238 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
239 for(
auto const& v : v_read)
240 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
250 template<
typename reg_type>
253 voltage_list.clear();
254 std::vector<uint16_t> v_read;
255 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
256 for(
auto const& v : v_read)
257 voltage_list.emplace_back(
static_cast<double>(v));
267 template<
typename reg_type>
269 std::vector<std::pair<double, uint8_t> > &data_list)
273 std::vector<std::array<uint8_t, 3> > raw_data;
274 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
276 for (
auto const& data : raw_data)
279 auto voltage =
static_cast<double>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
282 uint8_t temperature = data.at(2);
284 data_list.emplace_back(std::make_pair(voltage, temperature));
296 template<
typename reg_type>
299 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
310 template<
typename reg_type>
312 common::model::EActionType& action)
315 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_0_STATUS,
id, status);
316 action = interpretActionValue(status);
326 template<
typename reg_type>
330 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_1_STATUS,
id, status);
331 action = interpretActionValue(status);
341 template<
typename reg_type>
345 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_2_STATUS,
id, status);
346 action = interpretActionValue(status);
356 template<
typename reg_type>
358 std::vector<common::model::EActionType>& action_list)
360 std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3> > data_array_list;
362 res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_BUTTON_0_STATUS, {
id}, data_array_list);
363 if (res == COMM_SUCCESS && data_array_list.size() == 1)
365 for (
auto data : data_array_list.at(0))
367 action_list.push_back(interpretActionValue(data));
380 template<
typename reg_type>
383 return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X,
id, x_value);
392 template<
typename reg_type>
395 return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y,
id, y_value);
404 template<
typename reg_type>
407 return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z,
id, z_value);
416 template<
typename reg_type>
421 int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS,
id, value);
422 if (COMM_SUCCESS == res)
424 status = (value > 0) ?
true :
false;
435 template<
typename reg_type>
439 int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_IN,
id, value);
440 in = (value > 0) ?
true :
false;
450 template<
typename reg_type>
453 return COMM_TX_ERROR;
462 template<
typename reg_type>
465 return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUT,
id,
static_cast<uint8_t
>(out));
474 template<
typename reg_type>
477 return write<typename reg_type::TYPE_COLLISION_THRESHOLD>(reg_type::ADDR_COLLISION_THRESHOLD,
id,
static_cast<uint8_t
>(thresh));
486 template<
typename reg_type>
489 std::cout <<
"writeCollisionThreshAlgo2 not implemented for end effector" << std::endl;
496 #endif // EndEffectorDriver