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;
62 std::vector<std::pair<double, uint8_t>> &data_list)
override;
64 int syncReadHwErrorStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &hw_error_list)
override;
71 int changeId(uint8_t
id, uint8_t new_id)
override;
78 const std::vector<uint8_t> &torque_percentage_list)
override;
79 int syncWritePositionGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &position_list)
override;
80 int syncWriteVelocityGoal(
const std::vector<uint8_t> &id_list,
const std::vector<uint32_t> &velocity_list)
override;
83 int readPosition(uint8_t
id, uint32_t &present_position)
override;
84 int readVelocity(uint8_t
id, uint32_t &present_velocity)
override;
86 int syncReadPosition(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &position_list)
override;
87 int syncReadVelocity(
const std::vector<uint8_t> &id_list, std::vector<uint32_t> &velocity_list)
override;
89 std::vector<std::array<uint32_t, 2>> &data_array_list)
override;
93 common::model::EStepperCalibrationStatus
interpretHomingData(uint8_t status)
const override;
100 int readStatus(uint8_t
id,
const uint32_t &status);
101 int readEncAngle(uint8_t
id,
const uint32_t &enc_angle);
115 int writeHomingSetup(uint8_t
id, uint8_t direction, uint8_t stall_threshold);
119 int syncReadHomingStatus(
const std::vector<uint8_t> &id_list, std::vector<uint8_t> &status_list);
132 template <
typename reg_type>
134 std::shared_ptr<dynamixel::PacketHandler> packetHandler)
147 template <
typename reg_type>
159 template <
typename reg_type>
164 int res = write<typename reg_type::TYPE_ID>(reg_type::ADDR_ID,
id, new_id);
165 if (res == COMM_RX_TIMEOUT)
179 template <
typename reg_type>
182 int ping_result = getModelNumber(
id, model_number);
184 if (ping_result == COMM_SUCCESS)
187 auto validator = reg_type::createModelNumberValidator();
188 if (!validator->isValid(model_number))
190 ROS_WARN(
"Ned3ProStepperDriver: Model number %u not valid for %s (expected %s)", model_number,
191 common::model::HardwareTypeEnum(reg_type::motor_type).toString().c_str(), validator->describe().c_str());
192 return PING_WRONG_MODEL_NUMBER;
205 template <
typename reg_type>
210 res = read<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION,
id, data);
211 version = interpretFirmwareVersion(data);
223 template <
typename reg_type>
226 return write<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE,
id, torque_percentage);
235 template <
typename reg_type>
238 return write<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION,
id, position);
248 template <
typename reg_type>
251 return write<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY,
id, velocity);
260 template <
typename reg_type>
262 const std::vector<uint8_t> &torque_percentage_list)
264 return syncWrite<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list,
265 torque_percentage_list);
274 template <
typename reg_type>
276 const std::vector<uint32_t> &position_list)
278 return syncWrite<typename reg_type::TYPE_GOAL_POSITION>(reg_type::ADDR_GOAL_POSITION, id_list, position_list);
287 template <
typename reg_type>
289 const std::vector<uint32_t> &velocity_list)
291 return syncWrite<typename reg_type::TYPE_GOAL_VELOCITY>(reg_type::ADDR_GOAL_VELOCITY, id_list, velocity_list);
302 template <
typename reg_type>
305 return read<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION,
id, present_position);
314 template <
typename reg_type>
317 return read<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY,
id, present_velocity);
326 template <
typename reg_type>
329 return read<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE,
id, temperature);
338 template <
typename reg_type>
341 uint16_t voltage_mV = 0;
342 int res = read<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE,
id, voltage_mV);
343 voltage =
static_cast<double>(voltage_mV) / reg_type::VOLTAGE_CONVERSION;
353 template <
typename reg_type>
356 return read<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS,
id, hardware_error_status);
365 template <
typename reg_type>
367 std::vector<uint32_t> &position_list)
369 return syncRead<typename reg_type::TYPE_PRESENT_POSITION>(reg_type::ADDR_PRESENT_POSITION, id_list, position_list);
378 template <
typename reg_type>
380 std::vector<uint32_t> &velocity_list)
382 return syncRead<typename reg_type::TYPE_PRESENT_VELOCITY>(reg_type::ADDR_PRESENT_VELOCITY, id_list, velocity_list);
392 template <
typename reg_type>
394 std::vector<std::array<uint32_t, 2>> &data_array_list)
396 int res = COMM_TX_FAIL;
401 data_array_list.clear();
404 typename reg_type::TYPE_TORQUE_ENABLE torque{ 1 };
405 res = read<typename reg_type::TYPE_TORQUE_ENABLE>(reg_type::ADDR_TORQUE_ENABLE, id_list.at(0), torque);
406 if (COMM_SUCCESS != res)
407 std::cout <<
"#############"
408 " ERROR reading stepper torque in syncReadJointStatus (error "
409 << res <<
")" << std::endl;
414 res = syncReadConsecutiveBytes<uint32_t, 2>(reg_type::ADDR_PRESENT_VELOCITY, id_list, data_array_list);
418 std::vector<uint32_t> position_list;
419 res = syncReadPosition(id_list, position_list);
420 for (
auto p : position_list)
421 data_array_list.emplace_back(std::array<uint32_t, 2>{ 1, p });
433 template <
typename reg_type>
435 std::vector<std::string> &firmware_list)
438 firmware_list.clear();
439 std::vector<uint32_t> data_list{};
440 res = syncRead<typename reg_type::TYPE_FIRMWARE_VERSION>(reg_type::ADDR_FIRMWARE_VERSION, id_list, data_list);
441 for (
auto const &data : data_list)
442 firmware_list.emplace_back(interpretFirmwareVersion(data));
452 template <
typename reg_type>
454 std::vector<uint8_t> &temperature_list)
456 return syncRead<typename reg_type::TYPE_PRESENT_TEMPERATURE>(reg_type::ADDR_PRESENT_TEMPERATURE, id_list,
466 template <
typename reg_type>
468 std::vector<double> &voltage_list)
470 voltage_list.clear();
471 std::vector<uint16_t> v_read;
472 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
473 for (
auto const &v : v_read)
474 voltage_list.emplace_back(
static_cast<double>(v) / reg_type::VOLTAGE_CONVERSION);
484 template <
typename reg_type>
486 std::vector<double> &voltage_list)
488 voltage_list.clear();
489 std::vector<uint16_t> v_read;
490 int res = syncRead<typename reg_type::TYPE_PRESENT_VOLTAGE>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, v_read);
491 for (
auto const &v : v_read)
492 voltage_list.emplace_back(
static_cast<double>(v));
502 template <
typename reg_type>
504 std::vector<std::pair<double, uint8_t>> &data_list)
508 std::vector<std::array<uint8_t, 3>> raw_data;
509 int res = syncReadConsecutiveBytes<uint8_t, 3>(reg_type::ADDR_PRESENT_VOLTAGE, id_list, raw_data);
511 for (
auto const &data : raw_data)
514 auto v =
static_cast<uint16_t
>((
static_cast<uint16_t
>(data.at(1)) << 8) | data.at(0));
515 auto voltage =
static_cast<double>(v);
518 uint8_t temperature = data.at(2);
520 data_list.emplace_back(std::make_pair(voltage, temperature));
531 template <
typename reg_type>
533 std::vector<uint8_t> &hw_error_list)
535 return syncRead<typename reg_type::TYPE_HW_ERROR_STATUS>(reg_type::ADDR_HW_ERROR_STATUS, id_list, hw_error_list);
547 template <
typename reg_type>
550 enum Ned3ProStepperCalibrationStatus
552 UNINITIALIZED_MASK = 0,
553 IN_PROGRESS_MASK = 2,
558 return status & IN_PROGRESS_MASK ? common::model::EStepperCalibrationStatus::IN_PROGRESS :
559 status & FAIL_MASK ? common::model::EStepperCalibrationStatus::FAIL :
560 status & OK_MASK ? common::model::EStepperCalibrationStatus::OK :
561 common::model::EStepperCalibrationStatus::FAIL;
570 template <
typename reg_type>
573 return write<typename reg_type::TYPE_OPERATING_MODE>(reg_type::ADDR_OPERATING_MODE,
id, operating_mode);
582 template <
typename reg_type>
585 return write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY,
id, velocity_profile);
594 template <
typename reg_type>
597 return write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION,
id,
598 acceleration_profile);
607 template <
typename reg_type>
610 return write<typename reg_type::TYPE_CONTROL>(reg_type::ADDR_CONTROL,
id, command);
619 template <
typename reg_type>
622 return read<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS,
id, status);
625 template <
typename reg_type>
627 std::vector<uint8_t> &status_list)
629 std::vector<uint32_t> status_list_tmp;
630 auto result = syncRead<typename reg_type::TYPE_STATUS>(reg_type::ADDR_STATUS, id_list, status_list_tmp);
631 for (
const auto &status_tmp : status_list_tmp)
632 status_list.push_back(
static_cast<uint8_t
>(status_tmp));
643 template <
typename reg_type>
646 return read<typename reg_type::TYPE_ENC_ANGLE>(reg_type::ADDR_ENC_ANGLE,
id, enc_angle);
655 template <
typename reg_type>
658 typename reg_type::TYPE_FIRMWARE_RUNNING data{};
659 int res = read<typename reg_type::TYPE_FIRMWARE_RUNNING>(reg_type::ADDR_FIRMWARE_RUNNING,
id, data);
665 template <
typename reg_type>
668 ROS_WARN(
"Ned3ProStepperDriver::readMinPosition - Not implemented");
670 return COMM_NOT_AVAILABLE;
673 template <
typename reg_type>
676 ROS_WARN(
"Ned3ProStepperDriver::readMaxPosition - Not implemented");
678 return COMM_NOT_AVAILABLE;
681 template <
typename reg_type>
684 ROS_WARN(
"Ned3ProStepperDriver::readControlMode - Not implemented");
686 return COMM_NOT_AVAILABLE;
689 template <
typename reg_type>
692 ROS_WARN(
"Ned3ProStepperDriver::readVelocityProfile std::vector<uint32_t> &data_list - Not implemented");
694 return COMM_NOT_AVAILABLE;
697 template <
typename reg_type>
701 int res = COMM_RX_FAIL;
702 double wait_duration = 0.05;
705 constexpr
auto ACTIVE_TORQUE_PERCENT = 40;
706 writeTorquePercentage(
id, ACTIVE_TORQUE_PERCENT);
712 ros::Duration(wait_duration).sleep();
713 res = write<typename reg_type::TYPE_PROFILE_VELOCITY>(reg_type::ADDR_PROFILE_VELOCITY,
id, data_list.at(4));
714 if (res == COMM_SUCCESS)
717 if (res != COMM_SUCCESS)
724 ros::Duration(wait_duration).sleep();
725 res = write<typename reg_type::TYPE_PROFILE_ACCELERATION>(reg_type::ADDR_PROFILE_ACCELERATION,
id, data_list.at(3));
726 if (res == COMM_SUCCESS)
733 template <
typename reg_type>
736 ROS_WARN(
"Ned3ProStepperDriver::startHoming - Not implemented");
738 return COMM_NOT_AVAILABLE;
741 template <
typename reg_type>
744 ROS_WARN(
"Ned3ProStepperDriver::writeHomingSetup - Not implemented");
746 return COMM_NOT_AVAILABLE;
750 template <
typename reg_type>
753 ROS_WARN(
"Ned3ProStepperDriver::readHomingStatus - Not implemented");
755 return COMM_NOT_AVAILABLE;
757 template <
typename reg_type>
759 std::vector<uint32_t> &abs_position)
761 ROS_WARN(
"Ned3ProStepperDriver::syncReadHomingAbsPosition - Not implemented");
763 return COMM_NOT_AVAILABLE;
765 template <
typename reg_type>
767 const std::vector<uint32_t> &abs_position)
769 ROS_WARN(
"Ned3ProStepperDriver::syncWriteHomingAbsPosition - Not implemented");
771 return COMM_NOT_AVAILABLE;
774 template <
typename reg_type>
777 return reg_type::VELOCITY_UNIT;
781 #endif // NED3PRO_STEPPER_DRIVER_HPP