test_send_action.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include "testUtils.h"
3 
4 #include <ros/ros.h>
5 #include <ros/package.h>
6 
7 #include <end_effector/Parser.h>
12 #include <end_effector/Utils.h>
14 
15 #include <rosee_msg/ROSEECommandAction.h>
17 
18 #include <random>
19 
20 
21 namespace {
22 
31 class testSendAction: public ::testing::Test {
32 
33 
34 
35 protected:
36 
37  testSendAction() {
38  }
39 
40  virtual ~testSendAction() {
41  }
42 
43  virtual void SetUp() override {
44 
45  if (! nh.hasParam("robot_name")) {
46  std::cout << "[TEST FAIL: robot name not set on server]" << std::endl;
47  return;
48  }
49 
50  std::string robot_name = "";
51  nh.getParam("robot_name", robot_name);
52 
53  ROSEE::Parser p ( nh );
54  if (! p.init ( ROSEE::Utils::getPackagePath() + "/configs/urdf/" + robot_name + ".urdf",
55  ROSEE::Utils::getPackagePath() + "/configs/srdf/" + robot_name + ".srdf",
56  ros::package::getPath("end_effector") + "/actions/" + robot_name + "/") )
57  {
58 
59  std::cout << "[TEST SEND ACTIONS]parser FAIL: some config file missing]" << std::endl;
60  return;
61  }
62 
63  ee = std::make_shared<ROSEE::EEInterface>(p);
64 
65  folderForActions = p.getActionPath();
66  if ( folderForActions.size() == 0 ){ //if no action path is set in the yaml file...
67  std::cout << "[TEST SEND ACTIONS] parser FAIL: action_path in the config file is missing" << std::endl;
68  return;
69  }
70 
71  //note: test on the findActions part is done in other test files
72  parserMoveIt = std::make_shared<ROSEE::ParserMoveIt>();
73  if (! parserMoveIt->init ("robot_description", false) ) {
74 
75  std::cout << "[TEST SEND ACTIONS] FAILED parserMoveit Init, stopping execution" << std::endl;
76  return;
77  }
78 
79  //note: calls to find*** (like findTrig) are done in the specific testu
80  actionsFinder = std::make_shared<ROSEE::FindActions>(parserMoveIt);
81 
82 
83  }
84 
85  virtual void TearDown() override {
86  }
87 
88  void sendAndTest(ROSEE::Action::Ptr action, double percentageWanted = 1.0);
89 
90  ros::NodeHandle nh;
91  std::string folderForActions;
92  std::unique_ptr<ROSEE::TestUtils::Process> roseeExecutor;
94  ros::Publisher sendActionPub;
95  ros::Subscriber receiveRobStateSub;
96  ROSEE::YamlWorker yamlWorker;
97  std::shared_ptr <actionlib::SimpleActionClient <rosee_msg::ROSEECommandAction> > action_client;
98  ROSEE::ParserMoveIt::Ptr parserMoveIt;
99  std::shared_ptr<ROSEE::FindActions> actionsFinder;
100 
101  struct ClbkHelper {
102 
103  ClbkHelper() : js(), completed(false) {};
104 
105  void jointStateClbk(const sensor_msgs::JointState::ConstPtr& msg) {
106 
107  js.name = msg->name;
108  js.position = msg->position;
109  js.velocity = msg->velocity;
110  js.effort = msg->effort;
111  }
112 
113  void actionDoneClbk(const actionlib::SimpleClientGoalState& state,
114  const rosee_msg::ROSEECommandResultConstPtr& result) {
115 
116  completed = true;
117  goalState = state.state_;
118  actionCompleted = result->completed_action;
119  }
120 
121  void actionFeedbackClbk(const rosee_msg::ROSEECommandFeedbackConstPtr& feedback) {
122 
123  feedback_percentage = feedback->completation_percentage;
124  }
125 
126  void actionActiveClbk() { completed = false; }
127 
128  sensor_msgs::JointState js;
129  bool completed;
130  double feedback_percentage;
131  rosee_msg::ROSEEActionControl actionCompleted;
133 
134 
135  };
136 
137  ClbkHelper clbkHelper;
138 
139  void setMainNode();
140  void sendAction( ROSEE::Action::Ptr action, double percentageWanted);
141  void testAction( ROSEE::Action::Ptr actionSent, double percentageWanted);
142 
143 };
144 
145 void testSendAction::setMainNode() {
146 
147  std::string handNameArg = "hand_name:=" + ee->getName();
148  roseeExecutor.reset(new ROSEE::TestUtils::Process({"roslaunch", "end_effector", "test_rosee_startup.launch", handNameArg}));
149 
150  //TODO put a checkReady service instead of sleeping?
151  sleep(5); // lets wait for test_rosee_startup to be ready
152  std::string topic_name_js = "/ros_end_effector/joint_states";
153 
154  receiveRobStateSub = nh.subscribe (topic_name_js, 1, &ClbkHelper::jointStateClbk, &clbkHelper);
155 
156  action_client =
157  std::make_shared <actionlib::SimpleActionClient <rosee_msg::ROSEECommandAction>>
158  (nh, "/ros_end_effector/action_command", true); //TODO check this action command
159 
160  action_client->waitForServer();
161 
162 }
163 
164 void testSendAction::sendAction( ROSEE::Action::Ptr action, double percentageWanted) {
165 
166  rosee_msg::ROSEECommandGoal goal;
167  goal.goal_action.seq = 0 ;
168  goal.goal_action.stamp = ros::Time::now();
169  goal.goal_action.percentage = percentageWanted;
170  goal.goal_action.action_name = action->getName();
171  goal.goal_action.action_type = action->getType() ;
172 
173  if (action->getType() == ROSEE::Action::Type::Primitive) {
174  ROSEE::ActionPrimitive::Ptr primitivePtr = std::static_pointer_cast<ROSEE::ActionPrimitive>(action);
175  goal.goal_action.actionPrimitive_type = primitivePtr->getPrimitiveType() ;
176 
177  for (auto it : primitivePtr->getKeyElements()) {
178  goal.goal_action.selectable_items.push_back(it);
179  }
180  }
181 
182  action_client->sendGoal (goal, boost::bind(&ClbkHelper::actionDoneClbk, &clbkHelper, _1, _2),
183  boost::bind(&ClbkHelper::actionActiveClbk, &clbkHelper), boost::bind(&ClbkHelper::actionFeedbackClbk, &clbkHelper, _1)) ;
184 
185 }
186 
187 void testSendAction::testAction(ROSEE::Action::Ptr actionSent, double percentageWanted) {
188 
189  ros::Rate r(10); // 10 hz
190  while (!clbkHelper.completed) {
191  ROS_INFO_STREAM_ONCE("Test Send Actions: Waiting for action completion...");
192  ros::spinOnce();
193  r.sleep();
194  }
195 
196  //lets wait one sec more so subscriber for joint state receive the very last state
197  ros::Rate r2(1);
198  r2.sleep();
199  ros::spinOnce();
200 
201 
202  //finally, lets test if the pos set in the actions are the same of the robot when the action is completed
203  for (int i=0; i < clbkHelper.js.name.size(); i++) {
204 
205  auto wantedJointsPosMap = actionSent->getJointPos();
206 
207  auto findJoint = wantedJointsPosMap.find(clbkHelper.js.name[i]);
208 
209  if (findJoint == wantedJointsPosMap.end()){
210  continue; //this is not an error, in clbkHelper we have joint pos of all joints, not only actuated
211  }
212 
213  double wantedPos = (findJoint->second.at(0))*percentageWanted;
214  double realPos = clbkHelper.js.position[i];
215 
216  EXPECT_NEAR (wantedPos, realPos, 0.02); //norm of the accepted error in roseeExecutor is <0.01
217 
218  //the percentage must be exaclty 100 instead (apart double precisions errors, handled by the macro)
219  EXPECT_DOUBLE_EQ (clbkHelper.feedback_percentage, 100);
221 
222  //test if the action completed is the same sent
223  EXPECT_DOUBLE_EQ (percentageWanted, clbkHelper.actionCompleted.percentage);
224  EXPECT_EQ (actionSent->getName(), clbkHelper.actionCompleted.action_name);
225  EXPECT_EQ (actionSent->getType(), clbkHelper.actionCompleted.action_type);
226  if (actionSent->getType() == ROSEE::Action::Type::Primitive) {
227  ROSEE::ActionPrimitive::Ptr primitivePtr = std::static_pointer_cast<ROSEE::ActionPrimitive>(actionSent);
228  EXPECT_EQ (primitivePtr->getPrimitiveType(), clbkHelper.actionCompleted.actionPrimitive_type);
229  }
230  }
231 }
232 
233 void testSendAction::sendAndTest(ROSEE::Action::Ptr action, double percentageWanted) {
234 
235  setMainNode();
236  sendAction(action, percentageWanted);
237  testAction(action, percentageWanted);
238 
239 }
240 
254 TEST_F ( testSendAction, sendSimpleGeneric ) {
255 
256 
257  ROSEE::JointPos jp;
259 
260  std::vector<std::string> actJoints = ee->getActuatedJoints();
261 
262  ASSERT_FALSE (actJoints.empty());
263 
264  for (int i = 0; i<actJoints.size(); i++) {
265 
266  int id = -1;
267  ee->getInternalIdForJoint(actJoints.at(i), id);
268 
269  //create an action where all joints move toward their upper limit
270  std::vector<double> one_dof;
271  one_dof.push_back ( ee->getUpperPositionLimits()[id] );
272  jp.insert ( std::make_pair(actJoints.at(i), one_dof) );
273  jpc.insert (std::make_pair(actJoints.at(i), 1));
274 
275  }
276 
277  //ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionGeneric>("testAllUpperLim", jp, jpc);
278  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionGeneric>("RandomActionGeneric", jp, jpc);
279  //emit the yaml so roseeExecutor can find the action
280  yamlWorker.createYamlFile( action.get(), folderForActions + "/generics/" );
281 
282  sendAndTest(action);
283 
284 }
285 
286 TEST_F ( testSendAction, sendSimpleGeneric2 ) {
287 
288 
289  ROSEE::JointPos jp;
291 
292  std::vector<std::string> actJoints = ee->getActuatedJoints();
293 
294  ASSERT_FALSE (actJoints.empty());
295 
296  for (int i = 0; i<actJoints.size(); i++) {
297 
298  int id = -1;
299  ee->getInternalIdForJoint(actJoints.at(i), id);
300 
301  //create an action where all joints move toward their lower limit
302  std::vector<double> one_dof;
303  one_dof.push_back ( ee->getLowerPositionLimits()[id] );
304  jp.insert ( std::make_pair(actJoints.at(i), one_dof) );
305  jpc.insert (std::make_pair(actJoints.at(i), 1));
306 
307  }
308 
309  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionGeneric>("testAllLowerLim", jp, jpc);
310  //emit the yaml so roseeExecutor can find the action
311  yamlWorker.createYamlFile( action.get(), folderForActions + "/generics/" );
312 
313  sendAndTest(action);
314 
315 }
316 
317 
318 TEST_F ( testSendAction, sendSimpleGeneric3 ) {
319 
320  ROSEE::JointPos jp;
322 
323  std::vector<std::string> actJoints = ee->getActuatedJoints();
324 
325  ASSERT_FALSE (actJoints.empty());
326 
327  for (int i = 0; i<actJoints.size(); i++) {
328 
329  int id = -1;
330  ee->getInternalIdForJoint(actJoints.at(i), id);
331 
332  //create an action where all joints move, but make sure to stay within limits
333  std::vector<double> one_dof;
334  one_dof.push_back ( ee->getLowerPositionLimits()[id]*0.15 + 0.1 );
335  jp.insert ( std::make_pair(actJoints.at(i), one_dof) );
336  jpc.insert (std::make_pair(actJoints.at(i), 1));
337 
338  }
339 
340  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionGeneric>("testAllUpperLim2", jp, jpc);
341  //emit the yaml so roseeExecutor can find the action
342  yamlWorker.createYamlFile( action.get(), folderForActions + "/generics/" );
343 
344  sendAndTest(action, 0.33);
345 
346 }
347 
354 TEST_F ( testSendAction, sendTrig ) {
355 
356  ROSEE::ActionTrig::Map trigMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::Trig, folderForActions + "/primitives/") ;
357 
358  if (trigMap.size()>0){
359  std::vector<std::string> keys = ROSEE::Utils::extract_keys(trigMap);
360  //lets pick a random trig
361  srand((unsigned int)time(NULL));
362  int i = rand() % keys.size();
363  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionTrig>(trigMap.at(keys.at(i)));
364 
365  sendAndTest(action);
366 
367  //other than "default" check done in sendAndTest, we check that effectively the trig joints are gone
368  //toward their limit (from definition of trig)
369  std::vector<std::string> actJointsInvolved;
370  ee->getActuatedJointsInFinger(keys.at(i), actJointsInvolved);
371 
372  for (auto jointName : actJointsInvolved) {
373  //at O single dof joint
374  double bigBound = parserMoveIt->getBiggerBoundFromZero(jointName).at(0);
375 
376  for (int k = 0; k<clbkHelper.js.name.size(); k++) {
377 
378  if (clbkHelper.js.name[i].compare(jointName) == 0 ) {
379  EXPECT_NEAR(bigBound, clbkHelper.js.position[i], 0.02);
380  break;
381  }
382  }
383  }
384  }
385 }
386 
387 TEST_F ( testSendAction, sendTipFlex ) {
388 
389  auto tipFlexMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::TipFlex, folderForActions + "/primitives/");
390 
391  if (tipFlexMap.size()>0) {
392  std::vector<std::string> keys = ROSEE::Utils::extract_keys(tipFlexMap);
393  //lets pick a random
394  srand((unsigned int)time(NULL));
395  int i = rand() % keys.size();
396  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionTrig>(tipFlexMap.at(keys.at(i)));
397 
398  sendAndTest(action);
399 
400  //other than "default" check done in sendAndTest, we check that effectively the joint is gone to the limit
401 
402  //Workaround to take the single joint used by this action
403  auto jic = action->getJointsInvolvedCount();
404  std::string jointInvolved;
405  for (auto it : jic) {
406  if (it.second == 1 ){
407  jointInvolved = it.first;
408  }
409  }
410 
411  EXPECT_TRUE(jointInvolved.size() > 0);
412 
413  //at O single dof joint
414  double bigBound = parserMoveIt->getBiggerBoundFromZero(jointInvolved).at(0);
415 
416  for (int k = 0; k<clbkHelper.js.name.size(); k++) {
417 
418  if (clbkHelper.js.name[i].compare(jointInvolved) == 0 ) {
419  EXPECT_NEAR(bigBound, clbkHelper.js.position[i], 0.02);
420  break;
421 
422  }
423  }
424  }
425 }
426 
427 TEST_F ( testSendAction, sendFingFlex ) {
428 
429  auto fingFlexMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::FingFlex, folderForActions + "/primitives/");
430 
431  if (fingFlexMap.size()>0) {
432  std::vector<std::string> keys = ROSEE::Utils::extract_keys(fingFlexMap);
433  //lets pick a random
434  srand((unsigned int)time(NULL));
435  int i = rand() % keys.size();
436  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionTrig>(fingFlexMap.at(keys.at(i)));
437 
438  sendAndTest(action);
439 
440  //other than "default" check done in sendAndTest, we check that effectively the joint is gone to the limit
441 
442  //Workaround to take the single joint used by this action
443  auto jic = action->getJointsInvolvedCount();
444  std::string jointInvolved;
445  for (auto it : jic) {
446  if (it.second == 1 ){
447  jointInvolved = it.first;
448  }
449  }
450 
451  EXPECT_TRUE(jointInvolved.size() > 0);
452 
453  //at O single dof joint
454  double bigBound = parserMoveIt->getBiggerBoundFromZero(jointInvolved).at(0);
455 
456  for (int k = 0; k<clbkHelper.js.name.size(); k++) {
457 
458  if (clbkHelper.js.name[i].compare(jointInvolved) == 0 ) {
459  EXPECT_NEAR(bigBound, clbkHelper.js.position[i], 0.02);
460  break;
461 
462  }
463  }
464  }
465 }
466 
467 
468 TEST_F ( testSendAction, sendPinches ) {
469 
470  auto pinchTightMap = actionsFinder->findPinch(folderForActions + "/primitives/").first;
471 
472  if (pinchTightMap.size()>0){
473  std::vector<std::pair<std::string,std::string>> keys = ROSEE::Utils::extract_keys(pinchTightMap);
474  //lets pick a random
475  srand((unsigned int)time(NULL));
476  int i = rand() % keys.size();
477  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionPinchTight>(pinchTightMap.at(keys.at(i)));
478 
479  sendAndTest(action);
480 
481  }
482 }
483 
484 TEST_F ( testSendAction, sendPinchLoose ) {
485 
486  auto pinchLooseMap = actionsFinder->findPinch(folderForActions + "/primitives/").second;
487 
488  if (pinchLooseMap.size()>0){
489  std::vector<std::pair<std::string,std::string>> keys = ROSEE::Utils::extract_keys(pinchLooseMap);
490  //lets pick a random
491  srand((unsigned int)time(NULL));
492  int i = rand() % keys.size();
493  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionPinchLoose>(pinchLooseMap.at(keys.at(i)));
494 
495  sendAndTest(action);
496 
497  }
498 }
499 
500 TEST_F (testSendAction, sendMultiplePinchStrict ) {
501 
502 
503  std::vector < ROSEE::ActionMultiplePinchTight::Map > multiplePinchMapsStrict;
504  for (int i = 3; i <= ee->getFingersNumber(); i++) {
505  auto multiplePinchMapStrict = actionsFinder->findMultiplePinch(i, folderForActions + "/primitives/", true );
506 
507  //keep only if it is not empty
508  if (multiplePinchMapStrict.size() > 0 ) {
509  multiplePinchMapsStrict.push_back (multiplePinchMapStrict);
510  }
511  }
512 
513  if ( multiplePinchMapsStrict.size() > 0 ) {
514 
515  srand((unsigned int)time(NULL));
516  int j = rand() % multiplePinchMapsStrict.size();
517 
518  std::vector<std::set<std::string>> keys = ROSEE::Utils::extract_keys( multiplePinchMapsStrict.at(j) );
519  //lets pick a random trig
520  srand((unsigned int)time(NULL));
521  int i = rand() % keys.size();
522  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionMultiplePinchTight>(multiplePinchMapsStrict.at(j).at(keys.at(i)));
523 
524  sendAndTest(action);
525 
526  }
527 
528 }
529 
530 TEST_F (testSendAction, sendMultiplePinchNoStrict ) {
531 
532 
533  std::vector < ROSEE::ActionMultiplePinchTight::Map > multiplePinchMapsNOStrict;
534  for (int i = 3; i <= ee->getFingersNumber(); i++) {
535  auto multiplePinchMapNOStrict = actionsFinder->findMultiplePinch(i, folderForActions + "/primitives/", false );
536 
537  //keep only if it is not empty
538  if (multiplePinchMapNOStrict.size() > 0 ) {
539  multiplePinchMapsNOStrict.push_back (multiplePinchMapNOStrict);
540  }
541 
542  }
543 
544  if ( multiplePinchMapsNOStrict.size() > 0 ) {
545 
546  srand((unsigned int)time(NULL));
547  int j = rand() % multiplePinchMapsNOStrict.size();
548 
549  std::vector<std::set<std::string>> keys = ROSEE::Utils::extract_keys( multiplePinchMapsNOStrict.at(j) );
550  //lets pick a random trig
551  srand((unsigned int)time(NULL));
552  int i = rand() % keys.size();
553  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionMultiplePinchTight>(multiplePinchMapsNOStrict.at(j).at(keys.at(i)));
554 
555  sendAndTest(action);
556 
557  }
558 
559 }
560 
561 TEST_F (testSendAction, sendSingleJointMultipleTips ) {
562 
563  std::vector < ROSEE::ActionSingleJointMultipleTips::Map > singleJointMultipleTipsMaps;
564 
565  for (int i = 1; i<=ee->getFingersNumber(); i++) {
566 
567  std::map < std::string, ROSEE::ActionSingleJointMultipleTips> singleJointMultipleTipsMap =
568  actionsFinder->findSingleJointMultipleTips (i, folderForActions + "/primitives/") ;
569 
570  if (singleJointMultipleTipsMap.size()>0) {
571  singleJointMultipleTipsMaps.push_back(singleJointMultipleTipsMap);
572  }
573 
574  }
575 
576  if ( singleJointMultipleTipsMaps.size() > 0 ) {
577 
578  srand((unsigned int)time(NULL));
579  int j = rand() % singleJointMultipleTipsMaps.size();
580 
581  std::vector<std::string> keys = ROSEE::Utils::extract_keys( singleJointMultipleTipsMaps.at(j) );
582  //lets pick a random trig
583  srand((unsigned int)time(NULL));
584  int i = rand() % keys.size();
585  ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionSingleJointMultipleTips>(singleJointMultipleTipsMaps.at(j).at(keys.at(i)));
586 
587  sendAndTest(action);
588 
589  }
590 }
591 
592 
593 /***
594  * @brief Here we create a randomic action composed by some primitives
595  */
596 TEST_F (testSendAction, sendComposedAction ) {
597 
598  ROSEE::ActionTrig::Map trigMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::Trig, folderForActions + "/primitives/") ;
599  auto fingFlexMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::FingFlex, folderForActions + "/primitives/");
600  auto pinchTightMap = actionsFinder->findPinch(folderForActions + "/primitives/").first;
601 
602  ROSEE::ActionComposed actionComposed ( "TestComposed", false) ;
603 
604  for (auto trig : trigMap) {
605  std::shared_ptr <ROSEE::ActionPrimitive> pointer =
606  std::make_shared <ROSEE::ActionTrig> ( trig.second );
607 
608  double lower_bound = 0;
609  double upper_bound = 0.8; //low, we do not want to go out of joint limits
610  std::uniform_real_distribution<double> unif(lower_bound, upper_bound);
611  std::default_random_engine re;
612  double random = unif(re);
613  EXPECT_TRUE(actionComposed.sumAction ( pointer, random ));
614  }
615 
616  for (auto trig : fingFlexMap) {
617  std::shared_ptr <ROSEE::ActionPrimitive> pointer =
618  std::make_shared <ROSEE::ActionTrig> ( trig.second );
619 
620  double lower_bound = 0;
621  double upper_bound = 0.7; //low, we do not want to go out of joint limits
622  std::uniform_real_distribution<double> unif(lower_bound, upper_bound);
623  std::default_random_engine re;
624  double random = unif(re);
625  EXPECT_TRUE(actionComposed.sumAction ( pointer, random ));
626  }
627 
628  for (auto pinch : pinchTightMap) {
629 
630  std::shared_ptr <ROSEE::ActionPrimitive> pointer =
631  std::make_shared <ROSEE::ActionPinchTight> ( pinch.second );
632 
633  double lower_bound = 0;
634  double upper_bound = 0.29; //low, we do not want to go out of joint limits
635  std::uniform_real_distribution<double> unif(lower_bound, upper_bound);
636  std::default_random_engine re;
637  double random = unif(re);
638  EXPECT_TRUE(actionComposed.sumAction ( pointer, random, 2 ));
639  }
640 
641  if (actionComposed.numberOfInnerActions() > 0) {
642  ROSEE::Action::Ptr actionPtr = std::make_shared<ROSEE::ActionGeneric>(actionComposed);
643 
644  //do not forget to emit the file, in sendAndTest the rosee main node need to parse it
645  yamlWorker.createYamlFile( actionPtr.get(), folderForActions + "/generics/" );
646 
647  sendAndTest(actionPtr, 0.95);
648  }
649 
650 }
651 
652 
653 TEST_F (testSendAction, sendTimedAction ) {
654 
655  ROSEE::ActionTrig::Map trigMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::Trig, folderForActions + "/primitives/") ;
656  auto tipFlexMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::TipFlex, folderForActions + "/primitives/");
657  auto pinchMaps = actionsFinder->findPinch(folderForActions + "/primitives/");
658 
659  ROSEE::ActionTimed actionTimed ( "TestTimed" ) ;
660 
661  if (trigMap.size()>0) {
662  std::shared_ptr <ROSEE::ActionPrimitive> pointer =
663  std::make_shared <ROSEE::ActionTrig> ( trigMap.begin()->second );
664 
665  double lower_bound = 0;
666  double upper_bound = 0.8; //low, we do not want to go out of joint limits
667  std::uniform_real_distribution<double> unif(lower_bound, upper_bound);
668  std::default_random_engine re;
669  double random = unif(re);
670  EXPECT_TRUE(actionTimed.insertAction(pointer, 0, 0.7, 0, random));
671  }
672 
673  if (tipFlexMap.size() > 0) {
674  std::shared_ptr <ROSEE::ActionPrimitive> pointer =
675  std::make_shared <ROSEE::ActionTrig> ( tipFlexMap.rbegin()->second); //rbegin is the last element
676 
677  double lower_bound = 0;
678  double upper_bound = 0.95;
679  std::uniform_real_distribution<double> unif(lower_bound, upper_bound);
680  std::default_random_engine re;
681  double random = unif(re);
682  EXPECT_TRUE(actionTimed.insertAction(pointer, 0.2, 0.32, 0, random));
683  }
684 
685  if (! pinchMaps.first.empty()) {
686 
687  std::shared_ptr <ROSEE::ActionPrimitive> pointer =
688  std::make_shared <ROSEE::ActionPinchTight> ( pinchMaps.first.begin()->second );
689 
690  double lower_bound = 0.6;
691  double upper_bound = 1;
692  std::uniform_real_distribution<double> unif(lower_bound, upper_bound);
693  std::default_random_engine re;
694  double random = unif(re);
695  EXPECT_TRUE(actionTimed.insertAction(pointer, 0.2, 0.32, 1, random));
696  }
697 
698  if (! pinchMaps.second.empty()) {
699  std::shared_ptr <ROSEE::ActionPrimitive> pointer =
700  std::make_shared <ROSEE::ActionPinchLoose> ( pinchMaps.second.rbegin()->second );
701 
702  double lower_bound = 0;
703  double upper_bound = 1;
704  std::uniform_real_distribution<double> unif(lower_bound, upper_bound);
705  std::default_random_engine re;
706  double random = unif(re);
707  EXPECT_TRUE(actionTimed.insertAction(pointer, 0, 0, 0, random));
708  }
709 
710  if (actionTimed.getInnerActionsNames().size() > 0) {
711  ROSEE::Action::Ptr actionPtr = std::make_shared<ROSEE::ActionTimed>(actionTimed);
712 
713  //do not forget to emit the file, in sendAndTest the rosee main node need to parse it
714  yamlWorker.createYamlFile( actionPtr.get(), folderForActions + "/timeds/" );
715 
716  sendAndTest(actionPtr);
717  }
718 
719 }
720 
721 
722 
723 } //namespace
724 
725 int main ( int argc, char **argv ) {
726 
727  if (argc < 2 ){
728 
729  std::cout << "[TEST ERROR] Insert hand name as argument" << std::endl;
730  return -1;
731  }
732 
733  /******************* Run tests on an isolated roscore ********************************************************/
734  /* COMMENT ALL THIS block if you want to use roscore command by hand (useful for debugging the test) */
735  //TODO I do not really understand why everything fails if I put this block at the beginning of prepareROSForTests function
736  if(setenv("ROS_MASTER_URI", "http://localhost:11322", 1) == -1)
737  {
738  perror("setenv");
739  return 1;
740  }
741 
742  //run roscore
743  std::unique_ptr<ROSEE::TestUtils::Process> roscore;
744  roscore.reset(new ROSEE::TestUtils::Process({"roscore", "-p", "11322"}));
745  /****************************************************************************************************/
746 
747  if ( ROSEE::TestUtils::prepareROSForTests ( argc, argv, "testSendAction" ) != 0 ) {
748 
749  std::cout << "[TEST ERROR] Prepare Function failed" << std::endl;
750  return -1;
751  }
752 
753  ::testing::InitGoogleTest ( &argc, argv );
754  return RUN_ALL_TESTS();
755 }
ROSEE::YamlWorker
Definition: YamlWorker.h:47
actionlib::SimpleClientGoalState::state_
StateEnum state_
ros::Publisher
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
ROSEE::ActionTimed
An action composed by other ones that must be executed one after other with some wait time (also 0) i...
Definition: ActionTimed.h:39
Parser.h
ROSEE::ActionPrimitive::Ptr
std::shared_ptr< ActionPrimitive > Ptr
Definition: ActionPrimitive.h:53
ros.h
ActionGeneric.h
r
r
actionlib::SimpleClientGoalState
YamlWorker.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
ROSEE::JointsInvolvedCount
std::map< std::string, unsigned int > JointsInvolvedCount
The map to describe, how many times a joint is set by the action. An ActionPrimitive and an ActionCom...
Definition: Action.h:63
ROSEE::ActionTrig::Map
std::map< std::string, ActionTrig > Map
Definition: ActionTrig.h:69
ROSEE::TestUtils::prepareROSForTests
int prepareROSForTests(int argc, char **argv, std::string testName)
Function to be called in the main of each test, it runs roscore and fill parameter server with robot ...
Definition: testUtils.h:95
EEInterface.h
EXPECT_TRUE
#define EXPECT_TRUE(args)
Utils.h
ROSEE::TestUtils::Process
Definition: testUtils.h:22
actionlib::SimpleClientGoalState::StateEnum
StateEnum
ParserMoveIt.h
ROSEE::Utils::getPackagePath
static std::string getPackagePath()
Definition: Utils.h:87
simple_action_client.h
ROS_INFO_STREAM_ONCE
#define ROS_INFO_STREAM_ONCE(args)
ROSEE::Utils::extract_keys
static std::vector< KeyType > extract_keys(std::map< KeyType, ValueType > const &input_map)
Definition: Utils.h:95
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
TEST_F
TEST_F(TestRunner, threaded_test)
actionlib::SimpleClientGoalState::SUCCEEDED
SUCCEEDED
package.h
testUtils.h
ROSEE::ParserMoveIt::Ptr
std::shared_ptr< ParserMoveIt > Ptr
Definition: ParserMoveIt.h:40
ROSEE::Action::Ptr
std::shared_ptr< Action > Ptr
Definition: Action.h:75
r2
r2
ros::Rate
ROSEE::EEInterface::Ptr
std::shared_ptr< EEInterface > Ptr
Definition: EEInterface.h:40
main
int main(int argc, char **argv)
Definition: test_send_action.cpp:725
ROSEE::JointPos
std::map< std::string, std::vector< double > > JointPos
The map to describe the position of all actuated joints. The key is the name of the string,...
Definition: Action.h:40
ROSEE::Parser
Class responsible for parsing the YAML file providing the URDF, SRDF, the EE-HAL library implementati...
Definition: Parser.h:46
EXPECT_EQ
#define EXPECT_EQ(a, b)
ROSEE::ActionComposed
A ActionComposed, which is formed by one or more Primitives (or even other composed)....
Definition: ActionComposed.h:44
ros::NodeHandle
ros::Subscriber
FindActions.h
ros::Time::now
static Time now()


end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Sat Dec 14 2024 03:49:26