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;
59 int syncReadHwStatus(
const std::vector<uint8_t> &id_list, std::vector<std::pair<double, uint8_t>> &data_list)
override;
61 int syncReadHwErrorStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
override;
68 int changeId(uint8_t
id, uint8_t new_id)
override;
77 int syncWriteTorquePercentage(
const std::vector<uint8_t> &id_list,
const std::vector<uint8_t> &torque_percentage_list)
override;
78 int syncWritePositionGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &position_list)
override;
79 int syncWriteVelocityGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &velocity_list)
override;
82 int readPosition(uint8_t
id, uint32_t &present_position)
override;
83 int readVelocity(uint8_t
id, uint32_t &present_velocity)
override;
85 int syncReadPosition(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
override;
86 int syncReadVelocity(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
override;
87 int syncReadJointStatus(
const std::vector<uint8_t> &id_list, std::vector<std::array<uint32_t, 2>> &data_array_list)
override;
98 int writeHomingSetup(uint8_t
id, uint8_t direction, uint8_t stall_threshold)
override;
101 int syncReadHomingStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list)
override;
112 int writeA1(uint8_t
id, uint32_t a_1);
113 int writeV1(uint8_t
id, uint32_t v_1);
114 int writeAMax(uint8_t
id, uint32_t a_max);
115 int writeVMax(uint8_t
id, uint32_t v_max);
116 int writeDMax(uint8_t
id, uint32_t d_max);
117 int writeD1(uint8_t
id, uint32_t d_1);
126 template <
typename reg_type>
128 std::shared_ptr<dynamixel::PacketHandler> packetHandler) :
AbstractStepperDriver(std::move(portHandler),
129 std::move(packetHandler))
141 template <
typename reg_type>
153 template <
typename reg_type>
158 int res = write<typename reg_type::TYPE_ID>(reg_type::ADDR_ID,
id, new_id);
159 if (res == COMM_RX_TIMEOUT)
173 template <
typename reg_type>
176 int ping_result = getModelNumber(
id, model_number);
178 if (ping_result == COMM_SUCCESS && model_number != 0)
181 auto validator = reg_type::createModelNumberValidator();
182 if (!validator->isValid(model_number))
184 ROS_WARN(
"StepperDriver: Model number %u not valid for %s (expected %s)",
186 common::model::HardwareTypeEnum(reg_type::motor_type).toString().c_str(),
187 validator->describe().c_str());
188 return PING_WRONG_MODEL_NUMBER;
201 template <
typename reg_type>
206 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
207 version = interpretFirmwareVersion(data);
217 template <
typename reg_type>
220 return read<typename reg_type::TYPE_MIN_POSITION_LIMIT>(reg_type::ADDR_MIN_POSITION_LIMIT,
id, pos);
229 template <
typename reg_type>
232 return read<typename reg_type::TYPE_MAX_POSITION_LIMIT>(reg_type::ADDR_MAX_POSITION_LIMIT,
id, pos);
243 template <
typename reg_type>
246 auto torque_enable = torque_percentage > 0 ? 1 : 0;
247 return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE,
id, torque_enable);
256 template <
typename reg_type>
259 return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION,
id, position);
269 template <
typename reg_type>
272 return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY,
id, velocity);
281 template <
typename reg_type>
284 std::vector<uint8_t> torque_enable_list;
285 for(
const auto &torque_percentage : torque_percentage_list)
287 auto torque_enable = torque_percentage > 0 ? 1 : 0;
288 torque_enable_list.push_back(torque_enable);
290 return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list, torque_enable_list);
299 template <
typename reg_type>
302 return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
311 template <
typename reg_type>
314 return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
325 template <
typename reg_type>
328 return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION,
id, present_position);
337 template <
typename reg_type>
340 return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY,
id, present_velocity);
349 template <
typename reg_type>
352 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
361 template <
typename reg_type>
364 uint16_t voltage_mV = 0;
365 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
366 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
376 template <
typename reg_type>
379 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
388 template <
typename reg_type>
391 return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
400 template <
typename reg_type>
403 return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
413 template <
typename reg_type>
415 std::vector<std::array<uint32_t, 2>> &data_array_list)
417 int res = COMM_TX_FAIL;
422 data_array_list.clear();
425 typename reg_type::TYPE_TORQUE_ENABLE torque{1};
426 res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
427 if (COMM_SUCCESS != res)
428 std::cout <<
"#############"
429 " ERROR reading stepper torque in syncReadJointStatus (error "
430 << res <<
")" << std::endl;
435 res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
439 std::vector<uint32_t> position_list;
440 res = syncReadPosition(id_list, position_list);
441 for (
auto p : position_list)
442 data_array_list.emplace_back(std::array<uint32_t, 2>{1, p});
454 template <
typename reg_type>
458 firmware_list.clear();
459 std::vector<uint32_t> data_list{};
460 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
461 for (
auto const &data : data_list)
462 firmware_list.emplace_back(interpretFirmwareVersion(data));
472 template <
typename reg_type>
475 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
484 template <
typename reg_type>
487 voltage_list.clear();
488 std::vector<uint16_t> v_read;
489 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
490 for (
auto const &v : v_read)
491 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
501 template <
typename reg_type>
504 voltage_list.clear();
505 std::vector<uint16_t> v_read;
506 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
507 for (
auto const &v : v_read)
508 voltage_list.emplace_back(
static_cast<double>(v));
518 template <
typename reg_type>
520 std::vector<std::pair<double, uint8_t>> &data_list)
524 std::vector<std::array<uint8_t, 3>> raw_data;
525 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
527 for (
auto const &data : raw_data)
530 auto v =
static_cast<uint16_t
>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
531 auto voltage =
static_cast<double>(v);
534 uint8_t temperature = data.at(2);
536 data_list.emplace_back(std::make_pair(voltage, temperature));
547 template <
typename reg_type>
550 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
557 template <
typename reg_type>
560 return read<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE,
id, operating_mode);
563 template <
typename reg_type>
566 return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE,
id, operating_mode);
575 template <
typename reg_type>
578 int res = COMM_RX_FAIL;
581 std::vector<std::array<typename reg_type::TYPE_PROFILE, 8>> data_array_list;
582 if (COMM_SUCCESS == syncReadConsecutiveBytes<typename reg_type::TYPE_PROFILE, 8>(reg_type::ADDR_VSTART, {
id}, data_array_list))
584 if (!data_array_list.empty())
586 auto block = data_array_list.at(0);
588 for (
auto data : block)
590 data_list.emplace_back(data);
598 std::cout <<
"Failures during read Velocity Profile" << std::endl;
611 template <
typename reg_type>
615 int res = COMM_RX_FAIL;
616 double wait_duration = 0.05;
619 constexpr
auto ACTIVE_TORQUE_PERCENT = 1;
620 writeTorquePercentage(
id, ACTIVE_TORQUE_PERCENT);
626 ros::Duration(wait_duration).sleep();
627 res = writeVStart(
id, data_list.at(0));
628 if (res == COMM_SUCCESS)
631 if (res != COMM_SUCCESS)
638 ros::Duration(wait_duration).sleep();
639 res = writeA1(
id, data_list.at(1));
640 if (res == COMM_SUCCESS)
643 if (res != COMM_SUCCESS)
650 ros::Duration(wait_duration).sleep();
651 res = writeV1(
id, data_list.at(2));
652 if (res == COMM_SUCCESS)
655 if (res != COMM_SUCCESS)
662 ros::Duration(wait_duration).sleep();
663 res = writeAMax(
id, data_list.at(3));
664 if (res == COMM_SUCCESS)
667 if (res != COMM_SUCCESS)
674 ros::Duration(wait_duration).sleep();
675 res = writeVMax(
id, data_list.at(4));
676 if (res == COMM_SUCCESS)
679 if (res != COMM_SUCCESS)
686 ros::Duration(wait_duration).sleep();
687 res = writeDMax(
id, data_list.at(5));
688 if (res == COMM_SUCCESS)
691 if (res != COMM_SUCCESS)
698 ros::Duration(wait_duration).sleep();
699 res = writeD1(
id, data_list.at(6));
700 if (res == COMM_SUCCESS)
703 if (res != COMM_SUCCESS)
710 ros::Duration(wait_duration).sleep();
711 res = writeVStop(
id, data_list.at(7));
712 if (res == COMM_SUCCESS)
724 template <
typename reg_type>
727 return write<typename reg_type::TYPE_COMMAND>(reg_type::ADDR_COMMAND,
id, 0);
738 template <
typename reg_type>
742 double wait_duration = 0.05;
745 constexpr
auto ACTIVE_TORQUE_PERCENT = 1;
746 writeTorquePercentage(
id, ACTIVE_TORQUE_PERCENT);
747 ros::Duration(wait_duration).sleep();
749 if (COMM_SUCCESS != write<typename reg_type::TYPE_HOMING_DIRECTION>(reg_type::ADDR_HOMING_DIRECTION,
id, direction))
751 ros::Duration(wait_duration).sleep();
759 std::cout <<
"Failures during writeVelocityProfile : " << res << std::endl;
772 template <
typename reg_type>
775 return read<typename reg_type::TYPE_HOMING_STATUS>(reg_type::ADDR_HOMING_STATUS,
id, status);
784 template <
typename reg_type>
787 return syncRead<typename reg_type::TYPE_HOMING_STATUS>(reg_type::ADDR_HOMING_STATUS, id_list, status_list);
796 template <
typename reg_type>
799 typename reg_type::TYPE_FIRMWARE_RUNNING data{};
800 int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING,
id, data);
811 template <
typename reg_type>
814 return syncWrite<typename reg_type::TYPE_HOMING_ABS_POSITION>(reg_type::ADDR_HOMING_ABS_POSITION, id_list, abs_position);
823 template <
typename reg_type>
826 return syncRead<typename reg_type::TYPE_HOMING_ABS_POSITION>(reg_type::ADDR_HOMING_ABS_POSITION, id_list, abs_position);
837 template <
typename reg_type>
840 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VSTART,
id, v_start);
849 template <
typename reg_type>
852 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_A1,
id, a_1);
861 template <
typename reg_type>
864 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_V1,
id, v_1);
873 template <
typename reg_type>
876 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_AMAX,
id, a_max);
885 template <
typename reg_type>
888 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VMAX,
id, v_max);
897 template <
typename reg_type>
900 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_DMAX,
id, d_max);
909 template <
typename reg_type>
912 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_D1,
id, d_1);
921 template <
typename reg_type>
924 return write<typename reg_type::TYPE_PROFILE>(reg_type::ADDR_VSTOP,
id, v_stop);
927 template <
typename reg_type>
930 return reg_type::VELOCITY_UNIT;
935 #endif // STEPPER_DRIVER_HPP