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") &&
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"))
64  nb_joints++;
65 
66  // connect and register joint state interface
67 
68  int currentIdDxl = 1;
69  int currentIdStepper = 1;
70 
71  for (size_t j = 0; j < nb_joints; j++)
72  {
73  int joint_id_config = 0;
74  string joint_name;
75  string joint_type;
76  string joint_bus;
77 
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());
84 
85  if (eType == EHardwareType::STEPPER || eType == EHardwareType::FAKE_STEPPER_MOTOR)
86  { // stepper
87  std::string currentStepperNamespace = "steppers/stepper_" + to_string(currentIdStepper);
88 
89  auto stepperState = std::make_shared<StepperMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
90  eBusProto, static_cast<uint8_t>(joint_id_config));
91  if (stepperState)
92  {
93  double offsetPos = 0.0;
94  double gear_ratio = 1.0;
95  int direction = 1;
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;
101 
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);
110 
111  // acceleration and velocity profiles
112  common::model::VelocityProfile profile{};
113  int data{};
114  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_start"))
115  {
116  robot_hwnh.getParam(currentStepperNamespace + "/v_start", data);
117  profile.v_start = static_cast<uint32_t>(data);
118  }
119 
120  if (robot_hwnh.hasParam(currentStepperNamespace + "/a_1"))
121  {
122  robot_hwnh.getParam(currentStepperNamespace + "/a_1", data);
123  profile.a_1 = static_cast<uint32_t>(data);
124  }
125  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_1"))
126  {
127  robot_hwnh.getParam(currentStepperNamespace + "/v_1", data);
128  profile.v_1 = static_cast<uint32_t>(data);
129  }
130  if (robot_hwnh.hasParam(currentStepperNamespace + "/a_max"))
131  {
132  robot_hwnh.getParam(currentStepperNamespace + "/a_max", data);
133  profile.a_max = static_cast<uint32_t>(data);
134  }
135  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_max"))
136  {
137  robot_hwnh.getParam(currentStepperNamespace + "/v_max", data);
138  profile.v_max = static_cast<uint32_t>(data);
139  }
140  if (robot_hwnh.hasParam(currentStepperNamespace + "/d_max"))
141  {
142  robot_hwnh.getParam(currentStepperNamespace + "/d_max", data);
143  profile.d_max = static_cast<uint32_t>(data);
144  }
145  if (robot_hwnh.hasParam(currentStepperNamespace + "/d_1"))
146  {
147  robot_hwnh.getParam(currentStepperNamespace + "/d_1", data);
148  profile.d_1 = static_cast<uint32_t>(data);
149  }
150  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_stop"))
151  {
152  robot_hwnh.getParam(currentStepperNamespace + "/v_stop", data);
153  profile.v_stop = static_cast<uint32_t>(data);
154  }
155 
156  // add parameters
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);
166 
167  if (eBusProto == EBusProtocol::TTL)
168  ttl_interface->addJoint(stepperState);
169 
170  currentIdStepper++;
171  }
172  }
173  else if (eType != EHardwareType::UNKNOWN)
174  { // dynamixel
175  auto dxlState = std::make_shared<DxlMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
176  static_cast<uint8_t>(joint_id_config));
177  if (dxlState)
178  {
179  double offsetPos = 0.0;
180  int direction = 1;
181  int positionPGain = 0;
182  int positionIGain = 0;
183  int positionDGain = 0;
184  int velocityPGain = 0;
185  int velocityIGain = 0;
186  int FF1Gain = 0;
187  int FF2Gain = 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;
193 
194  std::string currentDxlNamespace = "dynamixels/dxl_" + to_string(currentIdDxl);
195 
196  robot_hwnh.getParam(currentDxlNamespace + "/offset_position", offsetPos);
197  robot_hwnh.getParam(currentDxlNamespace + "/direction", direction);
198 
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);
202 
203  robot_hwnh.getParam(currentDxlNamespace + "/velocity_P_gain", velocityPGain);
204  robot_hwnh.getParam(currentDxlNamespace + "/velocity_I_gain", velocityIGain);
205 
206  robot_hwnh.getParam(currentDxlNamespace + "/FF1_gain", FF1Gain);
207  robot_hwnh.getParam(currentDxlNamespace + "/FF2_gain", FF2Gain);
208 
209  robot_hwnh.getParam(currentDxlNamespace + "/velocity_profile", velocityProfile);
210  robot_hwnh.getParam(currentDxlNamespace + "/acceleration_profile", accelerationProfile);
211 
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);
215 
216  dxlState->setOffsetPosition(offsetPos);
217  dxlState->setDirection(static_cast<int8_t>(direction));
218 
219  dxlState->setPositionPGain(static_cast<uint32_t>(positionPGain));
220  dxlState->setPositionIGain(static_cast<uint32_t>(positionIGain));
221  dxlState->setPositionDGain(static_cast<uint32_t>(positionDGain));
222 
223  dxlState->setVelocityPGain(static_cast<uint32_t>(velocityPGain));
224  dxlState->setVelocityIGain(static_cast<uint32_t>(velocityIGain));
225 
226  dxlState->setFF1Gain(static_cast<uint32_t>(FF1Gain));
227  dxlState->setFF2Gain(static_cast<uint32_t>(FF2Gain));
228 
229  dxlState->setVelProfile(static_cast<uint32_t>(velocityProfile));
230  dxlState->setAccProfile(static_cast<uint32_t>(accelerationProfile));
231 
232  dxlState->setLimitPositionMin(limit_position_min);
233  dxlState->setLimitPositionMax(limit_position_max);
234 
235  dxlState->setHomePosition(home_position);
236 
237  if (eBusProto == EBusProtocol::TTL)
238  ttl_interface->addJoint(dxlState);
239 
240  currentIdDxl++;
241  }
242  }
243  } // end for (size_t j = 0; j < nb_joints; j++)
244 }
245 
250 void addJointToTtlManager(const std::shared_ptr<ttl_driver::TtlManager> &ttl_drv)
251 {
252  size_t nb_joints = 0;
253 
254  ros::NodeHandle robot_hwnh("joints_interface");
255  // retrieve nb joints with checking that the config param exists for both name and id
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"))
260  nb_joints++;
261 
262  // connect and register joint state interface
263  int currentIdStepper = 1;
264  int currentIdDxl = 1;
265 
266  for (size_t j = 0; j < nb_joints; j++)
267  {
268  int joint_id_config = 0;
269  string joint_name;
270  string joint_type;
271  string joint_bus;
272 
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);
277 
278  HardwareTypeEnum eType = HardwareTypeEnum(joint_type.c_str());
279  BusProtocolEnum eBusProto = BusProtocolEnum(joint_bus.c_str());
280 
281  if (eType == EHardwareType::STEPPER || eType == EHardwareType::FAKE_STEPPER_MOTOR)
282  { // stepper
283  std::string currentStepperNamespace = "steppers/stepper_" + to_string(currentIdStepper);
284 
285  auto stepperState = std::make_shared<StepperMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
286  eBusProto, static_cast<uint8_t>(joint_id_config));
287  if (stepperState)
288  {
289  double offsetPos = 0.0;
290  double gear_ratio = 1.0;
291  int direction = 1;
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;
297 
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);
306 
307  // acceleration and velocity profiles
308  common::model::VelocityProfile profile{};
309  int data{};
310  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_start"))
311  {
312  robot_hwnh.getParam(currentStepperNamespace + "/v_start", data);
313  profile.v_start = static_cast<uint32_t>(data);
314  }
315 
316  if (robot_hwnh.hasParam(currentStepperNamespace + "/a_1"))
317  {
318  robot_hwnh.getParam(currentStepperNamespace + "/a_1", data);
319  profile.a_1 = static_cast<uint32_t>(data);
320  }
321  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_1"))
322  {
323  robot_hwnh.getParam(currentStepperNamespace + "/v_1", data);
324  profile.v_1 = static_cast<uint32_t>(data);
325  }
326  if (robot_hwnh.hasParam(currentStepperNamespace + "/a_max"))
327  {
328  robot_hwnh.getParam(currentStepperNamespace + "/a_max", data);
329  profile.a_max = static_cast<uint32_t>(data);
330  }
331  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_max"))
332  {
333  robot_hwnh.getParam(currentStepperNamespace + "/v_max", data);
334  profile.v_max = static_cast<uint32_t>(data);
335  }
336  if (robot_hwnh.hasParam(currentStepperNamespace + "/d_max"))
337  {
338  robot_hwnh.getParam(currentStepperNamespace + "/d_max", data);
339  profile.d_max = static_cast<uint32_t>(data);
340  }
341  if (robot_hwnh.hasParam(currentStepperNamespace + "/d_1"))
342  {
343  robot_hwnh.getParam(currentStepperNamespace + "/d_1", data);
344  profile.d_1 = static_cast<uint32_t>(data);
345  }
346  if (robot_hwnh.hasParam(currentStepperNamespace + "/v_stop"))
347  {
348  robot_hwnh.getParam(currentStepperNamespace + "/v_stop", data);
349  profile.v_stop = static_cast<uint32_t>(data);
350  }
351 
352  // add parameters
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);
362 
363  // update ratio used to convert rad to pos motor
364  stepperState->updateMultiplierRatio();
365 
366  if (eBusProto == EBusProtocol::TTL)
367  {
368  ttl_drv->addHardwareComponent(stepperState);
369  }
370  currentIdStepper++;
371  }
372  }
373  else if (eType != EHardwareType::UNKNOWN)
374  { // dynamixel
375  auto dxlState = std::make_shared<DxlMotorState>(joint_name, eType, common::model::EComponentType::JOINT,
376  static_cast<uint8_t>(joint_id_config));
377  if (dxlState)
378  {
379  double offsetPos = 0.0;
380  int direction = 1;
381  int positionPGain = 0;
382  int positionIGain = 0;
383  int positionDGain = 0;
384  int velocityPGain = 0;
385  int velocityIGain = 0;
386  int FF1Gain = 0;
387  int FF2Gain = 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;
393 
394  std::string currentDxlNamespace = "dynamixels/dxl_" + to_string(currentIdDxl);
395 
396  robot_hwnh.getParam(currentDxlNamespace + "/offset_position", offsetPos);
397  robot_hwnh.getParam(currentDxlNamespace + "/direction", direction);
398 
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);
402 
403  robot_hwnh.getParam(currentDxlNamespace + "/velocity_P_gain", velocityPGain);
404  robot_hwnh.getParam(currentDxlNamespace + "/velocity_I_gain", velocityIGain);
405 
406  robot_hwnh.getParam(currentDxlNamespace + "/FF1_gain", FF1Gain);
407  robot_hwnh.getParam(currentDxlNamespace + "/FF2_gain", FF2Gain);
408 
409  robot_hwnh.getParam(currentDxlNamespace + "/velocity_profile", velocityProfile);
410  robot_hwnh.getParam(currentDxlNamespace + "/acceleration_profile", accelerationProfile);
411 
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);
415 
416  dxlState->setOffsetPosition(offsetPos);
417  dxlState->setDirection(static_cast<int8_t>(direction));
418 
419  dxlState->setPositionPGain(static_cast<uint32_t>(positionPGain));
420  dxlState->setPositionIGain(static_cast<uint32_t>(positionIGain));
421  dxlState->setPositionDGain(static_cast<uint32_t>(positionDGain));
422 
423  dxlState->setVelocityPGain(static_cast<uint32_t>(velocityPGain));
424  dxlState->setVelocityIGain(static_cast<uint32_t>(velocityIGain));
425 
426  dxlState->setFF1Gain(static_cast<uint32_t>(FF1Gain));
427  dxlState->setFF2Gain(static_cast<uint32_t>(FF2Gain));
428 
429  dxlState->setVelProfile(static_cast<uint32_t>(velocityProfile));
430  dxlState->setAccProfile(static_cast<uint32_t>(accelerationProfile));
431 
432  dxlState->setLimitPositionMin(limit_position_min);
433  dxlState->setLimitPositionMax(limit_position_max);
434 
435  dxlState->setHomePosition(home_position);
436 
437  if (eBusProto == EBusProtocol::TTL)
438  {
439  ttl_drv->addHardwareComponent(dxlState);
440  }
441  currentIdDxl++;
442  }
443  }
444  } // end for (size_t j = 0; j < nb_joints; j++)
445 }
446 
447 // Declare a test
448 /******************************************************/
449 /************ Tests of ttl interface ******************/
450 /******************************************************/
454 class TtlInterfaceTestSuite : public ::testing::Test
455 {
456 protected:
457  static void SetUpTestCase()
458  {
459  ros::NodeHandle nh("ttl_driver");
460  ros::Duration(5.0).sleep();
461 
462  ttl_interface = std::make_shared<ttl_driver::TtlInterfaceCore>(nh);
463 
465  // check connections
466  EXPECT_TRUE(ttl_interface->isConnectionOk());
467  EXPECT_TRUE(ttl_interface->scanMotorId(2));
468  EXPECT_TRUE(ttl_interface->scanMotorId(3));
469  EXPECT_TRUE(ttl_interface->scanMotorId(4));
470  EXPECT_TRUE(ttl_interface->scanMotorId(5));
471  EXPECT_TRUE(ttl_interface->scanMotorId(6));
472  EXPECT_TRUE(ttl_interface->scanMotorId(7));
473  }
474 
475  static void TearDownTestCase()
476  {
477  ros::shutdown();
478  }
479 
480  static std::shared_ptr<ttl_driver::TtlInterfaceCore> ttl_interface;
481 };
482 
483 std::shared_ptr<ttl_driver::TtlInterfaceCore> TtlInterfaceTestSuite::ttl_interface;
484 
485 // Test reboot motors
486 TEST_F(TtlInterfaceTestSuite, testRebootMotors)
487 {
488  int resutl = ttl_interface->rebootHardware(ttl_interface->getJointState(4));
489  EXPECT_EQ(resutl, static_cast<int>(niryo_robot_msgs::CommandStatus::SUCCESS));
490 }
491 
492 // Test reboot motor with wrong id
493 TEST_F(TtlInterfaceTestSuite, testRebootMotorsWrongID)
494 {
495  bool result;
496  result = ttl_interface->rebootHardware(std::make_shared<common::model::StepperMotorState>());
497  EXPECT_FALSE(result);
498 }
499 
503 class TtlManagerTestSuite : public ::testing::Test
504 {
505 protected:
506  static void SetUpTestCase()
507  {
508  ros::NodeHandle nh("ttl_driver");
509  ros::NodeHandle nh_private("~");
510 
511  ttl_drv = std::make_shared<ttl_driver::TtlManager>(nh);
512 
514  // check connections
515  EXPECT_TRUE(ttl_drv->ping(2));
516  EXPECT_TRUE(ttl_drv->ping(3));
517  EXPECT_TRUE(ttl_drv->ping(4));
518  EXPECT_TRUE(ttl_drv->ping(5));
519  EXPECT_TRUE(ttl_drv->ping(6));
520  EXPECT_TRUE(ttl_drv->ping(7));
521 
522  if (ttl_drv->getCalibrationStatus() != common::model::EStepperCalibrationStatus::OK)
523  {
524  ASSERT_TRUE(startCalibration());
525  }
526 
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));
533  }
534  static bool startCalibration()
535  {
536  // need reset calibration to get calibration status after the calibration
537  ttl_drv->resetCalibration();
538  ttl_drv->startCalibration();
539 
540  auto state_motor_3 = std::dynamic_pointer_cast<common::model::JointState>(ttl_drv->getHardwareState(3));
541  auto steps = static_cast<uint32_t>(state_motor_3->getPosition() + 10 * state_motor_3->getDirection());
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);
545 
546  // Move All Dynamixel to Home Position
547  // set torque on
548  common::model::DxlSyncCmd dynamixel_cmd(common::model::EDxlCommandType::CMD_TYPE_POSITION);
549 
550  for (auto jState : ttl_drv->getMotorsStates())
551  {
552  if (jState && jState->isDynamixel())
553  {
554  dynamixel_cmd.addMotorParam(jState->getHardwareType(), jState->getId(),
555  static_cast<uint32_t>(jState->to_motor_pos(jState->getHomePosition())));
556  }
557  }
558 
559  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::make_unique<common::model::DxlSyncCmd>(dynamixel_cmd)),
560  COMM_SUCCESS);
561 
562  // for stepper TTL 0 is decreasing direction
563  // send config before calibrate
564  for (uint8_t id = 2; id < 5; id++)
565  {
566  uint8_t direction{ 0 };
567  if (id == 3)
568  direction = 1;
569  uint8_t stall_threshold{ 6 };
570 
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 }))),
574  COMM_SUCCESS);
575  EXPECT_EQ(ttl_drv->writeSingleCommand(std::make_unique<common::model::StepperTtlSingleCmd>(
576  common::model::StepperTtlSingleCmd(common::model::EStepperCommandType::CMD_TYPE_CALIBRATION, id))),
577  COMM_SUCCESS);
578  }
579 
580  // wait calibration finish
581  double timeout = 0.0;
582  while (ttl_drv->getCalibrationStatus() != common::model::EStepperCalibrationStatus::OK)
583  {
584  if (timeout <= 30.0)
585  {
586  timeout += 0.5;
587  ros::Duration(0.5).sleep();
588  ttl_drv->readSteppersStatus();
589  }
590  else
591  return false;
592  }
593  return true;
594  }
595 
596  static std::shared_ptr<ttl_driver::TtlManager> ttl_drv;
597  static std::shared_ptr<common::model::JointState> state_motor_2;
598  static std::shared_ptr<common::model::JointState> state_motor_3;
599  static std::shared_ptr<common::model::JointState> state_motor_4;
600  static std::shared_ptr<common::model::JointState> state_motor_5;
601  static std::shared_ptr<common::model::JointState> state_motor_6;
602  static std::shared_ptr<common::model::JointState> state_motor_7;
603 };
604 
605 std::shared_ptr<ttl_driver::TtlManager> TtlManagerTestSuite::ttl_drv;
606 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_2;
607 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_3;
608 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_4;
609 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_5;
610 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_6;
611 std::shared_ptr<common::model::JointState> TtlManagerTestSuite::state_motor_7;
612 
613 /******************************************************/
614 /************** Tests of ttl manager ******************/
615 /******************************************************/
616 
617 TEST_F(TtlManagerTestSuite, initializeJoints)
618 {
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);
625 }
626 
627 TEST_F(TtlManagerTestSuite, calibrationStatus)
628 {
629  ASSERT_EQ(ttl_drv->getCalibrationStatus(), common::model::EStepperCalibrationStatus::OK);
630 }
631 // Test driver received cmd
632 
633 TEST_F(TtlManagerTestSuite, testSingleCmds)
634 {
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();
639 
640  // wrong id
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();
645 
646  // wrong type cmd
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();
651 
652  // wrong type of cmd object
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);
656 }
657 
658 // Test control cmds
659 TEST_F(TtlManagerTestSuite, testSingleControlCmds)
660 {
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 });
663 
664  EXPECT_EQ(ttl_drv->writeSingleCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
665  ros::Duration(0.01).sleep();
666 
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();
671 
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();
676 
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();
681 
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();
686 
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();
691 
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()));
698 
699  // single control cmd for stepper ttl id 2
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();
704 
705  // single control cmd for stepper ttl id 3
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();
710 
711  // single control cmd for stepper ttl id 4
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();
716 
717  // single control cmd for dxl ttl id 5
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();
722 
723  // single control cmd for dxl ttl id 6
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();
728 
729  // single control cmd for dxl ttl id 7
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();
734 
735  ttl_drv->readJointsStatus();
736 
737  // can miss 1 2 steps
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);
744 }
745 
747 {
748  // sync cmd
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);
752 
753  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_1)), COMM_SUCCESS);
754  ros::Duration(0.1).sleep();
755 
756  // redondant id
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);
760 
761  EXPECT_NE(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_3)), COMM_SUCCESS);
762 
763  // wrong cmd type
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);
767 
768  EXPECT_NE(ttl_drv->writeSynchronizeCommand(std::move(dynamixel_cmd_4)), COMM_SUCCESS);
769 }
770 
771 TEST_F(TtlManagerTestSuite, testSyncControlCmds)
772 {
773  // sync cmd
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);
778 
779  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
780  ros::Duration(0.01).sleep();
781 
782  auto cmd_2_torque =
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);
787 
788  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
789  ros::Duration(0.01).sleep();
790 
791  ttl_drv->readJointsStatus();
792 
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));
799 
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);
804 
805  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1)), COMM_SUCCESS);
806  ros::Duration(0.2).sleep();
807 
808  auto cmd_2 =
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);
813 
814  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2)), COMM_SUCCESS);
815  ros::Duration(4.0).sleep();
816 
817  ttl_drv->readJointsStatus();
818 
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);
825 }
826 
827 TEST_F(TtlManagerTestSuite, testSyncControlCmdsReturnHome)
828 {
829  // sync cmd
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);
834 
835  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1_torque)), COMM_SUCCESS);
836  ros::Duration(0.01).sleep();
837 
838  auto cmd_2_torque =
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);
843 
844  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2_torque)), COMM_SUCCESS);
845  ros::Duration(0.01).sleep();
846 
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()));
853 
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);
858 
859  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_1)), COMM_SUCCESS);
860  ros::Duration(0.2).sleep();
861 
862  auto cmd_2 =
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);
867 
868  EXPECT_EQ(ttl_drv->writeSynchronizeCommand(std::move(cmd_2)), COMM_SUCCESS);
869  ros::Duration(4.0).sleep();
870 
871  ttl_drv->readJointsStatus();
872 
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);
879 }
880 
881 // Test driver scan motors
883 {
884  EXPECT_EQ(ttl_drv->scanAndCheck(), COMM_SUCCESS);
885 }
886 
887 // Run all the tests that were declared with TEST()
888 int main(int argc, char **argv)
889 {
890  testing::InitGoogleTest(&argc, argv);
891  ros::init(argc, argv, "ttl_driver_unit_tests");
892  ros::start();
893 
894  std::string hardware_version;
895 
896  return RUN_ALL_TESTS();
897 }
main
int main(int argc, char **argv)
Definition: unit_tests_ned2.cpp:888
TtlManagerTestSuite
The TtlManagerTestSuite class.
Definition: unit_tests_ned2.cpp:503
ttl_interface_core.hpp
TtlInterfaceTestSuite
The TtlInterfaceTestSuite class.
Definition: unit_tests_ned2.cpp:454
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:602
TtlManagerTestSuite::state_motor_4
static std::shared_ptr< common::model::JointState > state_motor_4
Definition: unit_tests_ned2.cpp:599
TtlInterfaceTestSuite::ttl_interface
static std::shared_ptr< ttl_driver::TtlInterfaceCore > ttl_interface
Definition: unit_tests_ned2.cpp:480
TtlInterfaceTestSuite::SetUpTestCase
static void SetUpTestCase()
Definition: unit_tests_ned2.cpp:457
TtlManagerTestSuite::SetUpTestCase
static void SetUpTestCase()
Definition: unit_tests_ned2.cpp:506
TtlManagerTestSuite::state_motor_2
static std::shared_ptr< common::model::JointState > state_motor_2
Definition: unit_tests_ned2.cpp:597
TtlManagerTestSuite::state_motor_5
static std::shared_ptr< common::model::JointState > state_motor_5
Definition: unit_tests_ned2.cpp:600
TtlInterfaceTestSuite::TearDownTestCase
static void TearDownTestCase()
Definition: unit_tests_ned2.cpp:475
TtlManagerTestSuite::state_motor_3
static std::shared_ptr< common::model::JointState > state_motor_3
Definition: unit_tests_ned2.cpp:598
TtlManagerTestSuite::state_motor_6
static std::shared_ptr< common::model::JointState > state_motor_6
Definition: unit_tests_ned2.cpp:601
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:250
TtlManagerTestSuite::ttl_drv
static std::shared_ptr< ttl_driver::TtlManager > ttl_drv
Definition: unit_tests_ned2.cpp:596
TtlManagerTestSuite::startCalibration
static bool startCalibration()
Definition: unit_tests_ned2.cpp:534
TEST_F
TEST_F(TtlInterfaceTestSuite, testRebootMotors)
Definition: unit_tests_ned2.cpp:486
ttl_manager.hpp


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Fri Mar 6 2026 15:24:15