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