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;
95 template<
typename reg_type>
97 std::shared_ptr<dynamixel::PacketHandler> packetHandler) :
99 std::move(packetHandler))
110 template<
typename reg_type>
121 template<
typename reg_type>
124 uint16_t model_number = 0;
125 int ping_result = getModelNumber(
id, model_number);
127 if (ping_result == COMM_SUCCESS)
129 if (model_number && model_number != reg_type::MODEL_NUMBER)
131 return PING_WRONG_MODEL_NUMBER;
144 template<
typename reg_type>
147 int res = COMM_RX_FAIL;
149 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
150 version = interpretFirmwareVersion(data);
162 template<
typename reg_type>
165 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
174 template<
typename reg_type>
177 uint16_t voltage_mV = 0;
178 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
179 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
189 template<
typename reg_type>
192 hardware_error_status = 0;
193 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
202 template<
typename reg_type>
206 firmware_list.clear();
207 std::vector<uint32_t> data_list{};
208 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
209 for(
auto const& data : data_list)
210 firmware_list.emplace_back(interpretFirmwareVersion(data));
220 template<
typename reg_type>
223 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
232 template<
typename reg_type>
235 voltage_list.clear();
236 std::vector<uint16_t> v_read;
237 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
238 for(
auto const& v : v_read)
239 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
249 template<
typename reg_type>
252 voltage_list.clear();
253 std::vector<uint16_t> v_read;
254 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
255 for(
auto const& v : v_read)
256 voltage_list.emplace_back(
static_cast<double>(v));
266 template<
typename reg_type>
268 std::vector<std::pair<double, uint8_t> > &data_list)
272 std::vector<std::array<uint8_t, 3> > raw_data;
273 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
275 for (
auto const& data : raw_data)
278 auto voltage =
static_cast<double>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
281 uint8_t temperature = data.at(2);
283 data_list.emplace_back(std::make_pair(voltage, temperature));
295 template<
typename reg_type>
298 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
309 template<
typename reg_type>
311 common::model::EActionType& action)
314 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_0_STATUS,
id, status);
315 action = interpretActionValue(status);
325 template<
typename reg_type>
329 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_1_STATUS,
id, status);
330 action = interpretActionValue(status);
340 template<
typename reg_type>
344 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_BUTTON_2_STATUS,
id, status);
345 action = interpretActionValue(status);
355 template<
typename reg_type>
357 std::vector<common::model::EActionType>& action_list)
359 std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3> > data_array_list;
361 res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_BUTTON_0_STATUS, {
id}, data_array_list);
362 if (res == COMM_SUCCESS && data_array_list.size() == 1)
364 for (
auto data : data_array_list.at(0))
366 action_list.push_back(interpretActionValue(data));
379 template<
typename reg_type>
382 return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X,
id, x_value);
391 template<
typename reg_type>
394 return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y,
id, y_value);
403 template<
typename reg_type>
406 return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z,
id, z_value);
415 template<
typename reg_type>
420 int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS,
id, value);
421 if (COMM_SUCCESS == res)
423 status = (value > 0) ?
true :
false;
434 template<
typename reg_type>
438 int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_IN,
id, value);
439 in = (value > 0) ?
true :
false;
449 template<
typename reg_type>
452 return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUT,
id,
static_cast<uint8_t
>(out));
461 template<
typename reg_type>
464 return write<typename reg_type::TYPE_COLLISION_THRESHOLD>(reg_type::ADDR_COLLISION_THRESHOLD,
id,
static_cast<uint8_t
>(thresh));
473 template<
typename reg_type>
476 std::cout <<
"writeCollisionThreshAlgo2 not implemented for end effector" << std::endl;
483 #endif // EndEffectorDriver