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)
176 template <
typename reg_type>
179 int ping_result = getModelNumber(
id, model_number);
181 if (ping_result == COMM_SUCCESS)
184 auto validator = reg_type::createModelNumberValidator();
185 if (!validator->isValid(model_number))
187 ROS_WARN(
"Ned3ProStepperDriver: Model number %u not valid for %s (expected %s)",
189 common::model::HardwareTypeEnum(reg_type::motor_type).toString().c_str(),
190 validator->describe().c_str());
191 return PING_WRONG_MODEL_NUMBER;
204 template <
typename reg_type>
209 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
210 version = interpretFirmwareVersion(data);
222 template <
typename reg_type>
225 return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE,
id, torque_percentage);
234 template <
typename reg_type>
237 return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION,
id, position);
247 template <
typename reg_type>
250 return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY,
id, velocity);
259 template <
typename reg_type>
262 return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list, torque_percentage_list);
271 template <
typename reg_type>
274 return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
283 template <
typename reg_type>
286 return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
297 template <
typename reg_type>
300 return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION,
id, present_position);
309 template <
typename reg_type>
312 return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY,
id, present_velocity);
321 template <
typename reg_type>
324 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
333 template <
typename reg_type>
336 uint16_t voltage_mV = 0;
337 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
338 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
348 template <
typename reg_type>
351 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
360 template <
typename reg_type>
363 return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
372 template <
typename reg_type>
375 return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
385 template <
typename reg_type>
387 std::vector<std::array<uint32_t, 2>> &data_array_list)
389 int res = COMM_TX_FAIL;
394 data_array_list.clear();
397 typename reg_type::TYPE_TORQUE_ENABLE torque{1};
398 res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
399 if (COMM_SUCCESS != res)
400 std::cout <<
"#############"
401 " ERROR reading stepper torque in syncReadJointStatus (error "
402 << res <<
")" << std::endl;
407 res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
411 std::vector<uint32_t> position_list;
412 res = syncReadPosition(id_list, position_list);
413 for (
auto p : position_list)
414 data_array_list.emplace_back(std::array<uint32_t, 2>{1, p});
426 template <
typename reg_type>
430 firmware_list.clear();
431 std::vector<uint32_t> data_list{};
432 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
433 for (
auto const &data : data_list)
434 firmware_list.emplace_back(interpretFirmwareVersion(data));
444 template <
typename reg_type>
447 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list, temperature_list);
456 template <
typename reg_type>
459 voltage_list.clear();
460 std::vector<uint16_t> v_read;
461 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
462 for (
auto const &v : v_read)
463 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
473 template <
typename reg_type>
476 voltage_list.clear();
477 std::vector<uint16_t> v_read;
478 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
479 for (
auto const &v : v_read)
480 voltage_list.emplace_back(
static_cast<double>(v));
490 template <
typename reg_type>
492 std::vector<std::pair<double, uint8_t>> &data_list)
496 std::vector<std::array<uint8_t, 3>> raw_data;
497 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
499 for (
auto const &data : raw_data)
502 auto v =
static_cast<uint16_t
>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
503 auto voltage =
static_cast<double>(v);
506 uint8_t temperature = data.at(2);
508 data_list.emplace_back(std::make_pair(voltage, temperature));
519 template <
typename reg_type>
522 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
534 template <
typename reg_type>
537 enum Ned3ProStepperCalibrationStatus {
538 UNINITIALIZED_MASK = 0,
539 IN_PROGRESS_MASK = 2,
544 return status & IN_PROGRESS_MASK ? common::model::EStepperCalibrationStatus::IN_PROGRESS
545 : status & FAIL_MASK ? common::model::EStepperCalibrationStatus::FAIL
546 : status & OK_MASK ? common::model::EStepperCalibrationStatus::OK
547 : common::model::EStepperCalibrationStatus::FAIL;
556 template <
typename reg_type>
559 return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE,
id, operating_mode);
568 template <
typename reg_type>
571 return write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY,
id, velocity_profile);
580 template <
typename reg_type>
583 return write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION,
id, acceleration_profile);
592 template <
typename reg_type>
595 return write<typename reg_type::TYPE_CONTROL>(reg_type::ADDR_CONTROL,
id, command);
604 template <
typename reg_type>
607 return read<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS,
id, status);
610 template <
typename reg_type>
613 std::vector<uint32_t> status_list_tmp;
614 auto result = syncRead<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id_list, status_list_tmp);
615 for (
const auto &status_tmp : status_list_tmp)
616 status_list.push_back(
static_cast<uint8_t
>(status_tmp));
627 template <
typename reg_type>
630 return read<typename reg_type::TYPE_ENC_ANGLE>(reg_type::ADDR_ENC_ANGLE,
id, enc_angle);
639 template <
typename reg_type>
642 typename reg_type::TYPE_FIRMWARE_RUNNING data{};
643 int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING,
id, data);
649 template <
typename reg_type>
652 ROS_WARN(
"Ned3ProStepperDriver::readMinPosition - Not implemented");
654 return COMM_NOT_AVAILABLE;
657 template <
typename reg_type>
660 ROS_WARN(
"Ned3ProStepperDriver::readMaxPosition - Not implemented");
662 return COMM_NOT_AVAILABLE;
665 template <
typename reg_type>
668 ROS_WARN(
"Ned3ProStepperDriver::readControlMode - Not implemented");
670 return COMM_NOT_AVAILABLE;
673 template <
typename reg_type>
676 ROS_WARN(
"Ned3ProStepperDriver::readVelocityProfile std::vector<uint32_t> &data_list - Not implemented");
678 return COMM_NOT_AVAILABLE;
681 template <
typename reg_type>
685 int res = COMM_RX_FAIL;
686 double wait_duration = 0.05;
689 constexpr
auto ACTIVE_TORQUE_PERCENT = 40;
690 writeTorquePercentage(
id, ACTIVE_TORQUE_PERCENT);
696 ros::Duration(wait_duration).sleep();
697 res = write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY,
id, data_list.at(4));
698 if (res == COMM_SUCCESS)
701 if (res != COMM_SUCCESS)
708 ros::Duration(wait_duration).sleep();
709 res = write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION,
id, data_list.at(3));
710 if (res == COMM_SUCCESS)
717 template <
typename reg_type>
720 ROS_WARN(
"Ned3ProStepperDriver::startHoming - Not implemented");
722 return COMM_NOT_AVAILABLE;
725 template <
typename reg_type>
728 ROS_WARN(
"Ned3ProStepperDriver::writeHomingSetup - Not implemented");
730 return COMM_NOT_AVAILABLE;
734 template <
typename reg_type>
737 ROS_WARN(
"Ned3ProStepperDriver::readHomingStatus - Not implemented");
739 return COMM_NOT_AVAILABLE;
741 template <
typename reg_type>
744 ROS_WARN(
"Ned3ProStepperDriver::syncReadHomingAbsPosition - Not implemented");
746 return COMM_NOT_AVAILABLE;
748 template <
typename reg_type>
751 ROS_WARN(
"Ned3ProStepperDriver::syncWriteHomingAbsPosition - Not implemented");
753 return COMM_NOT_AVAILABLE;
756 template <
typename reg_type>
759 return reg_type::VELOCITY_UNIT;
763 #endif // NED3PRO_STEPPER_DRIVER_HPP