Skip to content

Commit

Permalink
Fix whitespace preservation behavior with TinyXML2 (#359)
Browse files Browse the repository at this point in the history
This addresses a change in how whitespace is preserved/collapsed between
tinyxml and tinyxml2. The change primarily impacts SDF files that have
newlines, which is frequently done for aesthetics with include uris.

In this case, we use an alternate constructor for TinyXML2 that will
collapse whitespace by default.

Note that there is a performance impact of this behavior, which causes
the parsing to run essentially twice.

More information on the behavior may be found here: https://leethomason.github.io/tinyxml2/

Closes #322

Signed-off-by: Michael Carroll <michael@openrobotics.org>

Co-authored-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
2 people authored and brawner committed Dec 11, 2020
1 parent 477635a commit 2a4c909
Show file tree
Hide file tree
Showing 5 changed files with 210 additions and 13 deletions.
42 changes: 29 additions & 13 deletions src/parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -81,11 +81,27 @@ bool readStringInternal(
const bool _convert,
Errors &_errors);

//////////////////////////////////////////////////
/// \brief Internal helper for creating XMLDocuments
///
/// This creates an XMLDocument with whitespace collapse
/// on, which is not default behavior in tinyxml2.
/// This function is to consolidate locations it is used.
///
/// There is a performance impact associated with collapsing whitespace.
///
/// For more information on the behavior and performance implications,
/// consult the TinyXML2 documentation: https://leethomason.github.io/tinyxml2/
inline auto makeSdfDoc()
{
return tinyxml2::XMLDocument(true, tinyxml2::COLLAPSE_WHITESPACE);
}

//////////////////////////////////////////////////
template <typename TPtr>
static inline bool _initFile(const std::string &_filename, TPtr _sdf)
{
tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
if (tinyxml2::XML_SUCCESS != xmlDoc.LoadFile(_filename.c_str()))
{
sdferr << "Unable to load file["
Expand All @@ -100,7 +116,7 @@ static inline bool _initFile(const std::string &_filename, TPtr _sdf)
bool init(SDFPtr _sdf)
{
std::string xmldata = SDF::EmbeddedSpec("root.sdf", false);
tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
xmlDoc.Parse(xmldata.c_str());
return initDoc(&xmlDoc, _sdf);
}
Expand All @@ -111,7 +127,7 @@ bool initFile(const std::string &_filename, SDFPtr _sdf)
std::string xmldata = SDF::EmbeddedSpec(_filename, true);
if (!xmldata.empty())
{
tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
xmlDoc.Parse(xmldata.c_str());
return initDoc(&xmlDoc, _sdf);
}
Expand All @@ -124,7 +140,7 @@ bool initFile(const std::string &_filename, ElementPtr _sdf)
std::string xmldata = SDF::EmbeddedSpec(_filename, true);
if (!xmldata.empty())
{
tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
xmlDoc.Parse(xmldata.c_str());
return initDoc(&xmlDoc, _sdf);
}
Expand All @@ -134,7 +150,7 @@ bool initFile(const std::string &_filename, ElementPtr _sdf)
//////////////////////////////////////////////////
bool initString(const std::string &_xmlString, SDFPtr _sdf)
{
tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
if (xmlDoc.Parse(_xmlString.c_str()))
{
sdferr << "Failed to parse string as XML: " << xmlDoc.ErrorStr() << '\n';
Expand Down Expand Up @@ -393,7 +409,7 @@ bool readFileWithoutConversion(
bool readFileInternal(const std::string &_filename, SDFPtr _sdf,
const bool _convert, Errors &_errors)
{
tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
std::string filename = sdf::findFile(_filename, true, true);

if (filename.empty())
Expand Down Expand Up @@ -429,7 +445,7 @@ bool readFileInternal(const std::string &_filename, SDFPtr _sdf,
else if (URDF2SDF::IsURDF(filename))
{
URDF2SDF u2g;
tinyxml2::XMLDocument doc;
auto doc = makeSdfDoc();
u2g.InitModelFile(filename, &doc);
if (sdf::readDoc(&doc, _sdf, "urdf file", _convert, _errors))
{
Expand Down Expand Up @@ -476,7 +492,7 @@ bool readStringWithoutConversion(
bool readStringInternal(const std::string &_xmlString, SDFPtr _sdf,
const bool _convert, Errors &_errors)
{
tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
xmlDoc.Parse(_xmlString.c_str());
if (xmlDoc.Error())
{
Expand All @@ -490,7 +506,7 @@ bool readStringInternal(const std::string &_xmlString, SDFPtr _sdf,
else
{
URDF2SDF u2g;
tinyxml2::XMLDocument doc;
auto doc = makeSdfDoc();
u2g.InitModelString(_xmlString, &doc);

if (sdf::readDoc(&doc, _sdf, "urdf string", _convert, _errors))
Expand Down Expand Up @@ -524,7 +540,7 @@ bool readString(const std::string &_xmlString, ElementPtr _sdf)
//////////////////////////////////////////////////
bool readString(const std::string &_xmlString, ElementPtr _sdf, Errors &_errors)
{
tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
xmlDoc.Parse(_xmlString.c_str());
if (xmlDoc.Error())
{
Expand Down Expand Up @@ -773,7 +789,7 @@ std::string getModelFilePath(const std::string &_modelDirPath)
}
}

tinyxml2::XMLDocument configFileDoc;
auto configFileDoc = makeSdfDoc();
if (tinyxml2::XML_SUCCESS != configFileDoc.LoadFile(configFilePath.c_str()))
{
sdferr << "Error parsing XML in file ["
Expand Down Expand Up @@ -1264,7 +1280,7 @@ bool convertFile(const std::string &_filename, const std::string &_version,
return false;
}

tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
if (!xmlDoc.LoadFile(filename.c_str()))
{
// read initial sdf version
Expand Down Expand Up @@ -1309,7 +1325,7 @@ bool convertString(const std::string &_sdfString, const std::string &_version,
return false;
}

tinyxml2::XMLDocument xmlDoc;
auto xmlDoc = makeSdfDoc();
xmlDoc.Parse(_sdfString.c_str());

if (!xmlDoc.Error())
Expand Down
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
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ set(tests
urdf_gazebo_extensions.cc
urdf_joint_parameters.cc
visual_dom.cc
whitespace.cc
world_dom.cc
)

Expand Down
64 changes: 64 additions & 0 deletions test/integration/whitespace.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
/*
* Copyright 2019 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <iostream>
#include <string>
#include <gtest/gtest.h>

#include "sdf/Actor.hh"
#include "sdf/Collision.hh"
#include "sdf/Filesystem.hh"
#include "sdf/Geometry.hh"
#include "sdf/Light.hh"
#include "sdf/Link.hh"
#include "sdf/Mesh.hh"
#include "sdf/Model.hh"
#include "sdf/parser.hh"
#include "sdf/Root.hh"
#include "sdf/SDFImpl.hh"
#include "sdf/Visual.hh"
#include "sdf/World.hh"
#include "test_config.h"

const auto g_testPath = sdf::filesystem::append(PROJECT_SOURCE_PATH, "test");
const auto g_modelsPath =
sdf::filesystem::append(g_testPath, "integration", "model");

/////////////////////////////////////////////////
std::string findFileCb(const std::string &_input)
{
return sdf::filesystem::append(g_testPath, "integration", "model", _input);
}

//////////////////////////////////////////////////
TEST(WhitespaceTest, Whitespace)
{
sdf::setFindCallback(findFileCb);

const auto worldFile =
sdf::filesystem::append(g_testPath, "sdf", "whitespace.sdf");

sdf::Root root;
sdf::Errors errors = root.Load(worldFile);
for (auto e : errors)
std::cout << e.Message() << std::endl;
EXPECT_TRUE(errors.empty());

ASSERT_NE(nullptr, root.Element());
EXPECT_EQ(worldFile, root.Element()->FilePath());
EXPECT_EQ("1.6", root.Element()->OriginalVersion());
}
40 changes: 40 additions & 0 deletions test/sdf/whitespace.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">

<include>
<uri>test_model</uri>
</include>

<include>
<uri>
test_model
</uri>
<name>override_model_name</name>
</include>

<include>
<uri>test_light</uri>
</include>

<include>
<uri>
test_light
</uri>
<name>override_light_name</name>
<pose>4 5 6 0 0 0</pose>
</include>

<include>
<uri>test_actor</uri>
</include>

<include>
<uri>
test_actor
</uri>
<name>override_actor_name</name>
</include>

</world>
</sdf>

0 comments on commit 2a4c909

Please sign in to comment.