17 #ifndef NED3PRO_STEPPER_DRIVER_HPP
18 #define NED3PRO_STEPPER_DRIVER_HPP
26 #include <ros/duration.h>
27 #include <ros/console.h>
39 template <
typename reg_type = Ned3ProStepperReg>
44 std::shared_ptr<dynamixel::PacketHandler> packetHandler);
48 std::string
str()
const override;
54 int readVoltage(uint8_t
id,
double &voltage)
override;
57 int syncReadFirmwareVersion(
const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
override;
58 int syncReadTemperature(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
override;
59 int syncReadVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
60 int syncReadRawVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
61 int syncReadHwStatus(
const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list)
override;
63 int syncReadHwErrorStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
override;
70 int changeId(uint8_t
id, uint8_t new_id)
override;
76 int syncWriteTorquePercentage(
const std::vector<uint8_t> &id_list,
const std::vector<uint8_t> &torque_percentage_list)
override;
77 int syncWritePositionGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &position_list)
override;
78 int syncWriteVelocityGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &velocity_list)
override;
81 int readPosition(uint8_t
id, uint32_t &present_position)
override;
82 int readVelocity(uint8_t
id, uint32_t &present_velocity)
override;
84 int syncReadPosition(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
override;
85 int syncReadVelocity(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
override;
86 int syncReadJointStatus(
const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2>> &data_array_list)
override;
90 common::model::EStepperCalibrationStatus
interpretHomingData(uint8_t status)
const override;
97 int readStatus(uint8_t
id,
const uint32_t &status);
112 int writeHomingSetup(uint8_t
id, uint8_t direction, uint8_t stall_threshold);
116 int syncReadHomingStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list);
129 template <
typename reg_type>
131 std::shared_ptr<dynamixel::PacketHandler> packetHandler) :
AbstractStepperDriver(std::move(portHandler),
132 std::move(packetHandler))
144 template <
typename reg_type>
156 template <
typename reg_type>
161 int res = write<typename reg_type::TYPE_ID>(reg_type::ADDR_ID,
id, new_id);
162 if (res == COMM_RX_TIMEOUT)
172 template <
typename reg_type>
175 uint16_t model_number = 0;
176 int ping_result = getModelNumber(
id, model_number);
178 if (ping_result == COMM_SUCCESS)
180 if (model_number && model_number != reg_type::MODEL_NUMBER)
182 return PING_WRONG_MODEL_NUMBER;
195 template <
typename reg_type>
200 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
201 version = interpretFirmwareVersion(data);
213 template <
typename reg_type>
216 return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE,
id, torque_percentage);
225 template <
typename reg_type>
228 return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION,
id, position);
238 template <
typename reg_type>
241 return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY,
id, velocity);
250 template <
typename reg_type>
253 return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list, torque_percentage_list);
262 template <
typename reg_type>
265 return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
274 template <
typename reg_type>
277 return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
288 template <
typename reg_type>
291 return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION,
id, present_position);
300 template <
typename reg_type>
303 return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY,
id, present_velocity);
312 template <
typename reg_type>
315 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
324 template <
typename reg_type>
327 uint16_t voltage_mV = 0;
328 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
329 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
339 template <
typename reg_type>
342 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
351 template <
typename reg_type>
354 return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
363 template <
typename reg_type>
366 return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
376 template <
typename reg_type>
378 std::vector<std::array<uint32_t, 2>> &data_array_list)
380 int res = COMM_TX_FAIL;
385 data_array_list.clear();
388 typename reg_type::TYPE_TORQUE_ENABLE torque{1};
389 res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
390 if (COMM_SUCCESS != res)
391 std::cout <<
"#############"
392 " ERROR reading stepper torque in syncReadJointStatus (error "
393 << res <<
")" << std::endl;
398 res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
402 std::vector<uint32_t> position_list;
403 res = syncReadPosition(id_list, position_list);
404 for (
auto p : position_list)
405 data_array_list.emplace_back(std::array<uint32_t, 2>{1, p});
417 template <
typename reg_type>
421 firmware_list.clear();
422 std::vector<uint32_t> data_list{};
423 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
424 for (
auto const &data : data_list)
425 firmware_list.emplace_back(interpretFirmwareVersion(data));
435 template <
typename reg_type>
438 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
447 template <
typename reg_type>
450 voltage_list.clear();
451 std::vector<uint16_t> v_read;
452 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
453 for (
auto const &v : v_read)
454 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
464 template <
typename reg_type>
467 voltage_list.clear();
468 std::vector<uint16_t> v_read;
469 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
470 for (
auto const &v : v_read)
471 voltage_list.emplace_back(
static_cast<double>(v));
481 template <
typename reg_type>
483 std::vector<std::pair<double, uint8_t>> &data_list)
487 std::vector<std::array<uint8_t, 3>> raw_data;
488 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
490 for (
auto const &data : raw_data)
493 auto v =
static_cast<uint16_t
>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
494 auto voltage =
static_cast<double>(v);
497 uint8_t temperature = data.at(2);
499 data_list.emplace_back(std::make_pair(voltage, temperature));
510 template <
typename reg_type>
513 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
525 template <
typename reg_type>
528 enum Ned3ProStepperCalibrationStatus {
529 UNINITIALIZED_MASK = 0,
530 IN_PROGRESS_MASK = 2,
535 return status & IN_PROGRESS_MASK ? common::model::EStepperCalibrationStatus::IN_PROGRESS
536 : status & FAIL_MASK ? common::model::EStepperCalibrationStatus::FAIL
537 : status & OK_MASK ? common::model::EStepperCalibrationStatus::OK
538 : common::model::EStepperCalibrationStatus::FAIL;
547 template <
typename reg_type>
550 return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE,
id, operating_mode);
559 template <
typename reg_type>
562 return write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY,
id, velocity_profile);
571 template <
typename reg_type>
574 return write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION,
id, acceleration_profile);
583 template <
typename reg_type>
586 return write<typename reg_type::TYPE_CONTROL>(reg_type::ADDR_CONTROL,
id, command);
595 template <
typename reg_type>
598 return read<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS,
id, status);
601 template <
typename reg_type>
604 std::vector<uint32_t> status_list_tmp;
605 auto result = syncRead<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id_list, status_list_tmp);
606 for (
const auto &status_tmp : status_list_tmp)
607 status_list.push_back(
static_cast<uint8_t
>(status_tmp));
618 template <
typename reg_type>
621 return read<typename reg_type::TYPE_ENC_ANGLE>(reg_type::ADDR_ENC_ANGLE,
id, enc_angle);
630 template <
typename reg_type>
633 typename reg_type::TYPE_FIRMWARE_RUNNING data{};
634 int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING,
id, data);
640 template <
typename reg_type>
643 ROS_WARN(
"Ned3ProStepperDriver::readMinPosition - Not implemented");
645 return COMM_NOT_AVAILABLE;
648 template <
typename reg_type>
651 ROS_WARN(
"Ned3ProStepperDriver::readMaxPosition - Not implemented");
653 return COMM_NOT_AVAILABLE;
656 template <
typename reg_type>
659 ROS_WARN(
"Ned3ProStepperDriver::readControlMode - Not implemented");
661 return COMM_NOT_AVAILABLE;
664 template <
typename reg_type>
667 ROS_WARN(
"Ned3ProStepperDriver::readVelocityProfile std::vector<uint32_t> &data_list - Not implemented");
669 return COMM_NOT_AVAILABLE;
672 template <
typename reg_type>
676 int res = COMM_RX_FAIL;
677 double wait_duration = 0.05;
680 constexpr
auto ACTIVE_TORQUE_PERCENT = 40;
681 writeTorquePercentage(
id, ACTIVE_TORQUE_PERCENT);
687 ros::Duration(wait_duration).sleep();
688 res = write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY,
id, data_list.at(4));
689 if (res == COMM_SUCCESS)
692 if (res != COMM_SUCCESS)
699 ros::Duration(wait_duration).sleep();
700 res = write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION,
id, data_list.at(3));
701 if (res == COMM_SUCCESS)
708 template <
typename reg_type>
711 ROS_WARN(
"Ned3ProStepperDriver::startHoming - Not implemented");
713 return COMM_NOT_AVAILABLE;
716 template <
typename reg_type>
719 ROS_WARN(
"Ned3ProStepperDriver::writeHomingSetup - Not implemented");
721 return COMM_NOT_AVAILABLE;
725 template <
typename reg_type>
728 ROS_WARN(
"Ned3ProStepperDriver::readHomingStatus - Not implemented");
730 return COMM_NOT_AVAILABLE;
732 template <
typename reg_type>
735 ROS_WARN(
"Ned3ProStepperDriver::syncReadHomingAbsPosition - Not implemented");
737 return COMM_NOT_AVAILABLE;
739 template <
typename reg_type>
742 ROS_WARN(
"Ned3ProStepperDriver::syncWriteHomingAbsPosition - Not implemented");
744 return COMM_NOT_AVAILABLE;
747 template <
typename reg_type>
750 return reg_type::VELOCITY_UNIT;
754 #endif // NED3PRO_STEPPER_DRIVER_HPP