Skip to content

Commit

Permalink
Fix parser_urdf_TEST
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <michael@openrobotics.org>
  • Loading branch information
mjcarroll committed May 27, 2020
1 parent bb017c9 commit e65a00d
Showing 1 changed file with 54 additions and 34 deletions.
88 changes: 54 additions & 34 deletions src/parser_urdf_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,11 @@ std::string convertUrdfStrToSdfStr(const std::string &_urdf)
SDF_SUPPRESS_DEPRECATED_BEGIN
sdf::URDF2SDF parser_;
SDF_SUPPRESS_DEPRECATED_END
tinyxml2::XMLDocument sdf_result = parser_.InitModelString(_urdf);
tinyxml2::XMLDocument sdf_result;
parser_.InitModelString(_urdf, &sdf_result);
tinyxml2::XMLPrinter printer;
sdf_result.Accept(&printer);
return printer.Str();
return printer.CStr();
}

/////////////////////////////////////////////////
Expand All @@ -59,7 +60,8 @@ TEST(URDFParser, InitModelDoc_EmptyDoc_NoThrow)
ASSERT_NO_THROW(
tinyxml2::XMLDocument doc = tinyxml2::XMLDocument();
sdf::URDF2SDF parser_;
tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc);
tinyxml2::XMLDocument sdf_result;
parser_.InitModelDoc(&doc, &sdf_result);
); // NOLINT(whitespace/parens)
SDF_SUPPRESS_DEPRECATED_END
}
Expand All @@ -73,7 +75,8 @@ TEST(URDFParser, InitModelDoc_BasicModel_NoThrow)
tinyxml2::XMLDocument doc;
doc.Parse(getMinimalUrdfTxt().c_str());
sdf::URDF2SDF parser_;
tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc);
tinyxml2::XMLDocument sdf_result;
parser_.InitModelDoc(&doc, &sdf_result);
); // NOLINT(whitespace/parens)
SDF_SUPPRESS_DEPRECATED_END
}
Expand All @@ -87,9 +90,13 @@ TEST(URDFParser, ParseResults_BasicModel_ParseEqualToModel)
SDF_SUPPRESS_DEPRECATED_BEGIN
sdf::URDF2SDF parser_;
SDF_SUPPRESS_DEPRECATED_END
tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc);
std::string sdf_result_str;
sdf_result_str << sdf_result;

tinyxml2::XMLDocument sdf_result;
parser_.InitModelDoc(&doc, &sdf_result);

tinyxml2::XMLPrinter printer;
sdf_result.Print(&printer);
std::string sdf_result_str = printer.CStr();

// SDF -> SDF
std::ostringstream stream;
Expand All @@ -99,8 +106,10 @@ TEST(URDFParser, ParseResults_BasicModel_ParseEqualToModel)
<< "</sdf>";
tinyxml2::XMLDocument sdf_doc;
sdf_doc.Parse(stream.str().c_str());
std::string sdf_same_result_str;
sdf_same_result_str << sdf_doc;

tinyxml2::XMLPrinter printer2;
sdf_doc.Print(&printer2);
std::string sdf_same_result_str = printer2.CStr();

ASSERT_EQ(sdf_same_result_str, sdf_result_str);
}
Expand All @@ -118,7 +127,8 @@ TEST(URDFParser, ParseRobotOriginXYZBlank)
SDF_SUPPRESS_DEPRECATED_BEGIN
sdf::URDF2SDF parser_;
SDF_SUPPRESS_DEPRECATED_END
tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc);
tinyxml2::XMLDocument sdf_result;
parser_.InitModelDoc(&doc, &sdf_result);
tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement("sdf");
ASSERT_NE(nullptr, sdf);
tinyxml2::XMLElement *model = sdf->FirstChildElement("model");
Expand All @@ -140,7 +150,8 @@ TEST(URDFParser, ParseRobotOriginRPYBlank)
sdf::URDF2SDF parser_;
SDF_SUPPRESS_DEPRECATED_END
doc.Parse(stream.str().c_str());
tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc);
tinyxml2::XMLDocument sdf_result;
parser_.InitModelDoc(&doc, &sdf_result);
tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement("sdf");
ASSERT_NE(nullptr, sdf);
tinyxml2::XMLElement *model = sdf->FirstChildElement("model");
Expand Down Expand Up @@ -175,7 +186,8 @@ TEST(URDFParser, ParseRobotMaterialBlank)
SDF_SUPPRESS_DEPRECATED_BEGIN
sdf::URDF2SDF parser;
SDF_SUPPRESS_DEPRECATED_END
auto sdfXml = parser.InitModelDoc(&doc);
tinyxml2::XMLDocument sdfXml;
parser.InitModelDoc(&doc, &sdfXml);
auto sdfElem = sdfXml.FirstChildElement("sdf");
ASSERT_NE(nullptr, sdfElem);
auto modelElem = sdfElem->FirstChildElement("model");
Expand Down Expand Up @@ -215,7 +227,10 @@ TEST(URDFParser, ParseRobotMaterialName)
SDF_SUPPRESS_DEPRECATED_BEGIN
sdf::URDF2SDF parser;
SDF_SUPPRESS_DEPRECATED_END
auto sdfXml = parser.InitModelDoc(&doc);

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

