17 #ifndef STEPPER_DRIVER_HPP
18 #define STEPPER_DRIVER_HPP
25 #include "ros/duration.h"
37 template <
typename reg_type = StepperReg>
41 StepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
42 std::shared_ptr<dynamixel::PacketHandler> packetHandler);
46 std::string
str()
const override;
52 int readVoltage(uint8_t
id,
double &voltage)
override;
55 int syncReadFirmwareVersion(
const std::vector<uint8_t> &id_list, std::vector<std::string> &firmware_list)
override;
56 int syncReadTemperature(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &temperature_list)
override;
57 int syncReadVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
58 int syncReadRawVoltage(
const std::vector<uint8_t> &id_list, std::vector<double> &voltage_list)
override;
60 std::vector<std::pair<double, uint8_t>> &data_list)
override;
62 int syncReadHwErrorStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
override;
69 int changeId(uint8_t
id, uint8_t new_id)
override;
79 const std::vector<uint8_t> &torque_percentage_list)
override;
80 int syncWritePositionGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &position_list)
override;
81 int syncWriteVelocityGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &velocity_list)
override;
84 int readPosition(uint8_t
id, uint32_t &present_position)
override;
85 int readVelocity(uint8_t
id, uint32_t &present_velocity)
override;
87 int syncReadPosition(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
override;
88 int syncReadVelocity(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
override;
90 std::vector<std::array<uint32_t, 2>> &data_array_list)
override;
101 int writeHomingSetup(uint8_t
id, uint8_t direction, uint8_t stall_threshold)
override;
104 int syncReadHomingStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list)
override;
110 const std::vector<uint32_t> &abs_position)
override;
116 int writeA1(uint8_t
id, uint32_t a_1);
117 int writeV1(uint8_t
id, uint32_t v_1);
118 int writeAMax(uint8_t
id, uint32_t a_max);
119 int writeVMax(uint8_t
id, uint32_t v_max);
120 int writeDMax(uint8_t
id, uint32_t d_max);
121 int writeD1(uint8_t
id, uint32_t d_1);
130 template <
typename reg_type>
132 std::shared_ptr<dynamixel::PacketHandler> packetHandler)
145 template <
typename reg_type>
157 template <
typename reg_type>
162 int res = write<typename reg_type::TYPE_ID>(reg_type::ADDR_ID,
id, new_id);
163 if (res == COMM_RX_TIMEOUT)
177 template <
typename reg_type>
180 int ping_result = getModelNumber(
id, model_number);
182 if (ping_result == COMM_SUCCESS && model_number != 0)
185 auto validator = reg_type::createModelNumberValidator();
186 if (!validator->isValid(model_number))
188 ROS_WARN(
"StepperDriver: Model number %u not valid for %s (expected %s)", model_number,
189 common::model::HardwareTypeEnum(reg_type::motor_type).toString().c_str(), validator->describe().c_str());
190 return PING_WRONG_MODEL_NUMBER;
203 template <
typename reg_type>
208 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
209 version = interpretFirmwareVersion(data);
219 template <
typename reg_type>
222 return read<typename reg_type::TYPE_MIN_POSITION_LIMIT>(reg_type::ADDR_MIN_POSITION_LIMIT,
id, pos);
231 template <
typename reg_type>
234 return read<typename reg_type::TYPE_MAX_POSITION_LIMIT>(reg_type::ADDR_MAX_POSITION_LIMIT,
id, pos);
245 template <
typename reg_type>
248 auto torque_enable = torque_percentage > 0 ? 1 : 0;
249 return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE,
id, torque_enable);
258 template <
typename reg_type>
261 return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION,
id, position);
271 template <
typename reg_type>
274 return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY,
id, velocity);
283 template <
typename reg_type>
285 const std::vector<uint8_t> &torque_percentage_list)
287 std::vector<uint8_t> torque_enable_list;
288 for (
const auto &torque_percentage : torque_percentage_list)
290 auto torque_enable = torque_percentage > 0 ? 1 : 0;
291 torque_enable_list.push_back(torque_enable);
293 return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list, torque_enable_list);
302 template <
typename reg_type>
304 const std::vector<uint32_t> &position_list)
306 return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
315 template <
typename reg_type>
317 const std::vector<uint32_t> &velocity_list)
319 return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
330 template <
typename reg_type>
333 return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION,
id, present_position);
342 template <
typename reg_type>
345 return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY,
id, present_velocity);
354 template <
typename reg_type>
357 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
366 template <
typename reg_type>
369 uint16_t voltage_mV = 0;
370 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
371 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
381 template <
typename reg_type>
384 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
393 template <
typename reg_type>
396 return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
405 template <
typename reg_type>
408 return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
418 template <
typename reg_type>
420 std::vector<std::array<uint32_t, 2>> &data_array_list)
422 int res = COMM_TX_FAIL;
427 data_array_list.clear();
430 typename reg_type::TYPE_TORQUE_ENABLE torque{ 1 };
431 res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
432 if (COMM_SUCCESS != res)
433 std::cout <<
"#############"
434 " ERROR reading stepper torque in syncReadJointStatus (error "
435 << res <<
")" << std::endl;
440 res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
444 std::vector<uint32_t> position_list;
445 res = syncReadPosition(id_list, position_list);
446 for (
auto p : position_list)
447 data_array_list.emplace_back(std::array<uint32_t, 2>{ 1, p });
459 template <
typename reg_type>
461 std::vector<std::string> &firmware_list)
464 firmware_list.clear();
465 std::vector<uint32_t> data_list{};
466 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
467 for (
auto const &data : data_list)
468 firmware_list.emplace_back(interpretFirmwareVersion(data));
478 template <
typename reg_type>
480 std::vector<uint8_t> &temperature_list)
482 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list,
492 template <
typename reg_type>
495 voltage_list.clear();
496 std::vector<uint16_t> v_read;
497 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
498 for (
auto const &v : v_read)
499 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
509 template <
typename reg_type>
512 voltage_list.clear();
513 std::vector<uint16_t> v_read;
514 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
515 for (
auto const &v : v_read)
516 voltage_list.emplace_back(
static_cast<double>(v));
526 template <
typename reg_type>
528 std::vector<std::pair<double, uint8_t>> &data_list)
532 std::vector<std::array<uint8_t, 3>> raw_data;
533 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
535 for (
auto const &data : raw_data)
538 auto v =
static_cast<uint16_t
>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
539 auto voltage =
static_cast<double>(v);
542 uint8_t temperature = data.at(2);
544 data_list.emplace_back(std::make_pair(voltage, temperature));
555 template <
typename reg_type>
557 std::vector<uint8_t> &hw_error_list)
559 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
566 template <
typename reg_type>
569 return read<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE,
id, operating_mode);
572 template <
typename reg_type>
575 return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE,
id, operating_mode);
584 template <
typename reg_type>
587 int res = COMM_RX_FAIL;
590 std::vector<std::array<typename reg_type::TYPE_PROFILE, 8>> data_array_list;
592 syncReadConsecutiveBytes<typename reg_type::TYPE_PROFILE, 8>(reg_type::ADDR_VSTART, {
id }, data_array_list))
594 if (!data_array_list.empty())
596 auto block = data_array_list.at(0);
598 for (
auto data : block)
600 data_list.emplace_back(data);
608 std::cout <<
"Failures during read Velocity Profile" << std::endl;
621 template <
typename reg_type>
625 int res = COMM_RX_FAIL;
626 double wait_duration = 0.05;
629 constexpr
auto ACTIVE_TORQUE_PERCENT = 1;
630 writeTorquePercentage(
id, ACTIVE_TORQUE_PERCENT);
636 ros::Duration(wait_duration).sleep();
637 res = writeVStart(
id, data_list.at(0));
638 if (res == COMM_SUCCESS)
641 if (res != COMM_SUCCESS)
648 ros::Duration(wait_duration).sleep();
649 res = writeA1(
id, data_list.at(1));
650 if (res == COMM_SUCCESS)
653 if (res != COMM_SUCCESS)
660 ros::Duration(wait_duration).sleep();
661 res = writeV1(
id, data_list.at(2));
662 if (res == COMM_SUCCESS)
665 if (res != COMM_SUCCESS)
672 ros::Duration(wait_duration).sleep();
673 res = writeAMax(
id, data_list.at(3));
674 if (res == COMM_SUCCESS)
677 if (res != COMM_SUCCESS)
684 ros::Duration(wait_duration).sleep();
685 res = writeVMax(
id, data_list.at(4));
686 if (res == COMM_SUCCESS)
689 if (res != COMM_SUCCESS)
696 ros::Duration(wait_duration).sleep();
697 res = writeDMax(
id, data_list.at(5));
698 if (res == COMM_SUCCESS)
701 if (res != COMM_SUCCESS)
708 ros::Duration(wait_duration).sleep();
709 res = writeD1(
id, data_list.at(6));
710 if (res == COMM_SUCCESS)
713 if (res != COMM_SUCCESS)
720 ros::Duration(wait_duration).sleep();
721 res = writeVStop(
id, data_list.at(7));
722 if (res == COMM_SUCCESS)
734 template <
typename reg_type>
737 return write<typename reg_type::TYPE_COMMAND>(reg_type::ADDR_COMMAND,
id, 0);
748 template <
typename reg_type>
752 double wait_duration = 0.05;
755 constexpr
auto ACTIVE_TORQUE_PERCENT = 1;
756 writeTorquePercentage(
id, ACTIVE_TORQUE_PERCENT);
757 ros::Duration(wait_duration).sleep();
759 if (COMM_SUCCESS != write<typename reg_type::TYPE_HOMING_DIRECTION>(reg_type::ADDR_HOMING_DIRECTION,
id, direction))
761 ros::Duration(wait_duration).sleep();
770 std::cout <<
"Failures during writeVelocityProfile : " << res << std::endl;
783 template <
typename reg_type>
786 return read<typename reg_type::TYPE_HOMING_STATUS>(reg_type::ADDR_HOMING_STATUS,
id, status);
795 template <
typename reg_type>
797 std::vector<uint8_t> &status_list)
799 return syncRead<typename reg_type::TYPE_HOMING_STATUS>(reg_type::ADDR_HOMING_STATUS, id_list, status_list);
808 template <
typename reg_type>
811 typename reg_type::TYPE_FIRMWARE_RUNNING data{};
812 int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING,
id, data);
823 template <
typename reg_type>
825 const std::vector<uint32_t> &abs_position)
827 return syncWrite<typename reg_type::TYPE_HOMING_ABS_POSITION>(reg_type::ADDR_HOMING_ABS_POSITION, id_list,
837 template <
typename reg_type>
839 std::vector<uint32_t> &abs_position)
841 return syncRead<typename reg_type::TYPE_HOMING_ABS_POSITION>(reg_type::ADDR_HOMING_ABS_POSITION, id_list,
853 template <
typename reg_type>
856 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VSTART,
id, v_start);
865 template <
typename reg_type>
868 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_A1,
id, a_1);
877 template <
typename reg_type>
880 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_V1,
id, v_1);
889 template <
typename reg_type>
892 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_AMAX,
id, a_max);
901 template <
typename reg_type>
904 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VMAX,
id, v_max);
913 template <
typename reg_type>
916 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_DMAX,
id, d_max);
925 template <
typename reg_type>
928 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_D1,
id, d_1);
937 template <
typename reg_type>
940 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VSTOP,
id, v_stop);
943 template <
typename reg_type>
946 return reg_type::VELOCITY_UNIT;
951 #endif // STEPPER_DRIVER_HPP