test_parser.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2011, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
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 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


srdf
Author(s): Ioan Sucan
autogenerated on Mon Aug 19 2013 11:02:22