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;
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;
98 template <
typename reg_type>
101 std::move(packetHandler))
113 template <
typename reg_type>
124 template <
typename reg_type>
127 uint16_t model_number = 0;
128 int ping_result = getModelNumber(
id, model_number);
130 if (ping_result == COMM_SUCCESS)
132 if (model_number && model_number != reg_type::MODEL_NUMBER)
134 return PING_WRONG_MODEL_NUMBER;
147 template <
typename reg_type>
150 int res = COMM_RX_FAIL;
152 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
153 version = interpretFirmwareVersion(data);
165 template <
typename reg_type>
168 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
177 template <
typename reg_type>
180 uint16_t voltage_mV = 0;
181 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
182 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
192 template <
typename reg_type>
195 hardware_error_status = 0;
196 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
205 template <
typename reg_type>
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>
226 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
235 template <
typename reg_type>
238 voltage_list.clear();
239 std::vector<uint16_t> v_read;
240 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
241 for (
auto const &v : v_read)
242 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
252 template <
typename reg_type>
255 voltage_list.clear();
256 std::vector<uint16_t> v_read;
257 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
258 for (
auto const &v : v_read)
259 voltage_list.emplace_back(
static_cast<double>(v));
269 template <
typename reg_type>
271 std::vector<std::pair<double, uint8_t>> &data_list)
275 std::vector<std::array<uint8_t, 3>> raw_data;
276 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
278 for (
auto const &data : raw_data)
281 auto voltage =
static_cast<double>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
284 uint8_t temperature = data.at(2);
286 data_list.emplace_back(std::make_pair(voltage, temperature));
298 template <
typename reg_type>
301 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
312 template <
typename reg_type>
314 common::model::EActionType &action)
317 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_CUSTOM,
id, status);
318 action = interpretActionValue(status);
328 template <
typename reg_type>
332 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_SAVE,
id, status);
333 action = interpretActionValue(status);
343 template <
typename reg_type>
347 int res = read<typename reg_type::TYPE_BUTTON_STATUS>(reg_type::ADDR_STATE_BUTTON_FREEDRIVE,
id, status);
348 action = interpretActionValue(status);
358 template <
typename reg_type>
360 std::vector<common::model::EActionType> &action_list)
362 std::vector<std::array<typename reg_type::TYPE_BUTTON_STATUS, 3>> data_array_list;
364 res = syncReadConsecutiveBytes<typename reg_type::TYPE_BUTTON_STATUS, 3>(reg_type::ADDR_STATE_BUTTON_FREEDRIVE, {
id}, data_array_list);
365 if (res == COMM_SUCCESS && data_array_list.size() == 1)
367 for (
auto data : data_array_list.at(0))
369 action_list.push_back(interpretActionValue(data));
382 template <
typename reg_type>
385 return read<typename reg_type::TYPE_ACCELERO_VALUE_X>(reg_type::ADDR_ACCELERO_VALUE_X,
id, x_value);
394 template <
typename reg_type>
397 return read<typename reg_type::TYPE_ACCELERO_VALUE_Y>(reg_type::ADDR_ACCELERO_VALUE_Y,
id, y_value);
406 template <
typename reg_type>
409 return read<typename reg_type::TYPE_ACCELERO_VALUE_Z>(reg_type::ADDR_ACCELERO_VALUE_Z,
id, z_value);
418 template <
typename reg_type>
423 int res = read<typename reg_type::TYPE_COLLISION_STATUS>(reg_type::ADDR_COLLISION_STATUS,
id, value);
424 if (COMM_SUCCESS == res)
426 status = (value > 0) ?
true :
false;
437 template <
typename reg_type>
441 int res = read<typename reg_type::TYPE_DIGITAL_IN>(reg_type::ADDR_DIGITAL_INPUT,
id, value);
442 in = (value > 0) ?
true :
false;
452 template <
typename reg_type>
455 return write<typename reg_type::TYPE_DIGITAL_OUT>(reg_type::ADDR_DIGITAL_OUTPUT,
id,
static_cast<uint8_t
>(out));
464 template <
typename reg_type>
467 return write<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_1>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_1,
id,
static_cast<uint32_t
>(thresh));
476 template <
typename reg_type>
479 return read<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_1>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_1,
id, thresh);
488 template <
typename reg_type>
491 return write<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_2>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_2,
id,
static_cast<uint32_t
>(thresh));
500 template <
typename reg_type>
503 return read<typename reg_type::TYPE_COLLISION_THRESHOLD_ALGO_2>(reg_type::ADDR_COLLISION_DETECT_THRESH_ALGO_2,
id, thresh);
508 #endif // Ned3ProEndEffectorDriver