Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #include <srdf/model.h>
00038 #include <urdf/model.h>
00039 #include <gtest/gtest.h>
00040 
00041 TEST(SRDF, Simple)
00042 {
00043     urdf::Model u;
00044     srdf::Model s;
00045     EXPECT_TRUE(u.initFile("test/res/pr2_desc.urdf"));
00046 
00047     EXPECT_TRUE(s.initFile(u, "test/res/pr2_desc.1.srdf"));
00048     EXPECT_TRUE(s.getVirtualJoints().size() == 0);
00049     EXPECT_TRUE(s.getGroups().size() == 0);
00050     EXPECT_TRUE(s.getGroupStates().size() == 0);
00051     EXPECT_TRUE(s.getDisabledCollisions().empty());
00052     EXPECT_TRUE(s.getEndEffectors().size() == 0);
00053 
00054     EXPECT_TRUE(s.initFile(u, "test/res/pr2_desc.2.srdf"));
00055     EXPECT_TRUE(s.getVirtualJoints().size() == 1);
00056     EXPECT_TRUE(s.getGroups().size() == 1);
00057     EXPECT_TRUE(s.getGroupStates().size() == 0);
00058     EXPECT_TRUE(s.getDisabledCollisions().empty());
00059     EXPECT_TRUE(s.getEndEffectors().size() == 0);
00060 
00061     EXPECT_TRUE(s.initFile(u, "test/res/pr2_desc.1.srdf"));
00062     EXPECT_TRUE(s.getVirtualJoints().size() == 0);
00063     EXPECT_TRUE(s.getGroups().size() == 0);
00064     EXPECT_TRUE(s.getGroupStates().size() == 0);
00065     EXPECT_TRUE(s.getDisabledCollisions().empty());
00066     EXPECT_TRUE(s.getEndEffectors().size() == 0);
00067 }
00068 
00069 TEST(SRDF, Complex)
00070 {
00071     urdf::Model u;
00072     srdf::Model s;
00073     EXPECT_TRUE(u.initFile("test/res/pr2_desc.urdf"));
00074 
00075     EXPECT_TRUE(s.initFile(u, "test/res/pr2_desc.3.srdf"));
00076     EXPECT_TRUE(s.getVirtualJoints().size() == 1);
00077     EXPECT_TRUE(s.getGroups().size() == 7);
00078     EXPECT_TRUE(s.getGroupStates().size() == 2);
00079     EXPECT_TRUE(s.getDisabledCollisions().size() == 2);
00080     EXPECT_TRUE(s.getEndEffectors().size() == 2);
00081 
00082     EXPECT_EQ(s.getVirtualJoints()[0].name_, "world_joint");
00083     EXPECT_EQ(s.getVirtualJoints()[0].type_, "planar");
00084     for (std::size_t i = 0 ; i < s.getGroups().size() ; ++i)
00085     {
00086         if (s.getGroups()[i].name_ == "left_arm" || s.getGroups()[i].name_ == "right_arm")
00087             EXPECT_TRUE(s.getGroups()[i].chains_.size() == 1);
00088         if (s.getGroups()[i].name_ == "arms")
00089             EXPECT_TRUE(s.getGroups()[i].subgroups_.size() == 2);
00090         if (s.getGroups()[i].name_ == "base")
00091             EXPECT_TRUE(s.getGroups()[i].joints_.size() == 1);
00092         if (s.getGroups()[i].name_ == "l_end_effector" || s.getGroups()[i].name_ == "r_end_effector")
00093         {
00094             EXPECT_TRUE(s.getGroups()[i].links_.size() == 1);
00095             EXPECT_TRUE(s.getGroups()[i].joints_.size() == 9);
00096         }
00097         if (s.getGroups()[i].name_ == "whole_body")
00098         {
00099             EXPECT_TRUE(s.getGroups()[i].joints_.size() == 1);
00100             EXPECT_TRUE(s.getGroups()[i].subgroups_.size() == 2);
00101         }
00102     }
00103     int index = 0;
00104     if (s.getGroupStates()[0].group_ != "arms")
00105         index = 1;
00106 
00107     EXPECT_EQ(s.getGroupStates()[index].group_, "arms");
00108     EXPECT_EQ(s.getGroupStates()[index].name_, "tuck_arms");
00109     EXPECT_EQ(s.getGroupStates()[1-index].group_, "base");
00110     EXPECT_EQ(s.getGroupStates()[1-index].name_, "home");
00111 
00112     const std::vector<double> &v = s.getGroupStates()[index].joint_values_.find("l_shoulder_pan_joint")->second;
00113     EXPECT_EQ(v.size(), 1);
00114     EXPECT_EQ(v[0], 0.2);
00115     const std::vector<double> &w = s.getGroupStates()[1-index].joint_values_.find("world_joint")->second;
00116     EXPECT_EQ(w.size(), 3);
00117     EXPECT_EQ(w[0], 0.4);
00118     EXPECT_EQ(w[1], 0);
00119     EXPECT_EQ(w[2], -1);
00120 
00121 
00122     index = (s.getEndEffectors()[0].name_[0] == 'r') ? 0 : 1;
00123     EXPECT_EQ(s.getEndEffectors()[index].name_, "r_end_effector");
00124     EXPECT_EQ(s.getEndEffectors()[index].component_group_, "r_end_effector");
00125     EXPECT_EQ(s.getEndEffectors()[index].parent_link_, "r_wrist_roll_link");
00126 }
00127 
00128 int main(int argc, char **argv)
00129 {
00130     testing::InitGoogleTest(&argc, argv);
00131     return RUN_ALL_TESTS();
00132 }