1 #include <gtest/gtest.h>
14 class testComposedAction:
public ::testing::Test {
19 testComposedAction() : grasp(
"grasp", true) {
22 virtual ~testComposedAction() {
25 virtual void SetUp()
override {
27 std::shared_ptr <ROSEE::ParserMoveIt> parserMoveIt = std::make_shared <ROSEE::ParserMoveIt> ();
30 ASSERT_TRUE(parserMoveIt->init (
"robot_description",
false)) ;
34 std::string folderForActions =
"ROSEE/actions/" + parserMoveIt->getHandName();
36 trigMap = actionsFinder.findTrig(ROSEE::ActionPrimitive::Type::Trig, folderForActions +
"/primitives/") ;
38 if (trigMap.size() > 0){
39 for (
auto trig : trigMap) {
40 std::shared_ptr <ROSEE::ActionPrimitive> pointer =
41 std::make_shared <ROSEE::ActionTrig> ( trig.second );
42 grasp.sumAction ( pointer );
46 yamlWorker.
createYamlFile (&grasp, folderForActions +
"/generics/");
49 graspParsed = yamlWorker.
parseYamlComposed (folderForActions +
"/generics/grasp.yaml");
54 virtual void TearDown()
override{
57 std::map < std::string , ROSEE::ActionTrig > trigMap;
64 TEST_F ( testComposedAction, checkNumberPrimitives ) {
66 EXPECT_EQ ( grasp.numberOfInnerActions(), grasp.getInnerActionsNames().size() );
68 EXPECT_EQ ( graspParsed.numberOfInnerActions(), graspParsed.getInnerActionsNames().size() );
72 TEST_F ( testComposedAction, checkEmitParse ) {
74 if (trigMap.size() > 0) {
76 EXPECT_EQ (grasp.getName(), graspParsed.getName() );
77 EXPECT_EQ (grasp.getType(), graspParsed.getType() );
78 EXPECT_EQ (grasp.isIndependent(), graspParsed.isIndependent() );
79 EXPECT_EQ (grasp.numberOfInnerActions(), graspParsed.numberOfInnerActions() );
80 EXPECT_EQ (grasp.getFingersInvolved(), graspParsed.getFingersInvolved() );
82 for (
auto joint: grasp.getJointPos() ) {
85 ASSERT_EQ (joint.second.size(), graspParsed.getJointPos().at(joint.first).size() );
87 for (
int j = 0; j < joint.second.size(); ++j ){
88 EXPECT_DOUBLE_EQ ( joint.second.at(j), graspParsed.getJointPos().at(joint.first).at(j) );
92 for (
auto jointCount : grasp.getJointsInvolvedCount()) {
94 EXPECT_EQ ( jointCount.second, graspParsed.getJointsInvolvedCount().at(jointCount.first) );
101 TEST_F ( testComposedAction, checkIndependence ) {
102 if (grasp.isIndependent()) {
103 for (
auto it : grasp.getJointsInvolvedCount() ) {
104 EXPECT_LE ( it.second, 1 );
111 int main (
int argc,
char **argv ) {
115 std::cout <<
"[TEST ERROR] Insert hand name as argument" << std::endl;
120 if(setenv(
"ROS_MASTER_URI",
"http://localhost:11322", 1) == -1)
127 std::unique_ptr<ROSEE::TestUtils::Process> roscore;
132 std::cout <<
"[TEST ERROR] Prepare Funcion failed" << std::endl;
137 ::testing::InitGoogleTest ( &argc, argv );
138 return RUN_ALL_TESTS();