test_robot_lib.cpp
Go to the documentation of this file.
1 
27 #include <sr_mechanism_model/simple_transmission.hpp>
28 #include <tinyxml2.h>
29 #include <gtest/gtest.h>
30 #include <ros/ros.h>
31 #include <utility>
32 #include <string>
33 #include <vector>
34 #include <chrono> // NOLINT
35 #include <map>
36 
37 #define error_flag_names palm_0200_edc_error_flag_names
38 #define STATUS_TYPE ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS
39 #define COMMAND_TYPE ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND
40 
42  public shadow_robot::SrMotorHandLib<STATUS_TYPE, COMMAND_TYPE>
43 {
44 public:
45  HandLibTestProtected(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh)
46  : shadow_robot::SrMotorHandLib<STATUS_TYPE, COMMAND_TYPE>(hw, nh, nh, "", "rh_")
47  {
48  };
49 
50 public:
54 };
55 
57 {
59 public:
62  sr_actuator::SrMotorActuator *actuator;
64 
66  {
67  tinyxml2::XMLElement *root;
68  tinyxml2::XMLElement *root_element;
69  tinyxml2::XMLDocument xml;
70  std::string robot_description;
71  if (ros::param::get("/robot_description", robot_description))
72  {
73  xml.Parse(robot_description.c_str());
74  }
75  else
76  {
77  ROS_ERROR_STREAM("Could not load the xml from parameter server");
78  }
79  root_element = xml.RootElement();
80  root = xml.FirstChildElement("robot");
81 
82  nh.getParam("joint_to_sensor_mapping", joint_to_sensor_mapping);
83  hw = new ros_ethercat_model::RobotState(root);
84 
85  hardware_interface::HardwareInterface *ehw = static_cast<hardware_interface::HardwareInterface *>(hw);
86  sr_hand_lib.reset(new HandLibTestProtected(ehw, nh));
87  }
88 
90  {
91  delete hw;
92  }
93 
94  void check_hw_actuator(std::string name, int motor_id, int id_in_enum, double expected_pos)
95  {
96  actuator = static_cast<sr_actuator::SrMotorActuator *>(hw->getActuator(name));
97 
98  EXPECT_EQ(actuator->state_.device_id_, motor_id);
99  // EXPECT_EQ(state.position_ , expected_pos);
100  }
101 };
102 
106 TEST(SrRobotLib, Initialization)
107 {
109 
110 // pr2_hardware_interface::HardwareInterface *hw;
111 // hw = new pr2_hardware_interface::HardwareInterface();
112 // boost::shared_ptr< shadow_robot::SrMotorHandLib<STATUS_TYPE, COMMAND_TYPE> > lib_test =
113 // boost::shared_ptr< shadow_robot::SrMotorHandLib<STATUS_TYPE, COMMAND_TYPE> >(
114 // new shadow_robot::SrMotorHandLib<STATUS_TYPE, COMMAND_TYPE>(hw) );
115 
116  EXPECT_TRUE(true);
117 }
118 
122 TEST(SrRobotLib, ConfigParsing)
123 {
125 
126 std::map<std::string, std::vector<double>> expected_processed_raw_values_coupled =
127  {
128  {
129  "THJ1",
130  {
131  2738, 2301, 2693,
132  2154, 2680, 1978,
133  2677, 1840, 2664,
134  1707, 2334, 2287,
135  2242, 2095, 2230,
136  1953, 2223, 1807,
137  2206, 1685, 1839,
138  2243, 1772, 2112,
139  1764, 1928, 1755,
140  1762, 1683, 1650,
141  1387, 2219, 1375,
142  2056, 1370, 1884,
143  1337, 1741, 1329,
144  1630, 1141, 2206,
145  1132, 2055, 1114,
146  1877, 1103, 1730,
147  1092, 1615, 3779.36,
148  1940.6, 3408.06,
149  3083.35, 2435.98,
150  3789.6, 1234.42,
151  3789.6, 262.344,
152  3083.35, -108.956,
153  1940.6, 262.344,
154  797.854, 1234.42,
155  91.5974, 2435.98,
156  91.5974, 3408.06,
157  797.854
158  }
159  }
160  ,
161  {
162  "THJ2",
163  {
164  2301, 2738, 2154, 2693,
165  1978, 2680, 1840, 2677,
166  1707, 2664, 2287, 2334,
167  2095, 2242, 1953, 2230,
168  1807, 2223, 1685, 2206,
169  2243, 1839, 2112, 1772,
170  1928, 1764, 1762, 1755,
171  1650, 1683, 2219, 1387,
172  2056, 1375, 1884, 1370,
173  1741, 1337, 1630, 1329,
174  2206, 1141, 2055, 1132,
175  1877, 1114, 1730, 1103,
176  1615, 1092, 3884.76,
177  1835.2, 3513.46,
178  2977.95, 2541.38,
179  3684.2, 1339.82,
180  3684.2, 367.744,
181  2977.95, -3.55637,
182  1835.2, 367.744,
183  692.454, 1339.82,
184  -13.8026, 2541.38,
185  -13.8026, 3513.46,
186  692.454
187  }
188  }
189  };
190 
191 std::map<std::string, std::vector<double>> expected_processed_calibrated_values =
192  {
193  {
194  "THJ1",
195  {
196  0, 0, 0, 0, 0,
197  0.3927, 0.3927,
198  0.3927, 0.3927,
199  0.3927, 0.7854,
200  0.7854, 0.7854,
201  0.7854, 0.7854,
202  1.1781, 1.1781,
203  1.1781, 1.1781,
204  1.1781, 1.5708,
205  1.5708, 1.5708,
206  1.5708, 1.5708,
207  -1.09804, -0.5832,
208  0.45440, 1.61843,
209  2.46427, 2.66884,
210  2.154, 1.1164,
211  -0.0476325, -0.893474
212  }
213  }
214  ,
215  {
216  "THJ2",
217  {
218  0.6981, 0.34906, 0,
219  -0.34906, -0.6981,
220  0.6981, 0.34906, 0,
221  -0.34906, -0.6981,
222  0.6981, 0.34906,
223  0, -0.34906, -0.6981,
224  0.6981, 0.34906, 0,
225  -0.34906, -0.6981,
226  0.6981, 0.34906, 0,
227  -0.34906, -0.6981,
228  4.52129, 3.48746,
229  1.12154, -1.67278,
230  -3.82814, -4.52129,
231  -3.48746, -1.12154,
232  1.67278, 3.82814
233  }
234  }
235  };
236 
237  for (auto const& x : lib_test->sr_hand_lib->coupled_calibration_map)
238  {
239  for (int i=0; i < x.second.raw_values_coupled_.size(); ++i)
240  {
241  EXPECT_NEAR(x.second.raw_values_coupled_[i], expected_processed_raw_values_coupled[x.first][i], 0.01);
242  }
243 
244  for (int i=0; i < x.second.calibrated_values_.size(); ++i)
245  {
246  EXPECT_NEAR(x.second.calibrated_values_[i], expected_processed_calibrated_values[x.first][i], 0.01);
247  }
248  }
249 }
250 
251 TEST(SrRobotLib, CalibrateJoint)
252 {
254  std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
255  const double expected_motor_position = 2.21185;
256 
257  STATUS_TYPE *status_data = new STATUS_TYPE();
258  // add growing sensors values
259  for (unsigned int i = 1; i < SENSORS_NUM_0220 + 2; ++i)
260  {
261  status_data->sensors[i] = i;
262  }
263 
264  status_data->motor_data_type = MOTOR_DATA_SGR;
265 
266  // even motors
267  status_data->which_motors = 0;
268 
269  // all motor data arrived with no errors
270  status_data->which_motor_data_arrived = 0x00055555;
271  status_data->which_motor_data_had_errors = 0;
272 
273  // add growing motor data packet values
274  for (unsigned int i = 0; i < 10; ++i)
275  {
276  status_data->motor_data_packet[i].torque = 4;
277  status_data->motor_data_packet[i].misc = 2 * i;
278  }
279  // filling the status data with known values
280  status_data->idle_time_us = 1;
281 
282  for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
283  {
284  if ("THJ1" == (*joint_tmp).joint_name)
285  {
286  break;
287  }
288  }
289 
290  lib_test->sr_hand_lib->calibrate_joint(joint_tmp, status_data);
291 
293  boost::static_pointer_cast<shadow_joints::MotorWrapper>(joint_tmp->actuator_wrapper);
294 
295  const sr_actuator::SrMotorActuator *sr_actuator =
296  static_cast<sr_actuator::SrMotorActuator *>(motor_wrapper->actuator);
297 
298  EXPECT_NEAR(expected_motor_position, sr_actuator->motor_state_.position_unfiltered_, 0.01);
299  delete status_data;
300 }
301 
302 TEST(SrRobotLib, TimedCalibrateJoint)
303 {
305  std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
306 
307  STATUS_TYPE *status_data = new STATUS_TYPE();
308  // add growing sensors values
309  for (unsigned int i = 1; i < SENSORS_NUM_0220 + 2; ++i)
310  {
311  // position = id in joint enum
312  status_data->sensors[i] = i;
313  }
314 
315  status_data->motor_data_type = MOTOR_DATA_SGR;
316 
317  // even motors
318  status_data->which_motors = 0;
319 
320  // all motor data arrived with no errors
321  status_data->which_motor_data_arrived = 0x00055555;
322  status_data->which_motor_data_had_errors = 0;
323 
324  // add growing motor data packet values
325  for (unsigned int i = 0; i < 10; ++i)
326  {
327  status_data->motor_data_packet[i].torque = 4;
328  status_data->motor_data_packet[i].misc = 2 * i;
329  }
330  // filling the status data with known values
331  status_data->idle_time_us = 1;
332 
333  for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
334  {
335  if ("THJ1" == (*joint_tmp).joint_name)
336  {
337  break;
338  }
339  }
340 
341  auto start = std::chrono::steady_clock::now();
342  for (int i = 0; i < 20000; i++)
343  {
344  lib_test->sr_hand_lib->calibrate_joint(joint_tmp, status_data);
345  }
346  auto stop = std::chrono::steady_clock::now();
347  auto diff = stop - start;
348  double diff_time = static_cast<double>(std::chrono::duration <double, std::milli> (diff).count());
349 
350  EXPECT_LT(diff_time, 100);
351  delete status_data;
352 }
353 
357 TEST(SrRobotLib, UpdateMotor)
358 {
360 
361  STATUS_TYPE *status_data = new STATUS_TYPE();
362  // add growing sensors values
363  for (unsigned int i = 1; i < SENSORS_NUM_0220 + 2; ++i)
364  {
365  // position = id in joint enum
366  status_data->sensors[i] = i;
367  }
368 
369  status_data->motor_data_type = MOTOR_DATA_SGR;
370 
371  // even motors
372  status_data->which_motors = 0;
373 
374  // all motor data arrived with no errors
375  status_data->which_motor_data_arrived = 0x00055555;
376  status_data->which_motor_data_had_errors = 0;
377 
378  // add growing motor data packet values
379  for (unsigned int i = 0; i < 10; ++i)
380  {
381  status_data->motor_data_packet[i].torque = 4;
382  status_data->motor_data_packet[i].misc = 2 * i;
383  }
384  // filling the status data with known values
385  status_data->idle_time_us = 1;
386 
387  // update the library
388  lib_test->sr_hand_lib->update(status_data);
389 
390  // check the data we read back are correct.
391  EXPECT_EQ(lib_test->sr_hand_lib->main_pic_idle_time, 1);
392  EXPECT_EQ(lib_test->sr_hand_lib->main_pic_idle_time_min, 1);
393 
394  // check the sensors etc..
395  std::vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
396  for (; joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
397  {
398  if (joint_tmp->has_actuator)
399  {
401  boost::static_pointer_cast<shadow_joints::MotorWrapper>(joint_tmp->actuator_wrapper);
402  // we updated the even motors
403  if (motor_wrapper->motor_id % 2 == 0)
404  {
405  const sr_actuator::SrMotorActuator *sr_actuator =
406  static_cast<sr_actuator::SrMotorActuator *>(motor_wrapper->actuator);
407 
408  ROS_ERROR_STREAM("last measured effort: " << sr_actuator->state_.last_measured_effort_ << " actuator: " <<
409  motor_wrapper->actuator);
410 
411  EXPECT_FLOAT_EQ(sr_actuator->motor_state_.force_unfiltered_, 4.0); // (double)motor_wrapper->motor_id/2.0);
412  EXPECT_EQ(sr_actuator->motor_state_.strain_gauge_right_, motor_wrapper->motor_id);
413  }
414  }
415  }
416  delete status_data;
417 }
418 
424 TEST(SrRobotLib, UpdateActuators)
425 {
427 
428  STATUS_TYPE *status_data = new STATUS_TYPE();
429  // add growing sensors values
430  for (unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
431  {
432  // position = id in joint enum
433  status_data->sensors[i] = i + 1;
434  }
435 
436  status_data->motor_data_type = MOTOR_DATA_VOLTAGE;
437 
438  // even motors
439  status_data->which_motors = 0;
440 
441  // all motor data arrived with no errors
442  status_data->which_motor_data_arrived = 0x00055555;
443  status_data->which_motor_data_had_errors = 0;
444 
445  // add growing motor data packet values
446  for (unsigned int i = 0; i < 10; ++i)
447  {
448  status_data->motor_data_packet[i].torque = i;
449  status_data->motor_data_packet[i].misc = 10 * i;
450  }
451  // filling the status data with known values
452  status_data->idle_time_us = 1;
453 
454  // update the library
455  lib_test->sr_hand_lib->update(status_data);
456 
457  // name, motor_id, id_in_enum, expected_pos
458  lib_test->check_hw_actuator("rh_FFJ4", 2, 3, 4.0);
459 
460  // cleanup
461  delete status_data;
462 }
463 
471  :
472  public HandLibTestProtected
473 {
474 public:
475  TestHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh)
476  : HandLibTestProtected(hw, nh)
477  {
478  }
479 
481 
482  // using HandLibTestProtected::status_data;
483 
484  // using HandLibTestProtected::actuator;
485 
487 };
488 
489 
495 // TEST(SrRobotLib, CalibrationOneMotor)
496 // {
497 
498 // pr2_hardware_interface::HardwareInterface *hw;
499 // boost::shared_ptr<TestHandLib> sr_hand_lib = boost::shared_ptr<TestHandLib>( new TestHandLib(hw) );
500 
501 // STATUS_TYPE status_data;
502 
503 // // set all the sensors to 0
504 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
505 // status_data.sensors[i] = 0;
506 
507 // sr_hand_lib->status_data = &status_data;
508 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
509 // EXPECT_EQ(sr_hand_lib->status_data->sensors[i], 0);
510 
511 // // let's find FFJ3 in the vector
512 // boost::ptr_vector<shadow_joints::Joint>::iterator ffj3 = sr_hand_lib->joints_vector.begin();
513 // std::string name_tmp = ffj3->joint_name;
514 // bool ffj3_found = false;
515 // int index_ffj3 = 0;
516 
517 // for(; ffj3 != sr_hand_lib->joints_vector.end(); ++ffj3)
518 // {
519 // name_tmp = ffj3->joint_name;
520 
521 // if( name_tmp.compare("FFJ3") == 0)
522 // {
523 // ffj3_found = true;
524 // break;
525 // }
526 
527 // ++index_ffj3;
528 // }
529 
530 // EXPECT_TRUE(ffj3_found);
531 // EXPECT_EQ(index_ffj3, 3);
532 
533 // sr_hand_lib->actuator = (ffj3->motor->actuator);
534 
535 // sr_hand_lib->calibrate_joint(ffj3);
536 // // all the sensors at 0 -> should be 0
537 // EXPECT_EQ( ffj3->motor->actuator->state_.position_unfiltered_ , 0.0);
538 
539 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
540 // sr_hand_lib->status_data->sensors[i] = 1;
541 
542 // // now ffj3 position should be 1
543 // sr_hand_lib->calibrate_joint(ffj3);
544 // // all the sensors at 1 -> should be 1
545 // EXPECT_EQ( ffj3->motor->actuator->state_.position_unfiltered_ , 1.0);
546 
547 // delete hw;
548 // }
549 
550 
551 // /**
552 // * Testing the calibration procedure for
553 // * a joint having calibrating the sensors first
554 // * and then combining them (FFJ0)
555 // *
556 // */
557 // TEST(SrRobotLib, CalibrationFFJ0)
558 // {
559 
560 // pr2_hardware_interface::HardwareInterface *hw;
561 // boost::shared_ptr<TestHandLib> sr_hand_lib = boost::shared_ptr<TestHandLib>( new TestHandLib(hw) );
562 
563 // STATUS_TYPE status_data;
564 
565 // // set all the sensors to 0
566 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
567 // status_data.sensors[i] = 0;
568 
569 // sr_hand_lib->status_data = &status_data;
570 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
571 // EXPECT_EQ(sr_hand_lib->status_data->sensors[i], 0);
572 
573 // // let's find FFJ0 in the vector
574 // boost::ptr_vector<shadow_joints::Joint>::iterator ffj0 = sr_hand_lib->joints_vector.begin();
575 // std::string name_tmp = ffj0->joint_name;
576 // bool ffj0_found = false;
577 // int index_ffj0 = 0;
578 
579 // for(; ffj0 != sr_hand_lib->joints_vector.end(); ++ffj0)
580 // {
581 // name_tmp = ffj0->joint_name;
582 
583 // if( name_tmp.compare("FFJ0") == 0)
584 // {
585 // ffj0_found = true;
586 // break;
587 // }
588 
589 // ++index_ffj0;
590 // }
591 
592 // EXPECT_TRUE(ffj0_found);
593 // EXPECT_EQ(index_ffj0, 0);
594 
595 // sr_hand_lib->actuator = (ffj0->motor->actuator);
596 
597 // sr_hand_lib->calibrate_joint(ffj0);
598 // // all the sensors at 0 -> should be 0
599 // EXPECT_EQ( ffj0->motor->actuator->state_.position_unfiltered_ , 0.0);
600 
601 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
602 // sr_hand_lib->status_data->sensors[i] = 1;
603 
604 // // now ffj0 position should be 1
605 // sr_hand_lib->calibrate_joint(ffj0);
606 // // all the sensors at 1 -> should be 2
607 // EXPECT_EQ( ffj0->motor->actuator->state_.position_unfiltered_ , 2.0);
608 
609 // delete hw;
610 // }
611 
612 // /**
613 // * Testing the calibration procedure for
614 // * a compound joint combining the sensors
615 // * and then calibrating the total (THJ5)
616 // *
617 // */
618 // TEST(SrRobotLib, CalibrationTHJ5)
619 // {
620 
621 // pr2_hardware_interface::HardwareInterface *hw;
622 // boost::shared_ptr<TestHandLib> sr_hand_lib = boost::shared_ptr<TestHandLib>( new TestHandLib(hw) );
623 
624 // STATUS_TYPE status_data;
625 
626 // // set all the sensors to 0
627 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
628 // status_data.sensors[i] = 0;
629 
630 // sr_hand_lib->status_data = &status_data;
631 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
632 // EXPECT_EQ(sr_hand_lib->status_data->sensors[i], 0);
633 
634 // // let's find THJ5 in the vector
635 // boost::ptr_vector<shadow_joints::Joint>::iterator thj5 = sr_hand_lib->joints_vector.begin();
636 // std::string name_tmp = thj5->joint_name;
637 // bool thj5_found = false;
638 // int index_thj5 = 0;
639 
640 // for(; thj5 != sr_hand_lib->joints_vector.end(); ++thj5)
641 // {
642 // name_tmp = thj5->joint_name;
643 
644 // if( name_tmp.compare("THJ5") == 0)
645 // {
646 // thj5_found = true;
647 // break;
648 // }
649 
650 // ++index_thj5;
651 // }
652 
653 // EXPECT_TRUE(thj5_found);
654 // EXPECT_EQ(index_thj5, 25);
655 
656 // sr_hand_lib->actuator = (thj5->motor->actuator);
657 
658 // sr_hand_lib->calibrate_joint(thj5);
659 // // all the sensors at 0 -> should be 0
660 // EXPECT_EQ( thj5->motor->actuator->state_.position_unfiltered_ , 0.0);
661 
662 // for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
663 // sr_hand_lib->status_data->sensors[i] = 1;
664 
665 // // now thj5 position should be 1
666 // sr_hand_lib->calibrate_joint(thj5);
667 // // all the sensors at 1 -> should be 1 (THJ5 = .5 THJ5A + .5 THJ5B)
668 // EXPECT_EQ( thj5->motor->actuator->state_.position_unfiltered_ , 1.0);
669 
670 // delete hw;
671 // }
672 
677 TEST(SrRobotLib, HumanizeFlags)
678 {
680 
681  std::vector<std::pair<std::string, bool> > flags;
682  // all flags set
683  flags = lib_test->sr_hand_lib->humanize_flags(0xFFFF);
684 
685  EXPECT_EQ(flags.size(), 16);
686 
687  for (unsigned int i = 0; i < 16; ++i)
688  {
689  EXPECT_EQ(flags[i].first.compare(error_flag_names[i]), 0);
690  }
691 
692  // The last three flags are serious
693  EXPECT_TRUE(flags[13].second);
694  EXPECT_TRUE(flags[14].second);
695  EXPECT_TRUE(flags[15].second);
696 }
697 
699 // MAIN //
701 
702 int main(int argc, char **argv)
703 {
704  ros::init(argc, argv, "calibration_test");
705  testing::InitGoogleTest(&argc, argv);
706  return RUN_ALL_TESTS();
707 }
708 /* For the emacs weenies in the crowd.
709  Local Variables:
710  c-basic-offset: 2
711  End:
712 */
713 
MOTOR_DATA_SGR
#define error_flag_names
ROSCPP_DECL void start()
SrRobotLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix)
TestHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh)
ros::NodeHandle nh
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::shared_ptr< HandLibTestProtected > sr_hand_lib
HandLibTestProtected(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh)
int main(int argc, char **argv)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
bool getParam(const std::string &key, std::string &s) const
#define COMMAND_TYPE
MOTOR_DATA_VOLTAGE
#define STATUS_TYPE
XmlRpc::XmlRpcValue joint_to_sensor_mapping
TEST(SrRobotLib, Initialization)
SrMotorHandLib(hardware_interface::HardwareInterface *hw, ros::NodeHandle nh, ros::NodeHandle nhtilde, std::string device_id, std::string joint_prefix)
void calibrate_joint(std::vector< shadow_joints::Joint >::iterator joint_tmp, STATUS_TYPE *status_data)
void check_hw_actuator(std::string name, int motor_id, int id_in_enum, double expected_pos)
#define ROS_ERROR_STREAM(args)
#define SENSORS_NUM_0220
sr_actuator::SrMotorActuator * actuator
std::vector< std::pair< std::string, bool > > humanize_flags(int flag)


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Mon Feb 28 2022 23:50:43