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") &&
61 robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/name") &&
62 robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/type") &&
63 robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/bus"))
69 int currentIdStepper = 1;
71 for (
size_t j = 0; j < nb_joints; j++)
73 int joint_id_config = 0;
78 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/id", joint_id_config);
79 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/name", joint_name);
80 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/type", joint_type);
81 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/bus", joint_bus);
82 HardwareTypeEnum eType = HardwareTypeEnum(joint_type.c_str());
83 BusProtocolEnum eBusProto = BusProtocolEnum(joint_bus.c_str());
85 if (eType == EHardwareType::STEPPER || eType == EHardwareType::FAKE_STEPPER_MOTOR)
87 std::string currentStepperNamespace =
"steppers/stepper_" + to_string(currentIdStepper);
89 auto stepperState = std::make_shared<StepperMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
90 eBusProto,
static_cast<uint8_t
>(joint_id_config));
93 double offsetPos = 0.0;
94 double gear_ratio = 1.0;
96 double max_effort = 0.0;
97 double home_position = 0.0;
98 double limit_position_min = 0.0;
99 double limit_position_max = 0.0;
100 double motor_ratio = 0.0;
102 robot_hwnh.getParam(currentStepperNamespace +
"/offset_position", offsetPos);
103 robot_hwnh.getParam(currentStepperNamespace +
"/gear_ratio", gear_ratio);
104 robot_hwnh.getParam(currentStepperNamespace +
"/direction", direction);
105 robot_hwnh.getParam(currentStepperNamespace +
"/max_effort", max_effort);
106 robot_hwnh.getParam(currentStepperNamespace +
"/default_home_position", home_position);
107 robot_hwnh.getParam(currentStepperNamespace +
"/limit_position_min", limit_position_min);
108 robot_hwnh.getParam(currentStepperNamespace +
"/limit_position_max", limit_position_max);
109 robot_hwnh.getParam(currentStepperNamespace +
"/motor_ratio", motor_ratio);
112 common::model::VelocityProfile profile{};
114 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_start"))
116 robot_hwnh.getParam(currentStepperNamespace +
"/v_start", data);
117 profile.v_start =
static_cast<uint32_t
>(data);
120 if (robot_hwnh.hasParam(currentStepperNamespace +
"/a_1"))
122 robot_hwnh.getParam(currentStepperNamespace +
"/a_1", data);
123 profile.a_1 =
static_cast<uint32_t
>(data);
125 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_1"))
127 robot_hwnh.getParam(currentStepperNamespace +
"/v_1", data);
128 profile.v_1 =
static_cast<uint32_t
>(data);
130 if (robot_hwnh.hasParam(currentStepperNamespace +
"/a_max"))
132 robot_hwnh.getParam(currentStepperNamespace +
"/a_max", data);
133 profile.a_max =
static_cast<uint32_t
>(data);
135 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_max"))
137 robot_hwnh.getParam(currentStepperNamespace +
"/v_max", data);
138 profile.v_max =
static_cast<uint32_t
>(data);
140 if (robot_hwnh.hasParam(currentStepperNamespace +
"/d_max"))
142 robot_hwnh.getParam(currentStepperNamespace +
"/d_max", data);
143 profile.d_max =
static_cast<uint32_t
>(data);
145 if (robot_hwnh.hasParam(currentStepperNamespace +
"/d_1"))
147 robot_hwnh.getParam(currentStepperNamespace +
"/d_1", data);
148 profile.d_1 =
static_cast<uint32_t
>(data);
150 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_stop"))
152 robot_hwnh.getParam(currentStepperNamespace +
"/v_stop", data);
153 profile.v_stop =
static_cast<uint32_t
>(data);
157 stepperState->setOffsetPosition(offsetPos);
158 stepperState->setGearRatio(gear_ratio);
159 stepperState->setDirection(
static_cast<int8_t
>(direction));
160 stepperState->setMaxEffort(max_effort);
161 stepperState->setHomePosition(home_position);
162 stepperState->setLimitPositionMax(limit_position_max);
163 stepperState->setLimitPositionMin(limit_position_min);
164 stepperState->setMotorRatio(motor_ratio);
165 stepperState->setVelocityProfile(profile);
167 if (eBusProto == EBusProtocol::TTL)
168 ttl_interface->addJoint(stepperState);
173 else if (eType != EHardwareType::UNKNOWN)
175 auto dxlState = std::make_shared<DxlMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
176 static_cast<uint8_t
>(joint_id_config));
179 double offsetPos = 0.0;
181 int positionPGain = 0;
182 int positionIGain = 0;
183 int positionDGain = 0;
184 int velocityPGain = 0;
185 int velocityIGain = 0;
188 int velocityProfile = 0;
189 int accelerationProfile = 0;
190 double limit_position_min = 0.0;
191 double limit_position_max = 0.0;
192 double home_position = 0.0;
194 std::string currentDxlNamespace =
"dynamixels/dxl_" + to_string(currentIdDxl);
196 robot_hwnh.getParam(currentDxlNamespace +
"/offset_position", offsetPos);
197 robot_hwnh.getParam(currentDxlNamespace +
"/direction", direction);
199 robot_hwnh.getParam(currentDxlNamespace +
"/position_P_gain", positionPGain);
200 robot_hwnh.getParam(currentDxlNamespace +
"/position_I_gain", positionIGain);
201 robot_hwnh.getParam(currentDxlNamespace +
"/position_D_gain", positionDGain);
203 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_P_gain", velocityPGain);
204 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_I_gain", velocityIGain);
206 robot_hwnh.getParam(currentDxlNamespace +
"/FF1_gain", FF1Gain);
207 robot_hwnh.getParam(currentDxlNamespace +
"/FF2_gain", FF2Gain);
209 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_profile", velocityProfile);
210 robot_hwnh.getParam(currentDxlNamespace +
"/acceleration_profile", accelerationProfile);
212 robot_hwnh.getParam(currentDxlNamespace +
"/default_home_position", home_position);
213 robot_hwnh.getParam(currentDxlNamespace +
"/limit_position_min", limit_position_min);
214 robot_hwnh.getParam(currentDxlNamespace +
"/limit_position_max", limit_position_max);
216 dxlState->setOffsetPosition(offsetPos);
217 dxlState->setDirection(
static_cast<int8_t
>(direction));
219 dxlState->setPositionPGain(
static_cast<uint32_t
>(positionPGain));
220 dxlState->setPositionIGain(
static_cast<uint32_t
>(positionIGain));
221 dxlState->setPositionDGain(
static_cast<uint32_t
>(positionDGain));
223 dxlState->setVelocityPGain(
static_cast<uint32_t
>(velocityPGain));
224 dxlState->setVelocityIGain(
static_cast<uint32_t
>(velocityIGain));
226 dxlState->setFF1Gain(
static_cast<uint32_t
>(FF1Gain));
227 dxlState->setFF2Gain(
static_cast<uint32_t
>(FF2Gain));
229 dxlState->setVelProfile(
static_cast<uint32_t
>(velocityProfile));
230 dxlState->setAccProfile(
static_cast<uint32_t
>(accelerationProfile));
232 dxlState->setLimitPositionMin(limit_position_min);
233 dxlState->setLimitPositionMax(limit_position_max);
235 dxlState->setHomePosition(home_position);
237 if (eBusProto == EBusProtocol::TTL)
238 ttl_interface->addJoint(dxlState);
252 size_t nb_joints = 0;
254 ros::NodeHandle robot_hwnh(
"joints_interface");
256 while (robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/id") &&
257 robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/name") &&
258 robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/type") &&
259 robot_hwnh.hasParam(
"joint_" + to_string(nb_joints + 1) +
"/bus"))
263 int currentIdStepper = 1;
264 int currentIdDxl = 1;
266 for (
size_t j = 0; j < nb_joints; j++)
268 int joint_id_config = 0;
273 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/id", joint_id_config);
274 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/name", joint_name);
275 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/type", joint_type);
276 robot_hwnh.getParam(
"joint_" + to_string(j + 1) +
"/bus", joint_bus);
278 HardwareTypeEnum eType = HardwareTypeEnum(joint_type.c_str());
279 BusProtocolEnum eBusProto = BusProtocolEnum(joint_bus.c_str());
281 if (eType == EHardwareType::STEPPER || eType == EHardwareType::FAKE_STEPPER_MOTOR)
283 std::string currentStepperNamespace =
"steppers/stepper_" + to_string(currentIdStepper);
285 auto stepperState = std::make_shared<StepperMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
286 eBusProto,
static_cast<uint8_t
>(joint_id_config));
289 double offsetPos = 0.0;
290 double gear_ratio = 1.0;
292 double max_effort = 0.0;
293 double home_position = 0.0;
294 double limit_position_min = 0.0;
295 double limit_position_max = 0.0;
296 double motor_ratio = 0.0;
298 robot_hwnh.getParam(currentStepperNamespace +
"/offset_position", offsetPos);
299 robot_hwnh.getParam(currentStepperNamespace +
"/gear_ratio", gear_ratio);
300 robot_hwnh.getParam(currentStepperNamespace +
"/direction", direction);
301 robot_hwnh.getParam(currentStepperNamespace +
"/max_effort", max_effort);
302 robot_hwnh.getParam(currentStepperNamespace +
"/default_home_position", home_position);
303 robot_hwnh.getParam(currentStepperNamespace +
"/limit_position_min", limit_position_min);
304 robot_hwnh.getParam(currentStepperNamespace +
"/limit_position_max", limit_position_max);
305 robot_hwnh.getParam(currentStepperNamespace +
"/motor_ratio", motor_ratio);
308 common::model::VelocityProfile profile{};
310 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_start"))
312 robot_hwnh.getParam(currentStepperNamespace +
"/v_start", data);
313 profile.v_start =
static_cast<uint32_t
>(data);
316 if (robot_hwnh.hasParam(currentStepperNamespace +
"/a_1"))
318 robot_hwnh.getParam(currentStepperNamespace +
"/a_1", data);
319 profile.a_1 =
static_cast<uint32_t
>(data);
321 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_1"))
323 robot_hwnh.getParam(currentStepperNamespace +
"/v_1", data);
324 profile.v_1 =
static_cast<uint32_t
>(data);
326 if (robot_hwnh.hasParam(currentStepperNamespace +
"/a_max"))
328 robot_hwnh.getParam(currentStepperNamespace +
"/a_max", data);
329 profile.a_max =
static_cast<uint32_t
>(data);
331 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_max"))
333 robot_hwnh.getParam(currentStepperNamespace +
"/v_max", data);
334 profile.v_max =
static_cast<uint32_t
>(data);
336 if (robot_hwnh.hasParam(currentStepperNamespace +
"/d_max"))
338 robot_hwnh.getParam(currentStepperNamespace +
"/d_max", data);
339 profile.d_max =
static_cast<uint32_t
>(data);
341 if (robot_hwnh.hasParam(currentStepperNamespace +
"/d_1"))
343 robot_hwnh.getParam(currentStepperNamespace +
"/d_1", data);
344 profile.d_1 =
static_cast<uint32_t
>(data);
346 if (robot_hwnh.hasParam(currentStepperNamespace +
"/v_stop"))
348 robot_hwnh.getParam(currentStepperNamespace +
"/v_stop", data);
349 profile.v_stop =
static_cast<uint32_t
>(data);
353 stepperState->setOffsetPosition(offsetPos);
354 stepperState->setGearRatio(gear_ratio);
355 stepperState->setDirection(
static_cast<int8_t
>(direction));
356 stepperState->setMaxEffort(max_effort);
357 stepperState->setHomePosition(home_position);
358 stepperState->setLimitPositionMax(limit_position_max);
359 stepperState->setLimitPositionMin(limit_position_min);
360 stepperState->setMotorRatio(motor_ratio);
361 stepperState->setVelocityProfile(profile);
364 stepperState->updateMultiplierRatio();
366 if (eBusProto == EBusProtocol::TTL)
368 ttl_drv->addHardwareComponent(stepperState);
373 else if (eType != EHardwareType::UNKNOWN)
375 auto dxlState = std::make_shared<DxlMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
376 static_cast<uint8_t
>(joint_id_config));
379 double offsetPos = 0.0;
381 int positionPGain = 0;
382 int positionIGain = 0;
383 int positionDGain = 0;
384 int velocityPGain = 0;
385 int velocityIGain = 0;
388 int velocityProfile = 0;
389 int accelerationProfile = 0;
390 double limit_position_min = 0.0;
391 double limit_position_max = 0.0;
392 double home_position = 0.0;
394 std::string currentDxlNamespace =
"dynamixels/dxl_" + to_string(currentIdDxl);
396 robot_hwnh.getParam(currentDxlNamespace +
"/offset_position", offsetPos);
397 robot_hwnh.getParam(currentDxlNamespace +
"/direction", direction);
399 robot_hwnh.getParam(currentDxlNamespace +
"/position_P_gain", positionPGain);
400 robot_hwnh.getParam(currentDxlNamespace +
"/position_I_gain", positionIGain);
401 robot_hwnh.getParam(currentDxlNamespace +
"/position_D_gain", positionDGain);
403 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_P_gain", velocityPGain);
404 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_I_gain", velocityIGain);
406 robot_hwnh.getParam(currentDxlNamespace +
"/FF1_gain", FF1Gain);
407 robot_hwnh.getParam(currentDxlNamespace +
"/FF2_gain", FF2Gain);
409 robot_hwnh.getParam(currentDxlNamespace +
"/velocity_profile", velocityProfile);
410 robot_hwnh.getParam(currentDxlNamespace +
"/acceleration_profile", accelerationProfile);
412 robot_hwnh.getParam(currentDxlNamespace +
"/default_home_position", home_position);
413 robot_hwnh.getParam(currentDxlNamespace +
"/limit_position_min", limit_position_min);
414 robot_hwnh.getParam(currentDxlNamespace +
"/limit_position_max", limit_position_max);
416 dxlState->setOffsetPosition(offsetPos);
417 dxlState->setDirection(
static_cast<int8_t
>(direction));
419 dxlState->setPositionPGain(
static_cast<uint32_t
>(positionPGain));
420 dxlState->setPositionIGain(
static_cast<uint32_t
>(positionIGain));
421 dxlState->setPositionDGain(
static_cast<uint32_t
>(positionDGain));
423 dxlState->setVelocityPGain(
static_cast<uint32_t
>(velocityPGain));
424 dxlState->setVelocityIGain(
static_cast<uint32_t
>(velocityIGain));
426 dxlState->setFF1Gain(
static_cast<uint32_t
>(FF1Gain));
427 dxlState->setFF2Gain(
static_cast<uint32_t
>(FF2Gain));
429 dxlState->setVelProfile(
static_cast<uint32_t
>(velocityProfile));
430 dxlState->setAccProfile(
static_cast<uint32_t
>(accelerationProfile));
432 dxlState->setLimitPositionMin(limit_position_min);
433 dxlState->setLimitPositionMax(limit_position_max);
435 dxlState->setHomePosition(home_position);
437 if (eBusProto == EBusProtocol::TTL)
439 ttl_drv->addHardwareComponent(dxlState);
459 ros::NodeHandle
nh(
"ttl_driver");
460 ros::Duration(5.0).sleep();
488 int resutl = ttl_interface->rebootHardware(ttl_interface->getJointState(4));
489 EXPECT_EQ(resutl,
static_cast<int>(niryo_robot_msgs::CommandStatus::SUCCESS));
496 result = ttl_interface->rebootHardware(std::make_shared<common::model::StepperMotorState>());
497 EXPECT_FALSE(result);
508 ros::NodeHandle
nh(
"ttl_driver");
509 ros::NodeHandle nh_private(
"~");
511 ttl_drv = std::make_shared<ttl_driver::TtlManager>(
nh);
522 if (
ttl_drv->getCalibrationStatus() != common::model::EStepperCalibrationStatus::OK)
527 state_motor_2 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(2));
528 state_motor_3 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(3));
529 state_motor_4 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(4));
530 state_motor_5 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(5));
531 state_motor_6 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(6));
532 state_motor_7 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(7));
540 auto state_motor_3 = std::dynamic_pointer_cast<common::model::JointState>(
ttl_drv->getHardwareState(3));
542 int res =
ttl_drv->writeSingleCommand(std::make_unique<common::model::StepperTtlSingleCmd>(
543 common::model::StepperTtlSingleCmd(common::model::EStepperCommandType::CMD_TYPE_POSITION, 3, { steps })));
544 EXPECT_EQ(res, COMM_SUCCESS);
548 common::model::DxlSyncCmd dynamixel_cmd(common::model::EDxlCommandType::CMD_TYPE_POSITION);
550 for (
auto jState :
ttl_drv->getMotorsStates())
552 if (jState && jState->isDynamixel())
554 dynamixel_cmd.addMotorParam(jState->getHardwareType(), jState->getId(),
555 static_cast<uint32_t
>(jState->to_motor_pos(jState->getHomePosition())));
559 EXPECT_EQ(
ttl_drv->writeSynchronizeCommand(std::make_unique<common::model::DxlSyncCmd>(dynamixel_cmd)),
564 for (uint8_t
id = 2;
id < 5;
id++)
566 uint8_t direction{ 0 };
569 uint8_t stall_threshold{ 6 };
571 EXPECT_EQ(
ttl_drv->writeSingleCommand(std::make_unique<common::model::StepperTtlSingleCmd>(
572 common::model::StepperTtlSingleCmd(common::model::EStepperCommandType::CMD_TYPE_CALIBRATION_SETUP,
573 id, { direction, stall_threshold }))),
575 EXPECT_EQ(
ttl_drv->writeSingleCommand(std::make_unique<common::model::StepperTtlSingleCmd>(
576 common::model::StepperTtlSingleCmd(common::model::EStepperCommandType::CMD_TYPE_CALIBRATION,
id))),
581 double timeout = 0.0;
582 while (
ttl_drv->getCalibrationStatus() != common::model::EStepperCalibrationStatus::OK)
587 ros::Duration(0.5).sleep();
596 static std::shared_ptr<ttl_driver::TtlManager>
ttl_drv;
619 EXPECT_NE(state_motor_2,
nullptr);
620 EXPECT_NE(state_motor_3,
nullptr);
621 EXPECT_NE(state_motor_4,
nullptr);
622 EXPECT_NE(state_motor_5,
nullptr);
623 EXPECT_NE(state_motor_6,
nullptr);
624 EXPECT_NE(state_motor_7,
nullptr);
629 ASSERT_EQ(ttl_drv->getCalibrationStatus(), common::model::EStepperCalibrationStatus::OK);
635 auto cmd_1 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 5,
636 std::initializer_list<uint32_t>{ 1 });
637 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_1)), COMM_SUCCESS);
638 ros::Duration(0.01).sleep();
641 auto cmd_2 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 20,
642 std::initializer_list<uint32_t>{ 1 });
643 EXPECT_NE(ttl_drv->writeSingleCommand(std::move(cmd_2)), COMM_SUCCESS);
644 ros::Duration(0.01).sleep();
647 auto cmd_3 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_UNKNOWN, 2,
648 std::initializer_list<uint32_t>{ 1 });
649 EXPECT_NE(ttl_drv->writeSingleCommand(std::move(cmd_3)), COMM_SUCCESS);
650 ros::Duration(0.01).sleep();
653 auto cmd_4 = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE,
654 5, std::initializer_list<uint32_t>{ 1 });
655 EXPECT_NE(ttl_drv->writeSingleCommand(std::move(cmd_4)), COMM_SUCCESS);
661 auto cmd_1_torque = std::make_unique<common::model::StepperTtlSingleCmd>(
662 common::model::EStepperCommandType::CMD_TYPE_TORQUE, 2, std::initializer_list<uint32_t>{ 1 });
664 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
665 ros::Duration(0.01).sleep();
667 auto cmd_2_torque = std::make_unique<common::model::StepperTtlSingleCmd>(
668 common::model::EStepperCommandType::CMD_TYPE_TORQUE, 3, std::initializer_list<uint32_t>{ 1 });
669 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
670 ros::Duration(0.01).sleep();
672 auto cmd_3_torque = std::make_unique<common::model::StepperTtlSingleCmd>(
673 common::model::EStepperCommandType::CMD_TYPE_TORQUE, 4, std::initializer_list<uint32_t>{ 1 });
674 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_3_torque)), COMM_SUCCESS);
675 ros::Duration(0.01).sleep();
677 auto cmd_4_torque = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 5,
678 std::initializer_list<uint32_t>{ 1 });
679 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_4_torque)), COMM_SUCCESS);
680 ros::Duration(0.01).sleep();
682 auto cmd_5_torque = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 6,
683 std::initializer_list<uint32_t>{ 1 });
684 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_5_torque)), COMM_SUCCESS);
685 ros::Duration(0.01).sleep();
687 auto cmd_6_torque = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE, 7,
688 std::initializer_list<uint32_t>{ 1 });
689 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_6_torque)), COMM_SUCCESS);
690 ros::Duration(0.01).sleep();
692 auto new_pos_2 =
static_cast<uint32_t
>(state_motor_2->to_motor_pos(state_motor_2->getHomePosition()));
693 auto new_pos_3 =
static_cast<uint32_t
>(state_motor_3->to_motor_pos(state_motor_3->getHomePosition()));
694 auto new_pos_4 =
static_cast<uint32_t
>(state_motor_4->to_motor_pos(state_motor_4->getHomePosition()));
695 auto new_pos_5 =
static_cast<uint32_t
>(state_motor_5->to_motor_pos(state_motor_5->getHomePosition()));
696 auto new_pos_6 =
static_cast<uint32_t
>(state_motor_6->to_motor_pos(state_motor_6->getHomePosition()));
697 auto new_pos_7 =
static_cast<uint32_t
>(state_motor_7->to_motor_pos(state_motor_7->getHomePosition()));
700 auto cmd_1 = std::make_unique<common::model::StepperTtlSingleCmd>(
701 common::model::EStepperCommandType::CMD_TYPE_POSITION, 2, std::initializer_list<uint32_t>{ new_pos_2 });
702 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_1)), COMM_SUCCESS);
703 ros::Duration(0.1).sleep();
706 auto cmd_2 = std::make_unique<common::model::StepperTtlSingleCmd>(
707 common::model::EStepperCommandType::CMD_TYPE_POSITION, 3, std::initializer_list<uint32_t>{ new_pos_3 });
708 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_2)), COMM_SUCCESS);
709 ros::Duration(0.1).sleep();
712 auto cmd_3 = std::make_unique<common::model::StepperTtlSingleCmd>(
713 common::model::EStepperCommandType::CMD_TYPE_POSITION, 4, std::initializer_list<uint32_t>{ new_pos_4 });
714 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_3)), COMM_SUCCESS);
715 ros::Duration(0.1).sleep();
718 auto cmd_4 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION, 5,
719 std::initializer_list<uint32_t>{ new_pos_5 });
720 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_4)), COMM_SUCCESS);
721 ros::Duration(0.1).sleep();
724 auto cmd_5 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION, 6,
725 std::initializer_list<uint32_t>{ new_pos_6 });
726 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_5)), COMM_SUCCESS);
727 ros::Duration(0.1).sleep();
730 auto cmd_6 = std::make_unique<common::model::DxlSingleCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION, 7,
731 std::initializer_list<uint32_t>{ new_pos_7 });
732 EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_6)), COMM_SUCCESS);
733 ros::Duration(4.0).sleep();
735 ttl_drv->readJointsStatus();
738 EXPECT_NEAR(state_motor_2->getPosition(), new_pos_2, 2);
739 EXPECT_NEAR(state_motor_3->getPosition(), new_pos_3, 2);
740 EXPECT_NEAR(state_motor_4->getPosition(), new_pos_4, 2);
741 EXPECT_NEAR(state_motor_5->getPosition(), new_pos_5, 2);
742 EXPECT_NEAR(state_motor_6->getPosition(), new_pos_6, 2);
743 EXPECT_NEAR(state_motor_7->getPosition(), new_pos_7, 2);
749 auto dynamixel_cmd_1 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE);
750 dynamixel_cmd_1->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
751 dynamixel_cmd_1->addMotorParam(state_motor_6->getHardwareType(), 6, 1);
753 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_1)), COMM_SUCCESS);
754 ros::Duration(0.1).sleep();
757 auto dynamixel_cmd_3 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE);
758 dynamixel_cmd_3->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
759 dynamixel_cmd_3->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
761 EXPECT_NE(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_3)), COMM_SUCCESS);
764 auto dynamixel_cmd_4 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_UNKNOWN);
765 dynamixel_cmd_4->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
766 dynamixel_cmd_4->addMotorParam(state_motor_6->getHardwareType(), 6, 1);
768 EXPECT_NE(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_4)), COMM_SUCCESS);
774 auto cmd_1_torque = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE);
775 cmd_1_torque->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
776 cmd_1_torque->addMotorParam(state_motor_6->getHardwareType(), 6, 1);
777 cmd_1_torque->addMotorParam(state_motor_7->getHardwareType(), 7, 1);
779 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
780 ros::Duration(0.01).sleep();
783 std::make_unique<common::model::StepperTtlSyncCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE);
784 cmd_2_torque->addMotorParam(state_motor_2->getHardwareType(), 2, 1);
785 cmd_2_torque->addMotorParam(state_motor_3->getHardwareType(), 3, 1);
786 cmd_2_torque->addMotorParam(state_motor_4->getHardwareType(), 4, 1);
788 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
789 ros::Duration(0.01).sleep();
791 ttl_drv->readJointsStatus();
793 auto new_pos_2 =
static_cast<uint32_t
>(state_motor_2->to_motor_pos(0.995));
794 auto new_pos_3 =
static_cast<uint32_t
>(state_motor_3->to_motor_pos(0.06));
795 auto new_pos_4 =
static_cast<uint32_t
>(state_motor_4->to_motor_pos(-0.44));
796 auto new_pos_5 =
static_cast<uint32_t
>(state_motor_5->to_motor_pos(0.956));
797 auto new_pos_6 =
static_cast<uint32_t
>(state_motor_6->to_motor_pos(0.602));
798 auto new_pos_7 =
static_cast<uint32_t
>(state_motor_7->to_motor_pos(0.884));
800 auto cmd_1 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION);
801 cmd_1->addMotorParam(state_motor_5->getHardwareType(), 5, new_pos_5);
802 cmd_1->addMotorParam(state_motor_6->getHardwareType(), 6, new_pos_6);
803 cmd_1->addMotorParam(state_motor_7->getHardwareType(), 7, new_pos_7);
805 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1)), COMM_SUCCESS);
806 ros::Duration(0.2).sleep();
809 std::make_unique<common::model::StepperTtlSyncCmd>(common::model::EStepperCommandType::CMD_TYPE_POSITION);
810 cmd_2->addMotorParam(state_motor_2->getHardwareType(), 2, new_pos_2);
811 cmd_2->addMotorParam(state_motor_3->getHardwareType(), 3, new_pos_3);
812 cmd_2->addMotorParam(state_motor_4->getHardwareType(), 4, new_pos_4);
814 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2)), COMM_SUCCESS);
815 ros::Duration(4.0).sleep();
817 ttl_drv->readJointsStatus();
819 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_5->getPosition()), new_pos_5, 2);
820 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_6->getPosition()), new_pos_6, 2);
821 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_7->getPosition()), new_pos_7, 2);
822 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_4->getPosition()), new_pos_4, 2);
823 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_2->getPosition()), new_pos_2, 2);
824 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_3->getPosition()), new_pos_3, 2);
830 auto cmd_1_torque = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_TORQUE);
831 cmd_1_torque->addMotorParam(state_motor_5->getHardwareType(), 5, 1);
832 cmd_1_torque->addMotorParam(state_motor_6->getHardwareType(), 6, 1);
833 cmd_1_torque->addMotorParam(state_motor_7->getHardwareType(), 7, 1);
835 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
836 ros::Duration(0.01).sleep();
839 std::make_unique<common::model::StepperTtlSyncCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE);
840 cmd_2_torque->addMotorParam(state_motor_2->getHardwareType(), 2, 1);
841 cmd_2_torque->addMotorParam(state_motor_3->getHardwareType(), 3, 1);
842 cmd_2_torque->addMotorParam(state_motor_4->getHardwareType(), 4, 1);
844 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
845 ros::Duration(0.01).sleep();
847 auto new_pos_2 =
static_cast<uint32_t
>(state_motor_2->to_motor_pos(state_motor_2->getHomePosition()));
848 auto new_pos_3 =
static_cast<uint32_t
>(state_motor_3->to_motor_pos(state_motor_3->getHomePosition()));
849 auto new_pos_4 =
static_cast<uint32_t
>(state_motor_4->to_motor_pos(state_motor_4->getHomePosition()));
850 auto new_pos_5 =
static_cast<uint32_t
>(state_motor_5->to_motor_pos(state_motor_5->getHomePosition()));
851 auto new_pos_6 =
static_cast<uint32_t
>(state_motor_6->to_motor_pos(state_motor_6->getHomePosition()));
852 auto new_pos_7 =
static_cast<uint32_t
>(state_motor_7->to_motor_pos(state_motor_7->getHomePosition()));
854 auto cmd_1 = std::make_unique<common::model::DxlSyncCmd>(common::model::EDxlCommandType::CMD_TYPE_POSITION);
855 cmd_1->addMotorParam(state_motor_5->getHardwareType(), 5, new_pos_5);
856 cmd_1->addMotorParam(state_motor_6->getHardwareType(), 6, new_pos_6);
857 cmd_1->addMotorParam(state_motor_7->getHardwareType(), 7, new_pos_7);
859 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1)), COMM_SUCCESS);
860 ros::Duration(0.2).sleep();
863 std::make_unique<common::model::StepperTtlSyncCmd>(common::model::EStepperCommandType::CMD_TYPE_POSITION);
864 cmd_2->addMotorParam(state_motor_2->getHardwareType(), 2, new_pos_2);
865 cmd_2->addMotorParam(state_motor_3->getHardwareType(), 3, new_pos_3);
866 cmd_2->addMotorParam(state_motor_4->getHardwareType(), 4, new_pos_4);
868 EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2)), COMM_SUCCESS);
869 ros::Duration(4.0).sleep();
871 ttl_drv->readJointsStatus();
873 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_5->getPosition()), new_pos_5, 2);
874 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_6->getPosition()), new_pos_6, 2);
875 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_7->getPosition()), new_pos_7, 2);
876 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_4->getPosition()), new_pos_4, 2);
877 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_2->getPosition()), new_pos_2, 2);
878 EXPECT_NEAR(
static_cast<uint32_t
>(state_motor_3->getPosition()), new_pos_3, 2);
884 EXPECT_EQ(ttl_drv->scanAndCheck(), COMM_SUCCESS);
888 int main(
int argc,
char **argv)
890 testing::InitGoogleTest(&argc, argv);
891 ros::init(argc, argv,
"ttl_driver_unit_tests");
894 std::string hardware_version;
896 return RUN_ALL_TESTS();