18 #include "common/model/abstract_motor_state.hpp"
19 #include "common/model/bus_protocol_enum.hpp"
20 #include "common/model/dxl_command_type_enum.hpp"
21 #include "common/model/dxl_motor_state.hpp"
22 #include "common/model/hardware_type_enum.hpp"
23 #include "common/model/joint_state.hpp"
24 #include "common/model/single_motor_cmd.hpp"
25 #include "common/model/stepper_command_type_enum.hpp"
26 #include "common/model/stepper_motor_state.hpp"
27 #include "common/model/synchronize_motor_cmd.hpp"
28 #include "dynamixel_sdk/dynamixel_sdk.h"
29 #include "ros/node_handle.h"
35 #include <gtest/gtest.h>
37 #include <ros/console.h>
41 using ::common::model::BusProtocolEnum;
42 using ::common::model::DxlMotorState;
43 using ::common::model::EBusProtocol;
44 using ::common::model::EHardwareType;
45 using ::common::model::HardwareTypeEnum;
46 using ::common::model::StepperMotorState;
48 using ::std::to_string;
58 ros::NodeHandle robot_hwnh(
"joints_interface");
60 while (robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/id") && robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/name") &&
61 robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/type") && robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/bus"))
67 int currentIdStepper = 1;
69 for (
size_t j = 0; j < nb_joints; j++)
71 int joint_id_config = 0;
76 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/id", joint_id_config);
77 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/name", joint_name);
78 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/type", joint_type);
79 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/bus", joint_bus);
80 HardwareTypeEnum eType = HardwareTypeEnum(joint_type.c_str());
81 BusProtocolEnum eBusProto = BusProtocolEnum(joint_bus.c_str());
83 if (eType == EHardwareType::STEPPER || eType == EHardwareType::FAKE_STEPPER_MOTOR)
85 std::string currentStepperNamespace =
"steppers/stepper_" + to_string(currentIdStepper);
87 auto stepperState = std::make_shared<StepperMotorState>(joint_name, eType, common::model::EComponentType::JOINT, eBusProto,
static_cast<uint8_t
>(joint_id_config));
90 double offsetPos = 0.0;
91 double gear_ratio = 1.0;
93 double max_effort = 0.0;
94 double home_position = 0.0;
95 double limit_position_min = 0.0;
96 double limit_position_max = 0.0;
97 double motor_ratio = 0.0;
99 robot_hwnh.getParam(currentStepperNamespace +
"/offset_position", offsetPos);
100 robot_hwnh.getParam(currentStepperNamespace +
"/gear_ratio", gear_ratio);
101 robot_hwnh.getParam(currentStepperNamespace +
"/direction", direction);
102 robot_hwnh.getParam(currentStepperNamespace +
"/max_effort", max_effort);
103 robot_hwnh.getParam(currentStepperNamespace +
"/default_home_position", home_position);
104 robot_hwnh.getParam(currentStepperNamespace +
"/limit_position_min", limit_position_min);
105 robot_hwnh.getParam(currentStepperNamespace +
"/limit_position_max", limit_position_max);
106 robot_hwnh.getParam(currentStepperNamespace +
"/motor_ratio", motor_ratio);
109 common::model::VelocityProfile profile{};
111 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_start"))
113 robot_hwnh.getParam(currentStepperNamespace +
"/v_start", data);
114 profile.v_start =
static_cast<uint32_t
>(data);
117 if (robot_hwnh.hasParam(currentStepperNamespace +
"/a_1"))
119 robot_hwnh.getParam(currentStepperNamespace +
"/a_1", data);
120 profile.a_1 =
static_cast<uint32_t
>(data);
122 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_1"))
124 robot_hwnh.getParam(currentStepperNamespace +
"/v_1", data);
125 profile.v_1 =
static_cast<uint32_t
>(data);
127 if (robot_hwnh.hasParam(currentStepperNamespace +
"/a_max"))
129 robot_hwnh.getParam(currentStepperNamespace +
"/a_max", data);
130 profile.a_max =
static_cast<uint32_t
>(data);
132 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_max"))
134 robot_hwnh.getParam(currentStepperNamespace +
"/v_max", data);
135 profile.v_max =
static_cast<uint32_t
>(data);
137 if (robot_hwnh.hasParam(currentStepperNamespace +
"/d_max"))
139 robot_hwnh.getParam(currentStepperNamespace +
"/d_max", data);
140 profile.d_max =
static_cast<uint32_t
>(data);
142 if (robot_hwnh.hasParam(currentStepperNamespace +
"/d_1"))
144 robot_hwnh.getParam(currentStepperNamespace +
"/d_1", data);
145 profile.d_1 =
static_cast<uint32_t
>(data);
147 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_stop"))
149 robot_hwnh.getParam(currentStepperNamespace +
"/v_stop", data);
150 profile.v_stop =
static_cast<uint32_t
>(data);
154 stepperState->setOffsetPosition(offsetPos);
155 stepperState->setGearRatio(gear_ratio);
156 stepperState->setDirection(
static_cast<int8_t
>(direction));
157 stepperState->setMaxEffort(max_effort);
158 stepperState->setHomePosition(home_position);
159 stepperState->setLimitPositionMax(limit_position_max);
160 stepperState->setLimitPositionMin(limit_position_min);
161 stepperState->setMotorRatio(motor_ratio);
162 stepperState->setVelocityProfile(profile);
164 if (eBusProto == EBusProtocol::TTL)
165 ttl_interface->addJoint(stepperState);
170 else if (eType != EHardwareType::UNKNOWN)
172 auto dxlState = std::make_shared<DxlMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
static_cast<uint8_t
>(joint_id_config));
175 double offsetPos = 0.0;
177 int positionPGain = 0;
178 int positionIGain = 0;
179 int positionDGain = 0;
180 int velocityPGain = 0;
181 int velocityIGain = 0;
184 int velocityProfile = 0;
185 int accelerationProfile = 0;
186 double limit_position_min = 0.0;
187 double limit_position_max = 0.0;
188 double home_position = 0.0;
190 std::string currentDxlNamespace =
"dynamixels/dxl_" + to_string(currentIdDxl);
192 robot_hwnh.getParam(currentDxlNamespace +
"/offset_position", offsetPos);
193 robot_hwnh.getParam(currentDxlNamespace +
"/direction", direction);
195 robot_hwnh.getParam(currentDxlNamespace +
"/position_P_gain", positionPGain);
196 robot_hwnh.getParam(currentDxlNamespace +
"/position_I_gain", positionIGain);
197 robot_hwnh.getParam(currentDxlNamespace +
"/position_D_gain", positionDGain);
199 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_P_gain", velocityPGain);
200 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_I_gain", velocityIGain);
202 robot_hwnh.getParam(currentDxlNamespace +
"/FF1_gain", FF1Gain);
203 robot_hwnh.getParam(currentDxlNamespace +
"/FF2_gain", FF2Gain);
205 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_profile", velocityProfile);
206 robot_hwnh.getParam(currentDxlNamespace +
"/acceleration_profile", accelerationProfile);
208 robot_hwnh.getParam(currentDxlNamespace +
"/default_home_position", home_position);
209 robot_hwnh.getParam(currentDxlNamespace +
"/limit_position_min", limit_position_min);
210 robot_hwnh.getParam(currentDxlNamespace +
"/limit_position_max", limit_position_max);
212 dxlState->setOffsetPosition(offsetPos);
213 dxlState->setDirection(
static_cast<int8_t
>(direction));
215 dxlState->setPositionPGain(
static_cast<uint32_t
>(positionPGain));
216 dxlState->setPositionIGain(
static_cast<uint32_t
>(positionIGain));
217 dxlState->setPositionDGain(
static_cast<uint32_t
>(positionDGain));
219 dxlState->setVelocityPGain(
static_cast<uint32_t
>(velocityPGain));
220 dxlState->setVelocityIGain(
static_cast<uint32_t
>(velocityIGain));
222 dxlState->setFF1Gain(
static_cast<uint32_t
>(FF1Gain));
223 dxlState->setFF2Gain(
static_cast<uint32_t
>(FF2Gain));
225 dxlState->setVelProfile(
static_cast<uint32_t
>(velocityProfile));
226 dxlState->setAccProfile(
static_cast<uint32_t
>(accelerationProfile));
228 dxlState->setLimitPositionMin(limit_position_min);
229 dxlState->setLimitPositionMax(limit_position_max);
231 dxlState->setHomePosition(home_position);
233 if (eBusProto == EBusProtocol::TTL)
234 ttl_interface->addJoint(dxlState);
248 size_t nb_joints = 0;
250 ros::NodeHandle robot_hwnh(
"joints_interface");
252 while (robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/id") && robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/name") &&
253 robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/type") && robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/bus"))
257 int currentIdStepper = 1;
258 int currentIdDxl = 1;
260 for (
size_t j = 0; j < nb_joints; j++)
262 int joint_id_config = 0;
267 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/id", joint_id_config);
268 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/name", joint_name);
269 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/type", joint_type);
270 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/bus", joint_bus);
272 HardwareTypeEnum eType = HardwareTypeEnum(joint_type.c_str());
273 BusProtocolEnum eBusProto = BusProtocolEnum(joint_bus.c_str());
275 if (eType == EHardwareType::STEPPER || eType == EHardwareType::FAKE_STEPPER_MOTOR)
277 std::string currentStepperNamespace =
"steppers/stepper_" + to_string(currentIdStepper);
279 auto stepperState = std::make_shared<StepperMotorState>(joint_name, eType, common::model::EComponentType::JOINT, eBusProto,
static_cast<uint8_t
>(joint_id_config));
282 double offsetPos = 0.0;
283 double gear_ratio = 1.0;
285 double max_effort = 0.0;
286 double home_position = 0.0;
287 double limit_position_min = 0.0;
288 double limit_position_max = 0.0;
289 double motor_ratio = 0.0;
291 robot_hwnh.getParam(currentStepperNamespace +
"/offset_position", offsetPos);
292 robot_hwnh.getParam(currentStepperNamespace +
"/gear_ratio", gear_ratio);
293 robot_hwnh.getParam(currentStepperNamespace +
"/direction", direction);
294 robot_hwnh.getParam(currentStepperNamespace +
"/max_effort", max_effort);
295 robot_hwnh.getParam(currentStepperNamespace +
"/default_home_position", home_position);
296 robot_hwnh.getParam(currentStepperNamespace +
"/limit_position_min", limit_position_min);
297 robot_hwnh.getParam(currentStepperNamespace +
"/limit_position_max", limit_position_max);
298 robot_hwnh.getParam(currentStepperNamespace +
"/motor_ratio", motor_ratio);
301 common::model::VelocityProfile profile{};
303 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_start"))
305 robot_hwnh.getParam(currentStepperNamespace +
"/v_start", data);
306 profile.v_start =
static_cast<uint32_t
>(data);
309 if (robot_hwnh.hasParam(currentStepperNamespace +
"/a_1"))
311 robot_hwnh.getParam(currentStepperNamespace +
"/a_1", data);
312 profile.a_1 =
static_cast<uint32_t
>(data);
314 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_1"))
316 robot_hwnh.getParam(currentStepperNamespace +
"/v_1", data);
317 profile.v_1 =
static_cast<uint32_t
>(data);
319 if (robot_hwnh.hasParam(currentStepperNamespace +
"/a_max"))
321 robot_hwnh.getParam(currentStepperNamespace +
"/a_max", data);
322 profile.a_max =
static_cast<uint32_t
>(data);
324 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_max"))
326 robot_hwnh.getParam(currentStepperNamespace +
"/v_max", data);
327 profile.v_max =
static_cast<uint32_t
>(data);
329 if (robot_hwnh.hasParam(currentStepperNamespace +
"/d_max"))
331 robot_hwnh.getParam(currentStepperNamespace +
"/d_max", data);
332 profile.d_max =
static_cast<uint32_t
>(data);
334 if (robot_hwnh.hasParam(currentStepperNamespace +
"/d_1"))
336 robot_hwnh.getParam(currentStepperNamespace +
"/d_1", data);
337 profile.d_1 =
static_cast<uint32_t
>(data);
339 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_stop"))
341 robot_hwnh.getParam(currentStepperNamespace +
"/v_stop", data);
342 profile.v_stop =
static_cast<uint32_t
>(data);
346 stepperState->setOffsetPosition(offsetPos);
347 stepperState->setGearRatio(gear_ratio);
348 stepperState->setDirection(
static_cast<int8_t
>(direction));
349 stepperState->setMaxEffort(max_effort);
350 stepperState->setHomePosition(home_position);
351 stepperState->setLimitPositionMax(limit_position_max);
352 stepperState->setLimitPositionMin(limit_position_min);
353 stepperState->setMotorRatio(motor_ratio);
354 stepperState->setVelocityProfile(profile);
357 stepperState->updateMultiplierRatio();
359 if (eBusProto == EBusProtocol::TTL)
361 ttl_drv->addHardwareComponent(stepperState);
366 else if (eType != EHardwareType::UNKNOWN)
368 auto dxlState = std::make_shared<DxlMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
static_cast<uint8_t
>(joint_id_config));
371 double offsetPos = 0.0;
373 int positionPGain = 0;
374 int positionIGain = 0;
375 int positionDGain = 0;
376 int velocityPGain = 0;
377 int velocityIGain = 0;
380 int velocityProfile = 0;
381 int accelerationProfile = 0;
382 double limit_position_min = 0.0;
383 double limit_position_max = 0.0;
384 double home_position = 0.0;
386 std::string currentDxlNamespace =
"dynamixels/dxl_" + to_string(currentIdDxl);
388 robot_hwnh.getParam(currentDxlNamespace +
"/offset_position", offsetPos);
389 robot_hwnh.getParam(currentDxlNamespace +
"/direction", direction);
391 robot_hwnh.getParam(currentDxlNamespace +
"/position_P_gain", positionPGain);
392 robot_hwnh.getParam(currentDxlNamespace +
"/position_I_gain", positionIGain);
393 robot_hwnh.getParam(currentDxlNamespace +
"/position_D_gain", positionDGain);
395 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_P_gain", velocityPGain);
396 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_I_gain", velocityIGain);
398 robot_hwnh.getParam(currentDxlNamespace +
"/FF1_gain", FF1Gain);
399 robot_hwnh.getParam(currentDxlNamespace +
"/FF2_gain", FF2Gain);
401 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_profile", velocityProfile);
402 robot_hwnh.getParam(currentDxlNamespace +
"/acceleration_profile", accelerationProfile);
404 robot_hwnh.getParam(currentDxlNamespace +
"/default_home_position", home_position);
405 robot_hwnh.getParam(currentDxlNamespace +
"/limit_position_min", limit_position_min);
406 robot_hwnh.getParam(currentDxlNamespace +
"/limit_position_max", limit_position_max);
408 dxlState->setOffsetPosition(offsetPos);
409 dxlState->setDirection(
static_cast<int8_t
>(direction));
411 dxlState->setPositionPGain(
static_cast<uint32_t
>(positionPGain));
412 dxlState->setPositionIGain(
static_cast<uint32_t
>(positionIGain));
413 dxlState->setPositionDGain(
static_cast<uint32_t
>(positionDGain));
415 dxlState->setVelocityPGain(
static_cast<uint32_t
>(velocityPGain));
416 dxlState->setVelocityIGain(
static_cast<uint32_t
>(velocityIGain));
418 dxlState->setFF1Gain(
static_cast<uint32_t
>(FF1Gain));
419 dxlState->setFF2Gain(
static_cast<uint32_t
>(FF2Gain));
421 dxlState->setVelProfile(
static_cast<uint32_t
>(velocityProfile));
422 dxlState->setAccProfile(
static_cast<uint32_t
>(accelerationProfile));
424 dxlState->setLimitPositionMin(limit_position_min);
425 dxlState->setLimitPositionMax(limit_position_max);
427 dxlState->setHomePosition(home_position);
429 if (eBusProto == EBusProtocol::TTL)
431 ttl_drv->addHardwareComponent(dxlState);
451 ros::NodeHandle
nh(
"ttl_driver");
452 ros::Duration(5.0).sleep();
477 int resutl = ttl_interface->rebootHardware(ttl_interface->getJointState(4));
478 EXPECT_EQ(resutl,
static_cast<int>(niryo_robot_msgs::CommandStatus::SUCCESS));
485 result = ttl_interface->rebootHardware(std::make_shared<common::model::StepperMotorState>());
486 EXPECT_FALSE(result);
497 ros::NodeHandle
nh(
"ttl_driver");
498 ros::NodeHandle nh_private(
"~");
500 ttl_drv = std::make_shared<ttl_driver::TtlManager>(
nh);
511 if (
ttl_drv->getCalibrationStatus() != common::model::EStepperCalibrationStatus::OK)
516 state_motor_2 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(2));
517 state_motor_3 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(3));
518 state_motor_4 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(4));
519 state_motor_5 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(5));
520 state_motor_6 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(6));
521 state_motor_7 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(7));
529 auto state_motor_3 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(3));
531 int res =
ttl_drv->writeSingleCommand(
532 std::make_unique<common::model::StepperTtlSingleCmd>(common::model::StepperTtlSingleCmd(common::model::EStepperCommandType::CMD_TYPE_POSITION, 3, {steps})));
533 EXPECT_EQ(res, COMM_SUCCESS);
537 common::model::DxlSyncCmd dynamixel_cmd(common::model::EDxlCommandType::CMD_TYPE_POSITION);
539 for (
auto jState :
ttl_drv->getMotorsStates())
541 if (jState && jState->isDynamixel())
543 dynamixel_cmd.addMotorParam(jState->getHardwareType(), jState->getId(),
static_cast<uint32_t
>(jState->to_motor_pos(jState->getHomePosition())));
547 EXPECT_EQ(
ttl_drv->writeSynchronizeCommand(std::make_unique<common::model::DxlSyncCmd>(dynamixel_cmd)), COMM_SUCCESS);
551 for (uint8_t
id = 2;
id < 5;
id++)
553 uint8_t direction{0};
556 uint8_t stall_threshold{6};
558 EXPECT_EQ(
ttl_drv->writeSingleCommand(std::make_unique<common::model::StepperTtlSingleCmd>(
559 common::model::StepperTtlSingleCmd(common::model::EStepperCommandType::CMD_TYPE_CALIBRATION_SETUP,
id, {direction, stall_threshold}))),
561 EXPECT_EQ(
ttl_drv->writeSingleCommand(
562 std::make_unique<common::model::StepperTtlSingleCmd>(common::model::StepperTtlSingleCmd(common::model::EStepperCommandType::CMD_TYPE_CALIBRATION,
id))),
567 double timeout = 0.0;
568 while (
ttl_drv->getCalibrationStatus() != common::model::EStepperCalibrationStatus::OK)
573 ros::Duration(0.5).sleep();
582 static std::shared_ptr<ttl_driver::TtlManager>
ttl_drv;
605 EXPECT_NE(state_motor_2,
nullptr);
606 EXPECT_NE(state_motor_3,
nullptr);
607 EXPECT_NE(state_motor_4,
nullptr);
608 EXPECT_NE(state_motor_5,
nullptr);
609 EXPECT_NE(state_motor_6,
nullptr);
610 EXPECT_NE(state_motor_7,
nullptr);
613 TEST_F(
TtlManagerTestSuite, calibrationStatus) { ASSERT_EQ(ttl_drv->getCalibrationStatus(), common::model::EStepperCalibrationStatus::OK); }
618 auto cmd_1 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 5, std::initializer_list<uint32_t>{1});
619 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_1)), COMM_SUCCESS);
620 ros::Duration(0.01).sleep();
623 auto cmd_2 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 20, std::initializer_list<uint32_t>{1});
624 EXPECT_NE(ttl_drv->writeSingleCommand(std::move(cmd_2)), COMM_SUCCESS);
625 ros::Duration(0.01).sleep();
628 auto cmd_3 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_UNKNOWN, 2, std::initializer_list<uint32_t>{1});
629 EXPECT_NE(ttl_drv->writeSingleCommand(std::move(cmd_3)), COMM_SUCCESS);
630 ros::Duration(0.01).sleep();
633 auto cmd_4 = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE, 5, std::initializer_list<uint32_t>{1});
634 EXPECT_NE(ttl_drv->writeSingleCommand(std::move(cmd_4)), COMM_SUCCESS);
640 auto cmd_1_torque = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE, 2, std::initializer_list<uint32_t>{1});
642 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
643 ros::Duration(0.01).sleep();
645 auto cmd_2_torque = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE, 3, std::initializer_list<uint32_t>{1});
646 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
647 ros::Duration(0.01).sleep();
649 auto cmd_3_torque = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE, 4, std::initializer_list<uint32_t>{1});
650 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_3_torque)), COMM_SUCCESS);
651 ros::Duration(0.01).sleep();
653 auto cmd_4_torque = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 5, std::initializer_list<uint32_t>{1});
654 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_4_torque)), COMM_SUCCESS);
655 ros::Duration(0.01).sleep();
657 auto cmd_5_torque = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 6, std::initializer_list<uint32_t>{1});
658 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_5_torque)), COMM_SUCCESS);
659 ros::Duration(0.01).sleep();
661 auto cmd_6_torque = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 7, std::initializer_list<uint32_t>{1});
662 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_6_torque)), COMM_SUCCESS);
663 ros::Duration(0.01).sleep();
665 auto new_pos_2 =
static_cast<uint32_t
>(state_motor_2->to_motor_pos(state_motor_2->getHomePosition()));
666 auto new_pos_3 =
static_cast<uint32_t
>(state_motor_3->to_motor_pos(state_motor_3->getHomePosition()));
667 auto new_pos_4 =
static_cast<uint32_t
>(state_motor_4->to_motor_pos(state_motor_4->getHomePosition()));
668 auto new_pos_5 =
static_cast<uint32_t
>(state_motor_5->to_motor_pos(state_motor_5->getHomePosition()));
669 auto new_pos_6 =
static_cast<uint32_t
>(state_motor_6->to_motor_pos(state_motor_6->getHomePosition()));
670 auto new_pos_7 =
static_cast<uint32_t
>(state_motor_7->to_motor_pos(state_motor_7->getHomePosition()));
673 auto cmd_1 = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_POSITION, 2, std::initializer_list<uint32_t>{new_pos_2});
674 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_1)), COMM_SUCCESS);
675 ros::Duration(0.1).sleep();
678 auto cmd_2 = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_POSITION, 3, std::initializer_list<uint32_t>{new_pos_3});
679 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_2)), COMM_SUCCESS);
680 ros::Duration(0.1).sleep();
683 auto cmd_3 = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_POSITION, 4, std::initializer_list<uint32_t>{new_pos_4});
684 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_3)), COMM_SUCCESS);
685 ros::Duration(0.1).sleep();
688 auto cmd_4 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION, 5, std::initializer_list<uint32_t>{new_pos_5});
689 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_4)), COMM_SUCCESS);
690 ros::Duration(0.1).sleep();
693 auto cmd_5 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION, 6, std::initializer_list<uint32_t>{new_pos_6});
694 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_5)), COMM_SUCCESS);
695 ros::Duration(0.1).sleep();
698 auto cmd_6 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION, 7, std::initializer_list<uint32_t>{new_pos_7});
699 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_6)), COMM_SUCCESS);
700 ros::Duration(4.0).sleep();
702 ttl_drv->readJointsStatus();
705 EXPECT_NEAR(state_motor_2->getPosition(), new_pos_2, 2);
706 EXPECT_NEAR(state_motor_3->getPosition(), new_pos_3, 2);
707 EXPECT_NEAR(state_motor_4->getPosition(), new_pos_4, 2);
708 EXPECT_NEAR(state_motor_5->getPosition(), new_pos_5, 2);
709 EXPECT_NEAR(state_motor_6->getPosition(), new_pos_6, 2);
710 EXPECT_NEAR(state_motor_7->getPosition(), new_pos_7, 2);
716 auto dynamixel_cmd_1 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE);
717 dynamixel_cmd_1->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
718 dynamixel_cmd_1->addMotorParam(state_motor_6->getHardwareType(), 6, 1);
720 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_1)), COMM_SUCCESS);
721 ros::Duration(0.1).sleep();
724 auto dynamixel_cmd_3 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE);
725 dynamixel_cmd_3->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
726 dynamixel_cmd_3->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
728 EXPECT_NE(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_3)), COMM_SUCCESS);
731 auto dynamixel_cmd_4 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_UNKNOWN);
732 dynamixel_cmd_4->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
733 dynamixel_cmd_4->addMotorParam(state_motor_6->getHardwareType(), 6, 1);
735 EXPECT_NE(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_4)), COMM_SUCCESS);
741 auto cmd_1_torque = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE);
742 cmd_1_torque->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
743 cmd_1_torque->addMotorParam(state_motor_6->getHardwareType(), 6, 1);
744 cmd_1_torque->addMotorParam(state_motor_7->getHardwareType(), 7, 1);
746 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
747 ros::Duration(0.01).sleep();
749 auto cmd_2_torque = std::make_unique<common::model::StepperTtlSyncCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE);
750 cmd_2_torque->addMotorParam(state_motor_2->getHardwareType(), 2, 1);
751 cmd_2_torque->addMotorParam(state_motor_3->getHardwareType(), 3, 1);
752 cmd_2_torque->addMotorParam(state_motor_4->getHardwareType(), 4, 1);
754 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
755 ros::Duration(0.01).sleep();
757 ttl_drv->readJointsStatus();
759 auto new_pos_2 =
static_cast<uint32_t
>(state_motor_2->to_motor_pos(0.995));
760 auto new_pos_3 =
static_cast<uint32_t
>(state_motor_3->to_motor_pos(0.06));
761 auto new_pos_4 =
static_cast<uint32_t
>(state_motor_4->to_motor_pos(-0.44));
762 auto new_pos_5 =
static_cast<uint32_t
>(state_motor_5->to_motor_pos(0.956));
763 auto new_pos_6 =
static_cast<uint32_t
>(state_motor_6->to_motor_pos(0.602));
764 auto new_pos_7 =
static_cast<uint32_t
>(state_motor_7->to_motor_pos(0.884));
766 auto cmd_1 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION);
767 cmd_1->addMotorParam(state_motor_5->getHardwareType(), 5, new_pos_5);
768 cmd_1->addMotorParam(state_motor_6->getHardwareType(), 6, new_pos_6);
769 cmd_1->addMotorParam(state_motor_7->getHardwareType(), 7, new_pos_7);
771 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1)), COMM_SUCCESS);
772 ros::Duration(0.2).sleep();
774 auto cmd_2 = std::make_unique<common::model::StepperTtlSyncCmd>(common::model::EStepperCommandType::CMD_TYPE_POSITION);
775 cmd_2->addMotorParam(state_motor_2->getHardwareType(), 2, new_pos_2);
776 cmd_2->addMotorParam(state_motor_3->getHardwareType(), 3, new_pos_3);
777 cmd_2->addMotorParam(state_motor_4->getHardwareType(), 4, new_pos_4);
779 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2)), COMM_SUCCESS);
780 ros::Duration(4.0).sleep();
782 ttl_drv->readJointsStatus();
784 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_5->getPosition()), new_pos_5, 2);
785 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_6->getPosition()), new_pos_6, 2);
786 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_7->getPosition()), new_pos_7, 2);
787 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_4->getPosition()), new_pos_4, 2);
788 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_2->getPosition()), new_pos_2, 2);
789 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_3->getPosition()), new_pos_3, 2);
795 auto cmd_1_torque = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE);
796 cmd_1_torque->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
797 cmd_1_torque->addMotorParam(state_motor_6->getHardwareType(), 6, 1);
798 cmd_1_torque->addMotorParam(state_motor_7->getHardwareType(), 7, 1);
800 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
801 ros::Duration(0.01).sleep();
803 auto cmd_2_torque = std::make_unique<common::model::StepperTtlSyncCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE);
804 cmd_2_torque->addMotorParam(state_motor_2->getHardwareType(), 2, 1);
805 cmd_2_torque->addMotorParam(state_motor_3->getHardwareType(), 3, 1);
806 cmd_2_torque->addMotorParam(state_motor_4->getHardwareType(), 4, 1);
808 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
809 ros::Duration(0.01).sleep();
811 auto new_pos_2 =
static_cast<uint32_t
>(state_motor_2->to_motor_pos(state_motor_2->getHomePosition()));
812 auto new_pos_3 =
static_cast<uint32_t
>(state_motor_3->to_motor_pos(state_motor_3->getHomePosition()));
813 auto new_pos_4 =
static_cast<uint32_t
>(state_motor_4->to_motor_pos(state_motor_4->getHomePosition()));
814 auto new_pos_5 =
static_cast<uint32_t
>(state_motor_5->to_motor_pos(state_motor_5->getHomePosition()));
815 auto new_pos_6 =
static_cast<uint32_t
>(state_motor_6->to_motor_pos(state_motor_6->getHomePosition()));
816 auto new_pos_7 =
static_cast<uint32_t
>(state_motor_7->to_motor_pos(state_motor_7->getHomePosition()));
818 auto cmd_1 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION);
819 cmd_1->addMotorParam(state_motor_5->getHardwareType(), 5, new_pos_5);
820 cmd_1->addMotorParam(state_motor_6->getHardwareType(), 6, new_pos_6);
821 cmd_1->addMotorParam(state_motor_7->getHardwareType(), 7, new_pos_7);
823 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1)), COMM_SUCCESS);
824 ros::Duration(0.2).sleep();
826 auto cmd_2 = std::make_unique<common::model::StepperTtlSyncCmd>(common::model::EStepperCommandType::CMD_TYPE_POSITION);
827 cmd_2->addMotorParam(state_motor_2->getHardwareType(), 2, new_pos_2);
828 cmd_2->addMotorParam(state_motor_3->getHardwareType(), 3, new_pos_3);
829 cmd_2->addMotorParam(state_motor_4->getHardwareType(), 4, new_pos_4);
831 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2)), COMM_SUCCESS);
832 ros::Duration(4.0).sleep();
834 ttl_drv->readJointsStatus();
836 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_5->getPosition()), new_pos_5, 2);
837 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_6->getPosition()), new_pos_6, 2);
838 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_7->getPosition()), new_pos_7, 2);
839 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_4->getPosition()), new_pos_4, 2);
840 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_2->getPosition()), new_pos_2, 2);
841 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_3->getPosition()), new_pos_3, 2);
848 int main(
int argc,
char **argv)
850 testing::InitGoogleTest(&argc, argv);
851 ros::init(argc, argv,
"ttl_driver_unit_tests");
854 std::string hardware_version;
856 return RUN_ALL_TESTS();