1 #include <gtest/gtest.h>
15 #include <rosee_msg/ROSEECommandAction.h>
31 class testSendAction:
public ::testing::Test {
40 virtual ~testSendAction() {
43 virtual void SetUp()
override {
45 if (! nh.hasParam(
"robot_name")) {
46 std::cout <<
"[TEST FAIL: robot name not set on server]" << std::endl;
50 std::string robot_name =
"";
51 nh.getParam(
"robot_name", robot_name);
59 std::cout <<
"[TEST SEND ACTIONS]parser FAIL: some config file missing]" << std::endl;
63 ee = std::make_shared<ROSEE::EEInterface>(p);
65 folderForActions = p.getActionPath();
66 if ( folderForActions.size() == 0 ){
67 std::cout <<
"[TEST SEND ACTIONS] parser FAIL: action_path in the config file is missing" << std::endl;
72 parserMoveIt = std::make_shared<ROSEE::ParserMoveIt>();
73 if (! parserMoveIt->init (
"robot_description",
false) ) {
75 std::cout <<
"[TEST SEND ACTIONS] FAILED parserMoveit Init, stopping execution" << std::endl;
80 actionsFinder = std::make_shared<ROSEE::FindActions>(parserMoveIt);
85 virtual void TearDown()
override {
91 std::string folderForActions;
92 std::unique_ptr<ROSEE::TestUtils::Process> roseeExecutor;
97 std::shared_ptr <actionlib::SimpleActionClient <rosee_msg::ROSEECommandAction> > action_client;
99 std::shared_ptr<ROSEE::FindActions> actionsFinder;
103 ClbkHelper() : js(), completed(false) {};
105 void jointStateClbk(
const sensor_msgs::JointState::ConstPtr& msg) {
108 js.position = msg->position;
109 js.velocity = msg->velocity;
110 js.effort = msg->effort;
114 const rosee_msg::ROSEECommandResultConstPtr& result) {
118 actionCompleted = result->completed_action;
121 void actionFeedbackClbk(
const rosee_msg::ROSEECommandFeedbackConstPtr& feedback) {
123 feedback_percentage = feedback->completation_percentage;
126 void actionActiveClbk() { completed =
false; }
128 sensor_msgs::JointState js;
130 double feedback_percentage;
131 rosee_msg::ROSEEActionControl actionCompleted;
137 ClbkHelper clbkHelper;
145 void testSendAction::setMainNode() {
147 std::string handNameArg =
"hand_name:=" + ee->getName();
148 roseeExecutor.reset(
new ROSEE::TestUtils::Process({
"roslaunch",
"end_effector",
"test_rosee_startup.launch", handNameArg}));
152 std::string topic_name_js =
"/ros_end_effector/joint_states";
154 receiveRobStateSub = nh.subscribe (topic_name_js, 1, &ClbkHelper::jointStateClbk, &clbkHelper);
157 std::make_shared <actionlib::SimpleActionClient <rosee_msg::ROSEECommandAction>>
158 (nh,
"/ros_end_effector/action_command",
true);
160 action_client->waitForServer();
164 void testSendAction::sendAction(
ROSEE::Action::Ptr action,
double percentageWanted) {
166 rosee_msg::ROSEECommandGoal goal;
167 goal.goal_action.seq = 0 ;
169 goal.goal_action.percentage = percentageWanted;
170 goal.goal_action.action_name = action->getName();
171 goal.goal_action.action_type = action->getType() ;
173 if (action->getType() == ROSEE::Action::Type::Primitive) {
175 goal.goal_action.actionPrimitive_type = primitivePtr->getPrimitiveType() ;
177 for (
auto it : primitivePtr->getKeyElements()) {
178 goal.goal_action.selectable_items.push_back(it);
182 action_client->sendGoal (goal, boost::bind(&ClbkHelper::actionDoneClbk, &clbkHelper, _1, _2),
183 boost::bind(&ClbkHelper::actionActiveClbk, &clbkHelper), boost::bind(&ClbkHelper::actionFeedbackClbk, &clbkHelper, _1)) ;
187 void testSendAction::testAction(
ROSEE::Action::Ptr actionSent,
double percentageWanted) {
190 while (!clbkHelper.completed) {
203 for (
int i=0; i < clbkHelper.js.name.size(); i++) {
205 auto wantedJointsPosMap = actionSent->getJointPos();
207 auto findJoint = wantedJointsPosMap.find(clbkHelper.js.name[i]);
209 if (findJoint == wantedJointsPosMap.end()){
213 double wantedPos = (findJoint->second.at(0))*percentageWanted;
214 double realPos = clbkHelper.js.position[i];
219 EXPECT_DOUBLE_EQ (clbkHelper.feedback_percentage, 100);
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) {
228 EXPECT_EQ (primitivePtr->getPrimitiveType(), clbkHelper.actionCompleted.actionPrimitive_type);
233 void testSendAction::sendAndTest(
ROSEE::Action::Ptr action,
double percentageWanted) {
236 sendAction(action, percentageWanted);
237 testAction(action, percentageWanted);
254 TEST_F ( testSendAction, sendSimpleGeneric ) {
260 std::vector<std::string> actJoints = ee->getActuatedJoints();
262 ASSERT_FALSE (actJoints.empty());
264 for (
int i = 0; i<actJoints.size(); i++) {
267 ee->getInternalIdForJoint(actJoints.at(i),
id);
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));
278 ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionGeneric>(
"RandomActionGeneric", jp, jpc);
280 yamlWorker.createYamlFile( action.get(), folderForActions +
"/generics/" );
286 TEST_F ( testSendAction, sendSimpleGeneric2 ) {
292 std::vector<std::string> actJoints = ee->getActuatedJoints();
294 ASSERT_FALSE (actJoints.empty());
296 for (
int i = 0; i<actJoints.size(); i++) {
299 ee->getInternalIdForJoint(actJoints.at(i),
id);
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));
309 ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionGeneric>(
"testAllLowerLim", jp, jpc);
311 yamlWorker.createYamlFile( action.get(), folderForActions +
"/generics/" );
318 TEST_F ( testSendAction, sendSimpleGeneric3 ) {
323 std::vector<std::string> actJoints = ee->getActuatedJoints();
325 ASSERT_FALSE (actJoints.empty());
327 for (
int i = 0; i<actJoints.size(); i++) {
330 ee->getInternalIdForJoint(actJoints.at(i),
id);
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));
340 ROSEE::Action::Ptr action = std::make_shared<ROSEE::ActionGeneric>(
"testAllUpperLim2", jp, jpc);
342 yamlWorker.createYamlFile( action.get(), folderForActions +
"/generics/" );
344 sendAndTest(action, 0.33);
354 TEST_F ( testSendAction, sendTrig ) {
356 ROSEE::ActionTrig::Map trigMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::Trig, folderForActions +
"/primitives/") ;
358 if (trigMap.size()>0){
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)));
369 std::vector<std::string> actJointsInvolved;
370 ee->getActuatedJointsInFinger(keys.at(i), actJointsInvolved);
372 for (
auto jointName : actJointsInvolved) {
374 double bigBound = parserMoveIt->getBiggerBoundFromZero(jointName).at(0);
376 for (
int k = 0; k<clbkHelper.js.name.size(); k++) {
378 if (clbkHelper.js.name[i].compare(jointName) == 0 ) {
379 EXPECT_NEAR(bigBound, clbkHelper.js.position[i], 0.02);
387 TEST_F ( testSendAction, sendTipFlex ) {
389 auto tipFlexMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::TipFlex, folderForActions +
"/primitives/");
391 if (tipFlexMap.size()>0) {
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)));
403 auto jic = action->getJointsInvolvedCount();
404 std::string jointInvolved;
405 for (
auto it : jic) {
406 if (it.second == 1 ){
407 jointInvolved = it.first;
414 double bigBound = parserMoveIt->getBiggerBoundFromZero(jointInvolved).at(0);
416 for (
int k = 0; k<clbkHelper.js.name.size(); k++) {
418 if (clbkHelper.js.name[i].compare(jointInvolved) == 0 ) {
419 EXPECT_NEAR(bigBound, clbkHelper.js.position[i], 0.02);
427 TEST_F ( testSendAction, sendFingFlex ) {
429 auto fingFlexMap = actionsFinder->findTrig (ROSEE::ActionPrimitive::Type::FingFlex, folderForActions +
"/primitives/");
431 if (fingFlexMap.size()>0) {
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)));
443 auto jic = action->getJointsInvolvedCount();
444 std::string jointInvolved;
445 for (
auto it : jic) {
446 if (it.second == 1 ){
447 jointInvolved = it.first;
454 double bigBound = parserMoveIt->getBiggerBoundFromZero(jointInvolved).at(0);
456 for (
int k = 0; k<clbkHelper.js.name.size(); k++) {
458 if (clbkHelper.js.name[i].compare(jointInvolved) == 0 ) {
459 EXPECT_NEAR(bigBound, clbkHelper.js.position[i], 0.02);
468 TEST_F ( testSendAction, sendPinches ) {
470 auto pinchTightMap = actionsFinder->findPinch(folderForActions +
"/primitives/").first;
472 if (pinchTightMap.size()>0){
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)));
484 TEST_F ( testSendAction, sendPinchLoose ) {
486 auto pinchLooseMap = actionsFinder->findPinch(folderForActions +
"/primitives/").second;
488 if (pinchLooseMap.size()>0){
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)));
500 TEST_F (testSendAction, sendMultiplePinchStrict ) {
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 );
508 if (multiplePinchMapStrict.size() > 0 ) {
509 multiplePinchMapsStrict.push_back (multiplePinchMapStrict);
513 if ( multiplePinchMapsStrict.size() > 0 ) {
515 srand((
unsigned int)time(NULL));
516 int j = rand() % multiplePinchMapsStrict.size();
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)));
530 TEST_F (testSendAction, sendMultiplePinchNoStrict ) {
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 );
538 if (multiplePinchMapNOStrict.size() > 0 ) {
539 multiplePinchMapsNOStrict.push_back (multiplePinchMapNOStrict);
544 if ( multiplePinchMapsNOStrict.size() > 0 ) {
546 srand((
unsigned int)time(NULL));
547 int j = rand() % multiplePinchMapsNOStrict.size();
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)));
561 TEST_F (testSendAction, sendSingleJointMultipleTips ) {
563 std::vector < ROSEE::ActionSingleJointMultipleTips::Map > singleJointMultipleTipsMaps;
565 for (
int i = 1; i<=ee->getFingersNumber(); i++) {
567 std::map < std::string, ROSEE::ActionSingleJointMultipleTips> singleJointMultipleTipsMap =
568 actionsFinder->findSingleJointMultipleTips (i, folderForActions +
"/primitives/") ;
570 if (singleJointMultipleTipsMap.size()>0) {
571 singleJointMultipleTipsMaps.push_back(singleJointMultipleTipsMap);
576 if ( singleJointMultipleTipsMaps.size() > 0 ) {
578 srand((
unsigned int)time(NULL));
579 int j = rand() % singleJointMultipleTipsMaps.size();
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)));
596 TEST_F (testSendAction, sendComposedAction ) {
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;
604 for (
auto trig : trigMap) {
605 std::shared_ptr <ROSEE::ActionPrimitive> pointer =
606 std::make_shared <ROSEE::ActionTrig> ( trig.second );
608 double lower_bound = 0;
609 double upper_bound = 0.8;
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 ));
616 for (
auto trig : fingFlexMap) {
617 std::shared_ptr <ROSEE::ActionPrimitive> pointer =
618 std::make_shared <ROSEE::ActionTrig> ( trig.second );
620 double lower_bound = 0;
621 double upper_bound = 0.7;
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 ));
628 for (
auto pinch : pinchTightMap) {
630 std::shared_ptr <ROSEE::ActionPrimitive> pointer =
631 std::make_shared <ROSEE::ActionPinchTight> ( pinch.second );
633 double lower_bound = 0;
634 double upper_bound = 0.29;
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 ));
641 if (actionComposed.numberOfInnerActions() > 0) {
642 ROSEE::Action::Ptr actionPtr = std::make_shared<ROSEE::ActionGeneric>(actionComposed);
645 yamlWorker.createYamlFile( actionPtr.get(), folderForActions +
"/generics/" );
647 sendAndTest(actionPtr, 0.95);
653 TEST_F (testSendAction, sendTimedAction ) {
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/");
661 if (trigMap.size()>0) {
662 std::shared_ptr <ROSEE::ActionPrimitive> pointer =
663 std::make_shared <ROSEE::ActionTrig> ( trigMap.begin()->second );
665 double lower_bound = 0;
666 double upper_bound = 0.8;
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));
673 if (tipFlexMap.size() > 0) {
674 std::shared_ptr <ROSEE::ActionPrimitive> pointer =
675 std::make_shared <ROSEE::ActionTrig> ( tipFlexMap.rbegin()->second);
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));
685 if (! pinchMaps.first.empty()) {
687 std::shared_ptr <ROSEE::ActionPrimitive> pointer =
688 std::make_shared <ROSEE::ActionPinchTight> ( pinchMaps.first.begin()->second );
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));
698 if (! pinchMaps.second.empty()) {
699 std::shared_ptr <ROSEE::ActionPrimitive> pointer =
700 std::make_shared <ROSEE::ActionPinchLoose> ( pinchMaps.second.rbegin()->second );
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));
710 if (actionTimed.getInnerActionsNames().size() > 0) {
714 yamlWorker.createYamlFile( actionPtr.get(), folderForActions +
"/timeds/" );
716 sendAndTest(actionPtr);
725 int main (
int argc,
char **argv ) {
729 std::cout <<
"[TEST ERROR] Insert hand name as argument" << std::endl;
736 if(setenv(
"ROS_MASTER_URI",
"http://localhost:11322", 1) == -1)
743 std::unique_ptr<ROSEE::TestUtils::Process> roscore;
749 std::cout <<
"[TEST ERROR] Prepare Function failed" << std::endl;
753 ::testing::InitGoogleTest ( &argc, argv );
754 return RUN_ALL_TESTS();