test_parser.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #include <srdfdom/model.h>
38 #include <urdf_parser/urdf_parser.h>
39 #include <fstream>
40 #include <stdexcept>
41 #include <gtest/gtest.h>
42 
43 #ifndef TEST_RESOURCE_LOCATION
44 #define TEST_RESOURCE_LOCATION "."
45 #endif
46 
48 {
49  ScopedLocale(const char* name = "C")
50  {
51  backup_ = setlocale(LC_ALL, nullptr); // store current locale
52  setlocale(LC_ALL, name);
53  }
55  {
56  setlocale(LC_ALL, backup_.c_str()); // restore locale
57  }
58  std::string backup_;
59 };
60 
61 urdf::ModelInterfaceSharedPtr loadURDF(const std::string& filename)
62 {
63  ScopedLocale l("C");
64  // get the entire file
65  std::string xml_string;
66  std::fstream xml_file(filename.c_str(), std::fstream::in);
67  if (xml_file.is_open())
68  {
69  while (xml_file.good())
70  {
71  std::string line;
72  std::getline(xml_file, line);
73  xml_string += (line + "\n");
74  }
75  xml_file.close();
76  return urdf::parseURDF(xml_string);
77  }
78  else
79  {
80  throw std::runtime_error("Could not open file " + filename + " for parsing.");
81  return urdf::ModelInterfaceSharedPtr();
82  }
83 }
84 
85 TEST(TestCpp, testSimple)
86 {
87  srdf::Model s;
88  urdf::ModelInterfaceSharedPtr u = loadURDF(std::string(TEST_RESOURCE_LOCATION) + "/pr2_desc.urdf");
89  ASSERT_TRUE(u != NULL);
90 
91  EXPECT_TRUE(s.initFile(*u, std::string(TEST_RESOURCE_LOCATION) + "/pr2_desc.1.srdf"));
92  EXPECT_TRUE(s.getVirtualJoints().size() == 0);
93  EXPECT_TRUE(s.getGroups().size() == 0);
94  EXPECT_TRUE(s.getGroupStates().size() == 0);
95  EXPECT_TRUE(s.getDisabledCollisionPairs().empty());
96  EXPECT_TRUE(s.getEndEffectors().size() == 0);
97 
98  EXPECT_TRUE(s.initFile(*u, std::string(TEST_RESOURCE_LOCATION) + "/pr2_desc.2.srdf"));
99  EXPECT_TRUE(s.getVirtualJoints().size() == 1);
100  EXPECT_TRUE(s.getGroups().size() == 1);
101  EXPECT_TRUE(s.getGroupStates().size() == 0);
102  EXPECT_TRUE(s.getDisabledCollisionPairs().empty());
103  EXPECT_TRUE(s.getEndEffectors().size() == 0);
104 
105  EXPECT_TRUE(s.initFile(*u, std::string(TEST_RESOURCE_LOCATION) + "/pr2_desc.1.srdf"));
106  EXPECT_TRUE(s.getVirtualJoints().size() == 0);
107  EXPECT_TRUE(s.getGroups().size() == 0);
108  EXPECT_TRUE(s.getGroupStates().size() == 0);
109  EXPECT_TRUE(s.getDisabledCollisionPairs().empty());
110  EXPECT_TRUE(s.getEndEffectors().size() == 0);
111 }
112 
113 TEST(TestCpp, testComplex)
114 {
115  srdf::Model s;
116  urdf::ModelInterfaceSharedPtr u = loadURDF(std::string(TEST_RESOURCE_LOCATION) + "/pr2_desc.urdf");
117  EXPECT_TRUE(u != NULL);
118 
119  EXPECT_TRUE(s.initFile(*u, std::string(TEST_RESOURCE_LOCATION) + "/pr2_desc.3.srdf"));
120  EXPECT_TRUE(s.getVirtualJoints().size() == 1);
121  EXPECT_TRUE(s.getGroups().size() == 7);
122  EXPECT_TRUE(s.getGroupStates().size() == 2);
123  EXPECT_TRUE(s.getDisabledCollisionPairs().size() == 2);
124  EXPECT_TRUE(s.getDisabledCollisionPairs()[0].reason_ == "adjacent");
125  EXPECT_TRUE(s.getEndEffectors().size() == 2);
126 
127  EXPECT_TRUE(s.getVirtualJoints()[0].name_ == "world_joint");
128  EXPECT_TRUE(s.getVirtualJoints()[0].type_ == "planar");
129  for (std::size_t i = 0; i < s.getGroups().size(); ++i)
130  {
131  if (s.getGroups()[i].name_ == "left_arm" || s.getGroups()[i].name_ == "right_arm")
132  EXPECT_TRUE(s.getGroups()[i].chains_.size() == 1);
133  if (s.getGroups()[i].name_ == "arms")
134  EXPECT_TRUE(s.getGroups()[i].subgroups_.size() == 2);
135  if (s.getGroups()[i].name_ == "base")
136  EXPECT_TRUE(s.getGroups()[i].joints_.size() == 1);
137  if (s.getGroups()[i].name_ == "l_end_effector" || s.getGroups()[i].name_ == "r_end_effector")
138  {
139  EXPECT_TRUE(s.getGroups()[i].links_.size() == 1);
140  EXPECT_TRUE(s.getGroups()[i].joints_.size() == 9);
141  }
142  if (s.getGroups()[i].name_ == "whole_body")
143  {
144  EXPECT_TRUE(s.getGroups()[i].joints_.size() == 1);
145  EXPECT_TRUE(s.getGroups()[i].subgroups_.size() == 2);
146  }
147  }
148  int index = 0;
149  if (s.getGroupStates()[0].group_ != "arms")
150  index = 1;
151 
152  EXPECT_TRUE(s.getGroupStates()[index].group_ == "arms");
153  EXPECT_TRUE(s.getGroupStates()[index].name_ == "tuck_arms");
154  EXPECT_TRUE(s.getGroupStates()[1 - index].group_ == "base");
155  EXPECT_TRUE(s.getGroupStates()[1 - index].name_ == "home");
156 
157  const std::vector<double>& v = s.getGroupStates()[index].joint_values_.find("l_shoulder_pan_joint")->second;
158  EXPECT_EQ(v.size(), 1u);
159  EXPECT_EQ(v[0], 0.2);
160  const std::vector<double>& w = s.getGroupStates()[1 - index].joint_values_.find("world_joint")->second;
161  EXPECT_EQ(w.size(), 3u);
162  EXPECT_EQ(w[0], 0.4);
163  EXPECT_EQ(w[1], 0);
164  EXPECT_EQ(w[2], -1);
165 
166  index = (s.getEndEffectors()[0].name_[0] == 'r') ? 0 : 1;
167  EXPECT_TRUE(s.getEndEffectors()[index].name_ == "r_end_effector");
168  EXPECT_TRUE(s.getEndEffectors()[index].component_group_ == "r_end_effector");
169  EXPECT_TRUE(s.getEndEffectors()[index].parent_link_ == "r_wrist_roll_link");
170 }
171 
172 int main(int argc, char** argv)
173 {
174  // use the environment locale so that the unit test can be repeated with various locales easily
175  setlocale(LC_ALL, "");
176  std::cout << "Using locale: " << setlocale(LC_ALL, nullptr) << std::endl;
177 
178  testing::InitGoogleTest(&argc, argv);
179  return RUN_ALL_TESTS();
180 }
#define TEST_RESOURCE_LOCATION
Definition: test_parser.cpp:44
int main(int argc, char **argv)
Representation of semantic information about the robot.
Definition: model.h:52
ScopedLocale(const char *name="C")
Definition: test_parser.cpp:49
const std::vector< VirtualJoint > & getVirtualJoints() const
Get the list of virtual joints defined for this model.
Definition: model.h:221
bool initFile(const urdf::ModelInterface &urdf_model, const std::string &filename)
Load Model given a filename.
Definition: model.cpp:638
XmlRpcServer s
TEST(TestCpp, testSimple)
Definition: test_parser.cpp:85
def xml_string(rootXml, addHeader=True)
const std::vector< Group > & getGroups() const
Get the list of groups defined for this model.
Definition: model.h:215
const std::vector< GroupState > & getGroupStates() const
Get the list of group states defined for this model.
Definition: model.h:233
urdf::ModelInterfaceSharedPtr loadURDF(const std::string &filename)
Definition: test_parser.cpp:61
const std::vector< EndEffector > & getEndEffectors() const
Get the list of end effectors defined for this model.
Definition: model.h:227
std::string backup_
Definition: test_parser.cpp:58
const std::vector< DisabledCollision > & getDisabledCollisionPairs() const
Definition: model.h:206


srdfdom
Author(s): Ioan Sucan , Guillaume Walck
autogenerated on Mon Feb 28 2022 23:49:16