17 #ifndef NED3PRO_END_EFFECTOR_DRIVER_HPP
18 #define NED3PRO_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 = Ned3ProEndEffectorReg>
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;
100 template <
typename reg_type>
102 std::shared_ptr<dynamixel::PacketHandler> packetHandler)
115 template <
typename reg_type>
118 return common::model::HardwareTypeEnum(reg_type::motor_type).toString() +
" : " +
127 template <
typename reg_type>
130 int ping_result = getModelNumber(
id, model_number);
132 if (ping_result == COMM_SUCCESS)
134 if (model_number && model_number != reg_type::MODEL_NUMBER)
136 return PING_WRONG_MODEL_NUMBER;
149 template <
typename reg_type>
152 int res = COMM_RX_FAIL;
154 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
155 version = interpretFirmwareVersion(data);
167 template <
typename reg_type>
170 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
179 template <
typename reg_type>
182 uint16_t voltage_mV = 0;
183 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
184 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
194 template <
typename reg_type>
197 hardware_error_status = 0;
198 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
207 template <
typename reg_type>
209 std::vector<std::string> &firmware_list)
212 firmware_list.clear();
213 std::vector<uint32_t> data_list{};
214 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
215 for (
auto const &data : data_list)
216 firmware_list.emplace_back(interpretFirmwareVersion(data));
226 template <
typename reg_type>
228 std::vector<uint8_t> &temperature_list)
230 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list,
240 template <
typename reg_type>
242 std::vector<double> &voltage_list)
244 voltage_list.clear();
245 std::vector<uint16_t> v_read;
246 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
247 for (
auto const &v : v_read)
248 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
258 template <
typename reg_type>
260 std::vector<double> &voltage_list)
262 voltage_list.clear();
263 std::vector<uint16_t> v_read;
264 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
265 for (
auto const &v : v_read)
266 voltage_list.emplace_back(
static_cast<double>(v));
276 template <
typename reg_type>
278 std::vector<std::pair<double, uint8_t>> &data_list)
282 std::vector<std::array<uint8_t, 3>> raw_data;
283 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
285 for (
auto const &data : raw_data)
288 auto voltage =
static_cast<double>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
291 uint8_t temperature = data.at(2);
293 data_list.emplace_back(std::make_pair(voltage, temperature));
305 template <
typename reg_type>
307 std::vector<uint8_t> &hw_error_list)
309 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
320 template <
typename reg_type>
324 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_CUSTOM,
id, status);
325 action = interpretActionValue(status);
335 template <
typename reg_type>
339 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_SAVE,
id, status);
340 action = interpretActionValue(status);
350 template <
typename reg_type>
354 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_FREEDRIVE,
id, status);
355 action = interpretActionValue(status);
365 template <
typename reg_type>
367 std::vector<common::model::EActionType> &action_list)
369 std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3>> data_array_list;
371 res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_STATE_BUTTON_FREEDRIVE,
372 {
id }, data_array_list);
373 if (res == COMM_SUCCESS && data_array_list.size() == 1)
375 for (
auto data : data_array_list.at(0))
377 action_list.push_back(interpretActionValue(data));
390 template <
typename reg_type>
393 return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X,
id, x_value);
402 template <
typename reg_type>
405 return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y,
id, y_value);
414 template <
typename reg_type>
417 return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z,
id, z_value);
426 template <
typename reg_type>
431 int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS,
id, value);
432 if (COMM_SUCCESS == res)
434 status = (value > 0) ?
true :
false;
445 template <
typename reg_type>
449 int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_INPUT,
id, value);
450 in = (value > 0) ?
true :
false;
460 template <
typename reg_type>
463 return COMM_TX_ERROR;
472 template <
typename reg_type>
475 return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUTPUT,
id,
static_cast<uint8_t
>(out));
484 template <
typename reg_type>
487 return write<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_1>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_1,
id,
488 static_cast<uint32_t
>(thresh));
497 template <
typename reg_type>
500 return read<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_1>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_1,
id,
510 template <
typename reg_type>
513 return write<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_2>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_2,
id,
514 static_cast<uint32_t
>(thresh));
523 template <
typename reg_type>
526 return read<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_2>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_2,
id,
532 #endif // Ned3ProEndEffectorDriver