39 #include <urdf_parser/urdf_parser.h>
42 #include <gtest/gtest.h>
44 #ifndef TEST_RESOURCE_LOCATION
45 #define TEST_RESOURCE_LOCATION "."
52 backup_ = setlocale(LC_ALL,
nullptr);
53 setlocale(LC_ALL, name);
57 setlocale(LC_ALL,
backup_.c_str());
62 urdf::ModelInterfaceSharedPtr
loadURDF(
const std::string& filename)
67 std::fstream xml_file(filename.c_str(), std::fstream::in);
68 if (xml_file.is_open())
70 while (xml_file.good())
73 std::getline(xml_file, line);
81 throw std::runtime_error(
"Could not open file " + filename +
" for parsing.");
82 return urdf::ModelInterfaceSharedPtr();
90 ASSERT_TRUE(u != NULL);
93 EXPECT_TRUE(
s.getVirtualJoints().size() == 0);
94 EXPECT_TRUE(
s.getGroups().size() == 0);
95 EXPECT_TRUE(
s.getGroupStates().size() == 0);
96 EXPECT_TRUE(
s.getDisabledCollisionPairs().empty());
97 EXPECT_TRUE(
s.getEnabledCollisionPairs().empty());
98 EXPECT_TRUE(
s.getEndEffectors().size() == 0);
101 EXPECT_TRUE(
s.getVirtualJoints().size() == 1);
102 EXPECT_TRUE(
s.getGroups().size() == 1);
103 EXPECT_TRUE(
s.getGroupStates().size() == 0);
104 EXPECT_TRUE(
s.getDisabledCollisionPairs().empty());
105 EXPECT_TRUE(
s.getEnabledCollisionPairs().empty());
106 EXPECT_TRUE(
s.getEndEffectors().size() == 0);
109 EXPECT_TRUE(
s.getVirtualJoints().size() == 0);
110 EXPECT_TRUE(
s.getGroups().size() == 0);
111 EXPECT_TRUE(
s.getGroupStates().size() == 0);
112 EXPECT_TRUE(
s.getDisabledCollisionPairs().empty());
113 EXPECT_TRUE(
s.getEnabledCollisionPairs().empty());
114 EXPECT_TRUE(
s.getEndEffectors().size() == 0);
121 EXPECT_TRUE(u != NULL);
124 EXPECT_TRUE(
s.getVirtualJoints().size() == 1);
125 EXPECT_TRUE(
s.getGroups().size() == 7);
126 EXPECT_TRUE(
s.getGroupStates().size() == 2);
127 EXPECT_TRUE(
s.getDisabledCollisionPairs().size() == 2);
128 EXPECT_TRUE(
s.getDisabledCollisionPairs()[0].reason_ ==
"adjacent");
129 EXPECT_TRUE(
s.getEndEffectors().size() == 2);
131 EXPECT_TRUE(
s.getVirtualJoints()[0].name_ ==
"world_joint");
132 EXPECT_TRUE(
s.getVirtualJoints()[0].type_ ==
"planar");
133 for (std::size_t i = 0; i <
s.getGroups().size(); ++i)
135 if (
s.getGroups()[i].name_ ==
"left_arm" ||
s.getGroups()[i].name_ ==
"right_arm")
137 EXPECT_TRUE(
s.getGroups()[i].chains_.size() == 1);
139 if (
s.getGroups()[i].name_ ==
"arms")
141 EXPECT_TRUE(
s.getGroups()[i].subgroups_.size() == 2);
143 if (
s.getGroups()[i].name_ ==
"base")
145 EXPECT_TRUE(
s.getGroups()[i].joints_.size() == 1);
147 if (
s.getGroups()[i].name_ ==
"l_end_effector" ||
s.getGroups()[i].name_ ==
"r_end_effector")
149 EXPECT_TRUE(
s.getGroups()[i].links_.size() == 1);
150 EXPECT_TRUE(
s.getGroups()[i].joints_.size() == 9);
152 if (
s.getGroups()[i].name_ ==
"whole_body")
154 EXPECT_TRUE(
s.getGroups()[i].joints_.size() == 1);
155 EXPECT_TRUE(
s.getGroups()[i].subgroups_.size() == 2);
159 if (
s.getGroupStates()[0].group_ !=
"arms")
162 EXPECT_TRUE(
s.getGroupStates()[index].group_ ==
"arms");
163 EXPECT_TRUE(
s.getGroupStates()[index].name_ ==
"tuck_arms");
164 EXPECT_TRUE(
s.getGroupStates()[1 - index].group_ ==
"base");
165 EXPECT_TRUE(
s.getGroupStates()[1 - index].name_ ==
"home");
167 const std::vector<double>& v =
s.getGroupStates()[index].joint_values_.find(
"l_shoulder_pan_joint")->second;
168 EXPECT_EQ(v.size(), 1u);
169 EXPECT_EQ(v[0], 0.2);
170 const std::vector<double>& w =
s.getGroupStates()[1 - index].joint_values_.find(
"world_joint")->second;
171 EXPECT_EQ(w.size(), 3u);
172 EXPECT_EQ(w[0], 0.4);
176 index = (
s.getEndEffectors()[0].name_[0] ==
'r') ? 0 : 1;
177 EXPECT_TRUE(
s.getEndEffectors()[index].name_ ==
"r_end_effector");
178 EXPECT_TRUE(
s.getEndEffectors()[index].component_group_ ==
"r_end_effector");
179 EXPECT_TRUE(
s.getEndEffectors()[index].parent_link_ ==
"r_wrist_roll_link");
183 EXPECT_EQ(gripper_props.size(), 0u);
188 EXPECT_EQ(made_up_props.size(), 0u);
191 ASSERT_EQ(world_props.size(), 1u);
192 EXPECT_EQ(world_props.at(
"angular_distance_weight"),
"0.5");
199 ASSERT_TRUE(u !=
nullptr);
206 std::string xml_content;
207 std::fstream xml_file(filename.c_str(), std::fstream::in);
208 ASSERT_TRUE(xml_file.is_open());
209 while (xml_file.good())
212 std::getline(xml_file, line);
213 xml_content += (line +
"\n");
215 xml_content.erase(xml_content.size() - 1, 1);
221 int main(
int argc,
char** argv)
224 setlocale(LC_ALL,
"");
225 std::cout <<
"Using locale: " << setlocale(LC_ALL,
nullptr) << std::endl;
227 testing::InitGoogleTest(&argc, argv);
228 return RUN_ALL_TESTS();