unit_tests_ned2.cpp
Go to the documentation of this file.
1 /*
2  ttl_driver_unit_tests.cpp
3  Copyright (C) 2020 Niryo
4  All rights reserved.
5  This program is free software: you can redistribute it and/or modify
6  it under the terms of the GNU General Public License as published by
7  the Free Software Foundation, either version 3 of the License, or
8  (at your option) any later version.
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13  You should have received a copy of the GNU General Public License
14  along with this program. If not, see <http:// www.gnu.org/licenses/>.
15 */
16 
17 // Bring in my package's API, which is what I'm testing
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"
32 
33 // Bring in gtest
34 #include <cassert>
35 #include <gtest/gtest.h>
36 #include <memory>
37 #include <ros/console.h>
38 #include <string>
39 #include <utility>
40 
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;
47 using ::std::string;
48 using ::std::to_string;
49 
54 void addJointToTtlInterface(const std::shared_ptr<ttl_driver::TtlInterfaceCore> &ttl_interface)
55 {
56  size_t nb_joints = 0;
57 
58  ros::NodeHandle robot_hwnh("joints_interface");
59  // retrieve nb joints with checking that the config param exists for both name and id
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"))
62  nb_joints++;
63 
64  // connect and register joint state interface
65 
66  int currentIdDxl = 1;
67  int currentIdStepper = 1;
68 
69  for (size_t j = 0; j < nb_joints; j++)
70  {
71  int joint_id_config = 0;
72  string joint_name;
73  string joint_type;
74  string joint_bus;
75 
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());
82 
83  if (eType == EHardwareType::STEPPER || eType == EHardwareType::FAKE_STEPPER_MOTOR)
84  { // stepper
85  std::string currentStepperNamespace = "steppers/stepper_" + to_string(currentIdStepper);
86 
87  auto stepperState = std::make_shared<StepperMotorState>(joint_name, eType, common::model::EComponentType::JOINT, eBusProto, static_cast<uint8_t>(joint_id_config));
88  if (stepperState)
89  {
90  double offsetPos = 0.0;
91  double gear_ratio = 1.0;
92  int direction = 1;
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;
98 
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);
107 
108  // acceleration and velocity profiles
109  common::model::VelocityProfile profile{};
110  int data{};
111  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_start"))
112  {
113  robot_hwnh.getParam(currentStepperNamespace + "/v_start", data);
114  profile.v_start = static_cast<uint32_t>(data);
115  }
116 
117  if (robot_hwnh.hasParam(currentStepperNamespace + "/a_1"))
118  {
119  robot_hwnh.getParam(currentStepperNamespace + "/a_1", data);
120  profile.a_1 = static_cast<uint32_t>(data);
121  }
122  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_1"))
123  {
124  robot_hwnh.getParam(currentStepperNamespace + "/v_1", data);
125  profile.v_1 = static_cast<uint32_t>(data);
126  }
127  if (robot_hwnh.hasParam(currentStepperNamespace + "/a_max"))
128  {
129  robot_hwnh.getParam(currentStepperNamespace + "/a_max", data);
130  profile.a_max = static_cast<uint32_t>(data);
131  }
132  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_max"))
133  {
134  robot_hwnh.getParam(currentStepperNamespace + "/v_max", data);
135  profile.v_max = static_cast<uint32_t>(data);
136  }
137  if (robot_hwnh.hasParam(currentStepperNamespace + "/d_max"))
138  {
139  robot_hwnh.getParam(currentStepperNamespace + "/d_max", data);
140  profile.d_max = static_cast<uint32_t>(data);
141  }
142  if (robot_hwnh.hasParam(currentStepperNamespace + "/d_1"))
143  {
144  robot_hwnh.getParam(currentStepperNamespace + "/d_1", data);
145  profile.d_1 = static_cast<uint32_t>(data);
146  }
147  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_stop"))
148  {
149  robot_hwnh.getParam(currentStepperNamespace + "/v_stop", data);
150  profile.v_stop = static_cast<uint32_t>(data);
151  }
152 
153  // add parameters
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);
163 
164  if (eBusProto == EBusProtocol::TTL)
165  ttl_interface->addJoint(stepperState);
166 
167  currentIdStepper++;
168  }
169  }
170  else if (eType != EHardwareType::UNKNOWN)
171  { // dynamixel
172  auto dxlState = std::make_shared<DxlMotorState>(joint_name, eType, common::model::EComponentType::JOINT, static_cast<uint8_t>(joint_id_config));
173  if (dxlState)
174  {
175  double offsetPos = 0.0;
176  int direction = 1;
177  int positionPGain = 0;
178  int positionIGain = 0;
179  int positionDGain = 0;
180  int velocityPGain = 0;
181  int velocityIGain = 0;
182  int FF1Gain = 0;
183  int FF2Gain = 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;
189 
190  std::string currentDxlNamespace = "dynamixels/dxl_" + to_string(currentIdDxl);
191 
192  robot_hwnh.getParam(currentDxlNamespace + "/offset_position", offsetPos);
193  robot_hwnh.getParam(currentDxlNamespace + "/direction", direction);
194 
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);
198 
199  robot_hwnh.getParam(currentDxlNamespace + "/velocity_P_gain", velocityPGain);
200  robot_hwnh.getParam(currentDxlNamespace + "/velocity_I_gain", velocityIGain);
201 
202  robot_hwnh.getParam(currentDxlNamespace + "/FF1_gain", FF1Gain);
203  robot_hwnh.getParam(currentDxlNamespace + "/FF2_gain", FF2Gain);
204 
205  robot_hwnh.getParam(currentDxlNamespace + "/velocity_profile", velocityProfile);
206  robot_hwnh.getParam(currentDxlNamespace + "/acceleration_profile", accelerationProfile);
207 
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);
211 
212  dxlState->setOffsetPosition(offsetPos);
213  dxlState->setDirection(static_cast<int8_t>(direction));
214 
215  dxlState->setPositionPGain(static_cast<uint32_t>(positionPGain));
216  dxlState->setPositionIGain(static_cast<uint32_t>(positionIGain));
217  dxlState->setPositionDGain(static_cast<uint32_t>(positionDGain));
218 
219  dxlState->setVelocityPGain(static_cast<uint32_t>(velocityPGain));
220  dxlState->setVelocityIGain(static_cast<uint32_t>(velocityIGain));
221 
222  dxlState->setFF1Gain(static_cast<uint32_t>(FF1Gain));
223  dxlState->setFF2Gain(static_cast<uint32_t>(FF2Gain));
224 
225  dxlState->setVelProfile(static_cast<uint32_t>(velocityProfile));
226  dxlState->setAccProfile(static_cast<uint32_t>(accelerationProfile));
227 
228  dxlState->setLimitPositionMin(limit_position_min);
229  dxlState->setLimitPositionMax(limit_position_max);
230 
231  dxlState->setHomePosition(home_position);
232 
233  if (eBusProto == EBusProtocol::TTL)
234  ttl_interface->addJoint(dxlState);
235 
236  currentIdDxl++;
237  }
238  }
239  } // end for (size_t j = 0; j < nb_joints; j++)
240 }
241 
246 void addJointToTtlManager(const std::shared_ptr<ttl_driver::TtlManager> &ttl_drv)
247 {
248  size_t nb_joints = 0;
249 
250  ros::NodeHandle robot_hwnh("joints_interface");
251  // retrieve nb joints with checking that the config param exists for both name and id
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"))
254  nb_joints++;
255 
256  // connect and register joint state interface
257  int currentIdStepper = 1;
258  int currentIdDxl = 1;
259 
260  for (size_t j = 0; j < nb_joints; j++)
261  {
262  int joint_id_config = 0;
263  string joint_name;
264  string joint_type;
265  string joint_bus;
266 
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);
271 
272  HardwareTypeEnum eType = HardwareTypeEnum(joint_type.c_str());
273  BusProtocolEnum eBusProto = BusProtocolEnum(joint_bus.c_str());
274 
275  if (eType == EHardwareType::STEPPER || eType == EHardwareType::FAKE_STEPPER_MOTOR)
276  { // stepper
277  std::string currentStepperNamespace = "steppers/stepper_" + to_string(currentIdStepper);
278 
279  auto stepperState = std::make_shared<StepperMotorState>(joint_name, eType, common::model::EComponentType::JOINT, eBusProto, static_cast<uint8_t>(joint_id_config));
280  if (stepperState)
281  {
282  double offsetPos = 0.0;
283  double gear_ratio = 1.0;
284  int direction = 1;
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;
290 
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);
299 
300  // acceleration and velocity profiles
301  common::model::VelocityProfile profile{};
302  int data{};
303  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_start"))
304  {
305  robot_hwnh.getParam(currentStepperNamespace + "/v_start", data);
306  profile.v_start = static_cast<uint32_t>(data);
307  }
308 
309  if (robot_hwnh.hasParam(currentStepperNamespace + "/a_1"))
310  {
311  robot_hwnh.getParam(currentStepperNamespace + "/a_1", data);
312  profile.a_1 = static_cast<uint32_t>(data);
313  }
314  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_1"))
315  {
316  robot_hwnh.getParam(currentStepperNamespace + "/v_1", data);
317  profile.v_1 = static_cast<uint32_t>(data);
318  }
319  if (robot_hwnh.hasParam(currentStepperNamespace + "/a_max"))
320  {
321  robot_hwnh.getParam(currentStepperNamespace + "/a_max", data);
322  profile.a_max = static_cast<uint32_t>(data);
323  }
324  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_max"))
325  {
326  robot_hwnh.getParam(currentStepperNamespace + "/v_max", data);
327  profile.v_max = static_cast<uint32_t>(data);
328  }
329  if (robot_hwnh.hasParam(currentStepperNamespace + "/d_max"))
330  {
331  robot_hwnh.getParam(currentStepperNamespace + "/d_max", data);
332  profile.d_max = static_cast<uint32_t>(data);
333  }
334  if (robot_hwnh.hasParam(currentStepperNamespace + "/d_1"))
335  {
336  robot_hwnh.getParam(currentStepperNamespace + "/d_1", data);
337  profile.d_1 = static_cast<uint32_t>(data);
338  }
339  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_stop"))
340  {
341  robot_hwnh.getParam(currentStepperNamespace + "/v_stop", data);
342  profile.v_stop = static_cast<uint32_t>(data);
343  }
344 
345  // add parameters
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);
355 
356  // update ratio used to convert rad to pos motor
357  stepperState->updateMultiplierRatio();
358 
359  if (eBusProto == EBusProtocol::TTL)
360  {
361  ttl_drv->addHardwareComponent(stepperState);
362  }
363  currentIdStepper++;
364  }
365  }
366  else if (eType != EHardwareType::UNKNOWN)
367  { // dynamixel
368  auto dxlState = std::make_shared<DxlMotorState>(joint_name, eType, common::model::EComponentType::JOINT, static_cast<uint8_t>(joint_id_config));
369  if (dxlState)
370  {
371  double offsetPos = 0.0;
372  int direction = 1;
373  int positionPGain = 0;
374  int positionIGain = 0;
375  int positionDGain = 0;
376  int velocityPGain = 0;
377  int velocityIGain = 0;
378  int FF1Gain = 0;
379  int FF2Gain = 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;
385 
386  std::string currentDxlNamespace = "dynamixels/dxl_" + to_string(currentIdDxl);
387 
388  robot_hwnh.getParam(currentDxlNamespace + "/offset_position", offsetPos);
389  robot_hwnh.getParam(currentDxlNamespace + "/direction", direction);
390 
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);
394 
395  robot_hwnh.getParam(currentDxlNamespace + "/velocity_P_gain", velocityPGain);
396  robot_hwnh.getParam(currentDxlNamespace + "/velocity_I_gain", velocityIGain);
397 
398  robot_hwnh.getParam(currentDxlNamespace + "/FF1_gain", FF1Gain);
399  robot_hwnh.getParam(currentDxlNamespace + "/FF2_gain", FF2Gain);
400 
401  robot_hwnh.getParam(currentDxlNamespace + "/velocity_profile", velocityProfile);
402  robot_hwnh.getParam(currentDxlNamespace + "/acceleration_profile", accelerationProfile);
403 
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);
407 
408  dxlState->setOffsetPosition(offsetPos);
409  dxlState->setDirection(static_cast<int8_t>(direction));
410 
411  dxlState->setPositionPGain(static_cast<uint32_t>(positionPGain));
412  dxlState->setPositionIGain(static_cast<uint32_t>(positionIGain));
413  dxlState->setPositionDGain(static_cast<uint32_t>(positionDGain));
414 
415  dxlState->setVelocityPGain(static_cast<uint32_t>(velocityPGain));
416  dxlState->setVelocityIGain(static_cast<uint32_t>(velocityIGain));
417 
418  dxlState->setFF1Gain(static_cast<uint32_t>(FF1Gain));
419  dxlState->setFF2Gain(static_cast<uint32_t>(FF2Gain));
420 
421  dxlState->setVelProfile(static_cast<uint32_t>(velocityProfile));
422  dxlState->setAccProfile(static_cast<uint32_t>(accelerationProfile));
423 
424  dxlState->setLimitPositionMin(limit_position_min);
425  dxlState->setLimitPositionMax(limit_position_max);
426 
427  dxlState->setHomePosition(home_position);
428 
429  if (eBusProto == EBusProtocol::TTL)
430  {
431  ttl_drv->addHardwareComponent(dxlState);
432  }
433  currentIdDxl++;
434  }
435  }
436  } // end for (size_t j = 0; j < nb_joints; j++)
437 }
438 
439 // Declare a test
440 /******************************************************/
441 /************ Tests of ttl interface ******************/
442 /******************************************************/
446 class TtlInterfaceTestSuite : public ::testing::Test
447 {
448  protected:
449  static void SetUpTestCase()
450  {
451  ros::NodeHandle nh("ttl_driver");
452  ros::Duration(5.0).sleep();
453 
454  ttl_interface = std::make_shared<ttl_driver::TtlInterfaceCore>(nh);
455 
457  // check connections
458  EXPECT_TRUE(ttl_interface->isConnectionOk());
459  EXPECT_TRUE(ttl_interface->scanMotorId(2));
460  EXPECT_TRUE(ttl_interface->scanMotorId(3));
461  EXPECT_TRUE(ttl_interface->scanMotorId(4));
462  EXPECT_TRUE(ttl_interface->scanMotorId(5));
463  EXPECT_TRUE(ttl_interface->scanMotorId(6));
464  EXPECT_TRUE(ttl_interface->scanMotorId(7));
465  }
466 
467  static void TearDownTestCase() { ros::shutdown(); }
468 
469  static std::shared_ptr<ttl_driver::TtlInterfaceCore> ttl_interface;
470 };
471 
472 std::shared_ptr<ttl_driver::TtlInterfaceCore> TtlInterfaceTestSuite::ttl_interface;
473 
474 // Test reboot motors
475 TEST_F(TtlInterfaceTestSuite, testRebootMotors)
476 {
477  int resutl = ttl_interface->rebootHardware(ttl_interface->getJointState(4));
478  EXPECT_EQ(resutl, static_cast<int>(niryo_robot_msgs::CommandStatus::SUCCESS));
479 }
480 
481 // Test reboot motor with wrong id
482 TEST_F(TtlInterfaceTestSuite, testRebootMotorsWrongID)
483 {
484  bool result;
485  result = ttl_interface->rebootHardware(std::make_shared<common::model::StepperMotorState>());
486  EXPECT_FALSE(result);
487 }
488 
492 class TtlManagerTestSuite : public ::testing::Test
493 {
494  protected:
495  static void SetUpTestCase()
496  {
497  ros::NodeHandle nh("ttl_driver");
498  ros::NodeHandle nh_private("~");
499 
500  ttl_drv = std::make_shared<ttl_driver::TtlManager>(nh);
501 
503  // check connections
504  EXPECT_TRUE(ttl_drv->ping(2));
505  EXPECT_TRUE(ttl_drv->ping(3));
506  EXPECT_TRUE(ttl_drv->ping(4));
507  EXPECT_TRUE(ttl_drv->ping(5));
508  EXPECT_TRUE(ttl_drv->ping(6));
509  EXPECT_TRUE(ttl_drv->ping(7));
510 
511  if (ttl_drv->getCalibrationStatus() != common::model::EStepperCalibrationStatus::OK)
512  {
513  ASSERT_TRUE(startCalibration());
514  }
515 
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));
522  }
523  static bool startCalibration()
524  {
525  // need reset calibration to get calibration status after the calibration
526  ttl_drv->resetCalibration();
527  ttl_drv->startCalibration();
528 
529  auto state_motor_3 = std::dynamic_pointer_cast<common::model::JointState>(ttl_drv->getHardwareState(3));
530  auto steps = static_cast<uint32_t>(state_motor_3->getPosition() + 10 * state_motor_3->getDirection());
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);
534 
535  // Move All Dynamixel to Home Position
536  // set torque on
537  common::model::DxlSyncCmd dynamixel_cmd(common::model::EDxlCommandType::CMD_TYPE_POSITION);
538 
539  for (auto jState : ttl_drv->getMotorsStates())
540  {
541  if (jState && jState->isDynamixel())
542  {
543  dynamixel_cmd.addMotorParam(jState->getHardwareType(), jState->getId(), static_cast<uint32_t>(jState->to_motor_pos(jState->getHomePosition())));
544  }
545  }
546 
547  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::make_unique<common::model::DxlSyncCmd>(dynamixel_cmd)), COMM_SUCCESS);
548 
549  // for stepper TTL 0 is decreasing direction
550  // send config before calibrate
551  for (uint8_t id = 2; id < 5; id++)
552  {
553  uint8_t direction{0};
554  if (id == 3)
555  direction = 1;
556  uint8_t stall_threshold{6};
557 
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}))),
560  COMM_SUCCESS);
561  EXPECT_EQ(ttl_drv->writeSingleCommand(
562  std::make_unique<common::model::StepperTtlSingleCmd>(common::model::StepperTtlSingleCmd(common::model::EStepperCommandType::CMD_TYPE_CALIBRATION, id))),
563  COMM_SUCCESS);
564  }
565 
566  // wait calibration finish
567  double timeout = 0.0;
568  while (ttl_drv->getCalibrationStatus() != common::model::EStepperCalibrationStatus::OK)
569  {
570  if (timeout <= 30.0)
571  {
572  timeout += 0.5;
573  ros::Duration(0.5).sleep();
574  ttl_drv->readSteppersStatus();
575  }
576  else
577  return false;
578  }
579  return true;
580  }
581 
582  static std::shared_ptr<ttl_driver::TtlManager> ttl_drv;
583  static std::shared_ptr<common::model::JointState> state_motor_2;
584  static std::shared_ptr<common::model::JointState> state_motor_3;
585  static std::shared_ptr<common::model::JointState> state_motor_4;
586  static std::shared_ptr<common::model::JointState> state_motor_5;
587  static std::shared_ptr<common::model::JointState> state_motor_6;
588  static std::shared_ptr<common::model::JointState> state_motor_7;
589 };
590 
591 std::shared_ptr<ttl_driver::TtlManager> TtlManagerTestSuite::ttl_drv;
592 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_2;
593 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_3;
594 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_4;
595 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_5;
596 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_6;
597 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_7;
598 
599 /******************************************************/
600 /************** Tests of ttl manager ******************/
601 /******************************************************/
602 
603 TEST_F(TtlManagerTestSuite, initializeJoints)
604 {
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);
611 }
612 
613 TEST_F(TtlManagerTestSuite, calibrationStatus) { ASSERT_EQ(ttl_drv->getCalibrationStatus(), common::model::EStepperCalibrationStatus::OK); }
614 // Test driver received cmd
615 
616 TEST_F(TtlManagerTestSuite, testSingleCmds)
617 {
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();
621 
622  // wrong id
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();
626 
627  // wrong type cmd
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();
631 
632  // wrong type of cmd object
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);
635 }
636 
637 // Test control cmds
638 TEST_F(TtlManagerTestSuite, testSingleControlCmds)
639 {
640  auto cmd_1_torque = std::make_unique<common::model::StepperTtlSingleCmd>(common::model::EStepperCommandType::CMD_TYPE_TORQUE, 2, std::initializer_list<uint32_t>{1});
641 
642  EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
643  ros::Duration(0.01).sleep();
644 
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();
648 
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();
652 
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();
656 
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();
660 
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();
664 
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()));
671 
672  // single control cmd for stepper ttl id 2
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();
676 
677  // single control cmd for stepper ttl id 3
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();
681 
682  // single control cmd for stepper ttl id 4
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();
686 
687  // single control cmd for dxl ttl id 5
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();
691 
692  // single control cmd for dxl ttl id 6
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();
696 
697  // single control cmd for dxl ttl id 7
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();
701 
702  ttl_drv->readJointsStatus();
703 
704  // can miss 1 2 steps
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);
711 }
712 
714 {
715  // sync cmd
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);
719 
720  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_1)), COMM_SUCCESS);
721  ros::Duration(0.1).sleep();
722 
723  // redondant id
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);
727 
728  EXPECT_NE(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_3)), COMM_SUCCESS);
729 
730  // wrong cmd type
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);
734 
735  EXPECT_NE(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_4)), COMM_SUCCESS);
736 }
737 
738 TEST_F(TtlManagerTestSuite, testSyncControlCmds)
739 {
740  // sync cmd
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);
745 
746  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
747  ros::Duration(0.01).sleep();
748 
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);
753 
754  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
755  ros::Duration(0.01).sleep();
756 
757  ttl_drv->readJointsStatus();
758 
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));
765 
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);
770 
771  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1)), COMM_SUCCESS);
772  ros::Duration(0.2).sleep();
773 
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);
778 
779  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2)), COMM_SUCCESS);
780  ros::Duration(4.0).sleep();
781 
782  ttl_drv->readJointsStatus();
783 
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);
790 }
791 
792 TEST_F(TtlManagerTestSuite, testSyncControlCmdsReturnHome)
793 {
794  // sync cmd
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);
799 
800  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
801  ros::Duration(0.01).sleep();
802 
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);
807 
808  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
809  ros::Duration(0.01).sleep();
810 
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()));
817 
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);
822 
823  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1)), COMM_SUCCESS);
824  ros::Duration(0.2).sleep();
825 
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);
830 
831  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2)), COMM_SUCCESS);
832  ros::Duration(4.0).sleep();
833 
834  ttl_drv->readJointsStatus();
835 
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);
842 }
843 
844 // Test driver scan motors
845 TEST_F(TtlManagerTestSuite, scanTest) { EXPECT_EQ(ttl_drv->scanAndCheck(), COMM_SUCCESS); }
846 
847 // Run all the tests that were declared with TEST()
848 int main(int argc, char **argv)
849 {
850  testing::InitGoogleTest(&argc, argv);
851  ros::init(argc, argv, "ttl_driver_unit_tests");
852  ros::start();
853 
854  std::string hardware_version;
855 
856  return RUN_ALL_TESTS();
857 }
main
int main(int argc, char **argv)
Definition: unit_tests_ned2.cpp:848
TtlManagerTestSuite
The TtlManagerTestSuite class.
Definition: unit_tests_ned2.cpp:492
ttl_interface_core.hpp
TtlInterfaceTestSuite
The TtlInterfaceTestSuite class.
Definition: unit_tests_ned2.cpp:446
addJointToTtlInterface
void addJointToTtlInterface(const std::shared_ptr< ttl_driver::TtlInterfaceCore > &ttl_interface)
addJointToTtlInterface
Definition: unit_tests_ned2.cpp:54
TtlManagerTestSuite::state_motor_7
static std::shared_ptr< common::model::JointState > state_motor_7
Definition: unit_tests_ned2.cpp:588
TtlManagerTestSuite::state_motor_4
static std::shared_ptr< common::model::JointState > state_motor_4
Definition: unit_tests_ned2.cpp:585
TtlInterfaceTestSuite::ttl_interface
static std::shared_ptr< ttl_driver::TtlInterfaceCore > ttl_interface
Definition: unit_tests_ned2.cpp:469
TtlInterfaceTestSuite::SetUpTestCase
static void SetUpTestCase()
Definition: unit_tests_ned2.cpp:449
TtlManagerTestSuite::SetUpTestCase
static void SetUpTestCase()
Definition: unit_tests_ned2.cpp:495
TtlManagerTestSuite::state_motor_2
static std::shared_ptr< common::model::JointState > state_motor_2
Definition: unit_tests_ned2.cpp:583
TtlManagerTestSuite::state_motor_5
static std::shared_ptr< common::model::JointState > state_motor_5
Definition: unit_tests_ned2.cpp:586
TtlInterfaceTestSuite::TearDownTestCase
static void TearDownTestCase()
Definition: unit_tests_ned2.cpp:467
TtlManagerTestSuite::state_motor_3
static std::shared_ptr< common::model::JointState > state_motor_3
Definition: unit_tests_ned2.cpp:584
TtlManagerTestSuite::state_motor_6
static std::shared_ptr< common::model::JointState > state_motor_6
Definition: unit_tests_ned2.cpp:587
nh
static std::unique_ptr< ros::NodeHandle > nh
Definition: service_client_ned2.cpp:31
addJointToTtlManager
void addJointToTtlManager(const std::shared_ptr< ttl_driver::TtlManager > &ttl_drv)
addJointToTtlManager
Definition: unit_tests_ned2.cpp:246
TtlManagerTestSuite::ttl_drv
static std::shared_ptr< ttl_driver::TtlManager > ttl_drv
Definition: unit_tests_ned2.cpp:582
TtlManagerTestSuite::startCalibration
static bool startCalibration()
Definition: unit_tests_ned2.cpp:523
TEST_F
TEST_F(TtlInterfaceTestSuite, testRebootMotors)
Definition: unit_tests_ned2.cpp:475
ttl_manager.hpp


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Wed May 21 2025 08:30:14