38 #include <urdf_parser/urdf_parser.h> 41 #include <gtest/gtest.h> 43 #ifndef TEST_RESOURCE_LOCATION 44 #define TEST_RESOURCE_LOCATION "." 51 backup_ = setlocale(LC_ALL,
nullptr);
52 setlocale(LC_ALL, name);
56 setlocale(LC_ALL,
backup_.c_str());
61 urdf::ModelInterfaceSharedPtr
loadURDF(
const std::string& filename)
66 std::fstream xml_file(filename.c_str(), std::fstream::in);
67 if (xml_file.is_open())
69 while (xml_file.good())
72 std::getline(xml_file, line);
73 xml_string += (line +
"\n");
76 return urdf::parseURDF(xml_string);
80 throw std::runtime_error(
"Could not open file " + filename +
" for parsing.");
81 return urdf::ModelInterfaceSharedPtr();
89 ASSERT_TRUE(u != NULL);
117 EXPECT_TRUE(u != NULL);
129 for (std::size_t i = 0; i < s.
getGroups().size(); ++i)
132 EXPECT_TRUE(s.
getGroups()[i].chains_.size() == 1);
134 EXPECT_TRUE(s.
getGroups()[i].subgroups_.size() == 2);
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")
139 EXPECT_TRUE(s.
getGroups()[i].links_.size() == 1);
140 EXPECT_TRUE(s.
getGroups()[i].joints_.size() == 9);
142 if (s.
getGroups()[i].name_ ==
"whole_body")
144 EXPECT_TRUE(s.
getGroups()[i].joints_.size() == 1);
145 EXPECT_TRUE(s.
getGroups()[i].subgroups_.size() == 2);
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);
168 EXPECT_TRUE(s.
getEndEffectors()[index].component_group_ ==
"r_end_effector");
169 EXPECT_TRUE(s.
getEndEffectors()[index].parent_link_ ==
"r_wrist_roll_link");
172 int main(
int argc,
char** argv)
175 setlocale(LC_ALL,
"");
176 std::cout <<
"Using locale: " << setlocale(LC_ALL,
nullptr) << std::endl;
178 testing::InitGoogleTest(&argc, argv);
179 return RUN_ALL_TESTS();
#define TEST_RESOURCE_LOCATION
int main(int argc, char **argv)
Representation of semantic information about the robot.
ScopedLocale(const char *name="C")
const std::vector< VirtualJoint > & getVirtualJoints() const
Get the list of virtual joints defined for this model.
bool initFile(const urdf::ModelInterface &urdf_model, const std::string &filename)
Load Model given a filename.
TEST(TestCpp, testSimple)
def xml_string(rootXml, addHeader=True)
const std::vector< Group > & getGroups() const
Get the list of groups defined for this model.
const std::vector< GroupState > & getGroupStates() const
Get the list of group states defined for this model.
urdf::ModelInterfaceSharedPtr loadURDF(const std::string &filename)
const std::vector< EndEffector > & getEndEffectors() const
Get the list of end effectors defined for this model.
const std::vector< DisabledCollision > & getDisabledCollisionPairs() const