auto sdfElem = sdfXml.FirstChildElement("sdf");
ASSERT_NE(nullptr, sdfElem);
auto modelElem = sdfElem->FirstChildElement("model");
Expand Down Expand Up @@ -251,7 +266,8 @@ TEST(URDFParser, ParseRobotOriginInvalidXYZ)
sdf::URDF2SDF parser_;
SDF_SUPPRESS_DEPRECATED_END
doc.Parse(stream.str().c_str());
tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc);
tinyxml2::XMLDocument sdf_result;
parser_.InitModelDoc(&doc, &sdf_result);
tinyxml2::XMLElement *sdf = sdf_result.FirstChildElement("sdf");
ASSERT_NE(nullptr, sdf);
tinyxml2::XMLElement *model = sdf->FirstChildElement("model");
Expand Down Expand Up @@ -314,7 +330,8 @@ TEST(URDFParser, ParseGazeboLinkFactors)
sdf::URDF2SDF parser_;
SDF_SUPPRESS_DEPRECATED_END
doc.Parse(stream.str().c_str());
tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc);
tinyxml2::XMLDocument sdf_result;
parser_.InitModelDoc(&doc, &sdf_result);

tinyxml2::XMLElement *tmp = sdf_result.FirstChildElement("sdf");
ASSERT_NE(nullptr, tmp);
Expand All @@ -323,12 +340,12 @@ TEST(URDFParser, ParseGazeboLinkFactors)

for (i = 0; i < it->second.size() - 1; ++i)
{
tmp = tmp->FirstChildElement(it->second[i]);
tmp = tmp->FirstChildElement(it->second[i].c_str());
ASSERT_NE(nullptr, tmp);
}

// For the last element, check that it is exactly what we expect
EXPECT_EQ(tmp->FirstChild()->ValueStr(), it->second[i]);
EXPECT_EQ(tmp->FirstChild()->Value(), it->second[i]);
}
}

Expand All @@ -352,7 +369,8 @@ TEST(URDFParser, ParseGazeboInvalidDampingFactor)
sdf::URDF2SDF parser_;
SDF_SUPPRESS_DEPRECATED_END
doc.Parse(stream.str().c_str());
ASSERT_THROW(tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc),
tinyxml2::XMLDocument sdf_result;
ASSERT_THROW(parser_.InitModelDoc(&doc, &sdf_result),
std::invalid_argument);
}

Expand Down Expand Up @@ -423,7 +441,8 @@ TEST(URDFParser, ParseGazeboJointElements)
sdf::URDF2SDF parser_;
SDF_SUPPRESS_DEPRECATED_END
doc.Parse(stream.str().c_str());
tinyxml2::XMLDocument sdf_result = parser_.InitModelDoc(&doc);
tinyxml2::XMLDocument sdf_result;
parser_.InitModelDoc(&doc, &sdf_result);

tinyxml2::XMLElement *tmp = sdf_result.FirstChildElement("sdf");
ASSERT_NE(nullptr, tmp);
Expand All @@ -432,12 +451,12 @@ TEST(URDFParser, ParseGazeboJointElements)

for (i = 0; i < it->second.size() - 1; ++i)
{
tmp = tmp->FirstChildElement(it->second[i]);
tmp = tmp->FirstChildElement(it->second[i].c_str());
ASSERT_NE(nullptr, tmp);
}

// For the last element, check that it is exactly what we expect
EXPECT_EQ(tmp->FirstChild()->ValueStr(), it->second[i]);
EXPECT_STREQ(tmp->FirstChild()->Value(), it->second[i].c_str());
}
}

Expand Down Expand Up @@ -722,7 +741,7 @@ TEST(URDFParser, CheckJointTransform)
<child>link1</child>
</joint>
<link name="link1">
<pose relative_to="jointw_1" />
<pose relative_to="jointw_1"/>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1</mass>
Expand All @@ -742,12 +761,12 @@ TEST(URDFParser, CheckJointTransform)
<child>link2</child>
<axis>
<xyz>1 0 0</xyz>
<limit />
<dynamics />
<limit/>
<dynamics/>
</axis>
</joint>
<link name="link2">
<pose relative_to="joint1_2" />
<pose relative_to="joint1_2"/>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1</mass>
Expand All @@ -767,12 +786,12 @@ TEST(URDFParser, CheckJointTransform)
<child>link3</child>
<axis>
<xyz>1 0 0</xyz>
<limit />
<dynamics />
<limit/>
<dynamics/>
</axis>
</joint>
<link name="link3">
<pose relative_to="joint2_3" />
<pose relative_to="joint2_3"/>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1</mass>
Expand Down Expand Up @@ -810,19 +829,20 @@ TEST(URDFParser, OutputPrecision)
SDF_SUPPRESS_DEPRECATED_BEGIN
sdf::URDF2SDF parser;
SDF_SUPPRESS_DEPRECATED_END
tinyxml2::XMLDocument sdfResult = parser.InitModelString(str);
tinyxml2::XMLDocument sdfResult;
parser.InitModelString(str, &sdfResult);

auto root = sdfResult.RootElement();
auto model = root->FirstChild("model");
auto model = root->FirstChildElement("model");
ASSERT_NE(nullptr, model);
auto link = model->FirstChild("link");
auto link = model->FirstChildElement("link");
ASSERT_NE(nullptr, link);
auto inertial = link->FirstChild("inertial");
auto inertial = link->FirstChildElement("inertial");
ASSERT_NE(nullptr, inertial);
auto pose = inertial->FirstChild("pose");
auto pose = inertial->FirstChildElement("pose");
ASSERT_NE(nullptr, pose);
ASSERT_NE(nullptr, pose->FirstChild());
std::string poseTxt = pose->FirstChild()->ValueStr();
std::string poseTxt = pose->FirstChild()->Value();
EXPECT_FALSE(poseTxt.empty());

std::string poseValues[6];
Expand Down

0 comments on commit e65a00d

Please sign in to comment.