Skip to content

Commit

Permalink
Add test case for URDF Gazebo extensions
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <michael@openrobotics.org>
  • Loading branch information
mjcarroll committed Sep 9, 2020
1 parent 27d6bd0 commit 2721714
Showing 1 changed file with 76 additions and 0 deletions.
76 changes: 76 additions & 0 deletions src/parser_urdf_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -852,6 +852,82 @@ TEST(URDFParser, OutputPrecision)
EXPECT_EQ("0", poseValues[5]);
}

/////////////////////////////////////////////////
TEST(URDFParser, ParseWhitespace)
{
std::string str = R"(<robot name="test">
<link name="link">
<inertial>
<mass value="0.1" />
<origin rpy="1.570796326794895 0 0" xyz="0.123456789123456 0 0.0" />
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01" />
</inertial>
<visual>
<geometry>
<sphere radius="1.0"/>
</geometry>
</visual>
<collision>
<geometry>
<sphere radius="1.0"/>
</geometry>
</collision>
</link>
<gazebo reference="link">
<material>
Gazebo/Orange
</material>
<mu1>
100
</mu1>
<mu2>
1000
</mu2>
</gazebo>"
</robot>)";
tinyxml2::XMLDocument doc;
doc.Parse(str.c_str());

sdf::URDF2SDF parser;
tinyxml2::XMLDocument sdfXml;
parser.InitModelDoc(&doc, &sdfXml);

auto root = sdfXml.RootElement();
ASSERT_NE(nullptr, root);
auto modelElem = root->FirstChildElement("model");
ASSERT_NE(nullptr, modelElem);
auto linkElem = modelElem->FirstChildElement("link");
ASSERT_NE(nullptr, linkElem);
auto visualElem = linkElem->FirstChildElement("visual");
ASSERT_NE(nullptr, visualElem);
auto collisionElem = linkElem->FirstChildElement("collision");
ASSERT_NE(nullptr, collisionElem);

auto materialElem = visualElem->FirstChildElement("material");
ASSERT_NE(nullptr, materialElem);
auto scriptElem = materialElem->FirstChildElement("script");
ASSERT_NE(nullptr, scriptElem);
auto nameElem = scriptElem->FirstChildElement("name");
ASSERT_NE(nullptr, nameElem);
EXPECT_EQ("Gazebo/Orange", std::string(nameElem->GetText()));

auto surfaceElem = collisionElem->FirstChildElement("surface");
ASSERT_NE(nullptr, surfaceElem);
auto frictionElem = surfaceElem->FirstChildElement("friction");
ASSERT_NE(nullptr, frictionElem);
auto odeElem = frictionElem->FirstChildElement("ode");
ASSERT_NE(nullptr, odeElem);
auto muElem = odeElem->FirstChildElement("mu");
ASSERT_NE(nullptr, muElem);
auto mu2Elem = odeElem->FirstChildElement("mu2");
ASSERT_NE(nullptr, mu2Elem);

EXPECT_EQ("100", std::string(muElem->GetText()));
EXPECT_EQ("1000", std::string(mu2Elem->GetText()));
}

/////////////////////////////////////////////////
/// Main
int main(int argc, char **argv)
Expand Down

0 comments on commit 2721714

Please sign in to comment.