Skip to content

Commit

Permalink
Merged in parser_read_convert (pull request gazebosim#647)
Browse files Browse the repository at this point in the history
Parser: add boolean parameter to `readFile` and `readString` for disabling conversion to latest SDF spec.

Approved-by: Addisu Z. Taddese <addisu@openrobotics.org>
Approved-by: Eric Cousineau <eacousineau@gmail.com>
  • Loading branch information
scpeters committed Jan 23, 2020
2 parents 2aa4b72 + f3922b6 commit f39f2f5
Show file tree
Hide file tree
Showing 7 changed files with 234 additions and 5 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ set (SDF_MINOR_VERSION 1)
set (SDF_PATCH_VERSION 0)

set (SDF_VERSION ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION})
set (SDF_VERSION_FULL ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}.${SDF_PATCH_VERSION})
set (SDF_VERSION_FULL ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}.${SDF_PATCH_VERSION}~pre1)

string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
string(REGEX REPLACE "[0-9]+" "" PROJECT_NAME_NO_VERSION ${PROJECT_NAME})
Expand Down
3 changes: 3 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@

### SDFormat 9.1.0 (201X-XX-XX)

1. Parser: add boolean parameter to `readFile` and `readString` for disabling conversion to latest SDF spec.
* [Pull request 647](https://bitbucket.org/osrf/sdformat/pull-requests/647)

1. Added accessors to `ignition::math::[Boxd, Cylinderd, Planed, Sphered]`
in the matching `sdf::[Box, Cylinder, Plane, Sphere]` classes.
* [Pull request 639](https://bitbucket.org/osrf/sdformat/pull-requests/639)
Expand Down
50 changes: 50 additions & 0 deletions include/sdf/parser.hh
Original file line number Diff line number Diff line change
Expand Up @@ -57,12 +57,20 @@ namespace sdf
bool initString(const std::string &_xmlString, SDFPtr _sdf);

/// \brief Populate the SDF values from a file
///
/// This populates the given sdf pointer from a file. If the file is a URDF
/// file it is converted to SDF first. All files are converted to the latest
/// SDF version
/// \param[in] _filename Name of the SDF file
/// \return Populated SDF pointer.
SDFORMAT_VISIBLE
sdf::SDFPtr readFile(const std::string &_filename);

/// \brief Populate the SDF values from a file
///
/// This populates the given sdf pointer from a file. If the file is a URDF
/// file it is converted to SDF first. All files are converted to the latest
/// SDF version
/// \param[in] _filename Name of the SDF file
/// \param[out] _errors Parsing errors will be appended to this variable.
/// \return Populated SDF pointer.
Expand All @@ -81,6 +89,21 @@ namespace sdf
SDFORMAT_VISIBLE
bool readFile(const std::string &_filename, SDFPtr _sdf, Errors &_errors);

/// \brief Populate the SDF values from a file without converting to the
/// latest SDF version
///
/// This populates the given sdf pointer from a file. If the file is a URDF
/// file it is converted to SDF first. This function does not convert the
/// loaded SDF to the latest version. Use this function with care, as it may
/// prevent loading of DOM objects from this SDF object.
/// \param[in] _filename Name of the SDF file
/// \param[in] _sdf Pointer to an SDF object.
/// \param[out] _errors Parsing errors will be appended to this variable.
/// \return True if successful.
SDFORMAT_VISIBLE
bool readFileWithoutConversion(
const std::string &_filename, SDFPtr _sdf, Errors &_errors);

/// \brief Populate the SDF values from a file
///
/// This populates the given sdf pointer from a file. If the file is a URDF
Expand All @@ -97,7 +120,10 @@ namespace sdf
/// This populates the sdf pointer from a string. If the string is a URDF
/// string it is converted to SDF first. All string are converted to the
/// latest SDF version
/// \param[in] _xmlString XML string to be parsed.
/// \param[in] _sdf Pointer to an SDF object.
/// \param[out] _errors Parsing errors will be appended to this variable.
/// \return True if successful.
SDFORMAT_VISIBLE
bool readString(const std::string &_xmlString, SDFPtr _sdf, Errors &_errors);

Expand All @@ -106,6 +132,9 @@ namespace sdf
/// This populates the sdf pointer from a string. If the string is a URDF
/// string it is converted to SDF first. All string are converted to the
/// latest SDF version
/// \param[in] _xmlString XML string to be parsed.
/// \param[in] _sdf Pointer to an SDF object.
/// \return True if successful.
SDFORMAT_VISIBLE
bool readString(const std::string &_xmlString, SDFPtr _sdf);

Expand All @@ -114,16 +143,37 @@ namespace sdf
/// This populates the sdf pointer from a string. If the string is a URDF
/// string it is converted to SDF first. All strings are converted to the
/// latest SDF version
/// \param[in] _xmlString XML string to be parsed.
/// \param[in] _sdf Pointer to an SDF object.
/// \param[out] _errors Parsing errors will be appended to this variable.
/// \return True if successful.
SDFORMAT_VISIBLE
bool readString(const std::string &_xmlString, ElementPtr _sdf,
Errors &_errors);

/// \brief Populate the SDF values from a string without converting to the
/// latest SDF version
///
/// This populates the sdf pointer from a string. If the string is a URDF
/// file it is converted to SDF first. This function does not convert the
/// loaded SDF to the latest version. Use this function with care, as it may
/// prevent loading of DOM objects from this SDF object.
/// \param[in] _xmlString XML string to be parsed.
/// \param[in] _sdf Pointer to an SDF object.
/// \param[out] _errors Parsing errors will be appended to this variable.
/// \return True if successful.
SDFORMAT_VISIBLE
bool readStringWithoutConversion(
const std::string &_xmlString, SDFPtr _sdf, Errors &_errors);

/// \brief Populate the SDF values from a string
///
/// This populates the sdf pointer from a string. If the string is a URDF
/// string it is converted to SDF first. All strings are converted to the
/// latest SDF version
/// \param[in] _xmlString XML string to be parsed.
/// \param[in] _sdf Pointer to an sdf Element object.
/// \return True if successful.
SDFORMAT_VISIBLE
bool readString(const std::string &_xmlString, ElementPtr _sdf);

Expand Down
10 changes: 10 additions & 0 deletions src/Root.cc
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,16 @@ Errors Root::Load(SDFPtr _sdf)
return errors;
}

// Check that the version is 1.7, since this is assumed by the DOM API
if ("1.7" != versionPair.first)
{
errors.push_back(
{ErrorCode::ATTRIBUTE_INVALID,
"SDF version attribute[" + versionPair.first + "] should match "
"the latest version[1.7] when loading DOM objects."});
return errors;
}

this->dataPtr->version = versionPair.first;

// Read all the worlds
Expand Down
71 changes: 67 additions & 4 deletions src/parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,41 @@
namespace sdf
{
inline namespace SDF_VERSION_NAMESPACE {
//////////////////////////////////////////////////
/// \brief Internal helper for readFile, which populates the SDF values
/// from a file
///
/// This populates the given sdf pointer from a file. If the file is a URDF
/// file it is converted to SDF first. Conversion to the latest
/// SDF version is controlled by a function parameter.
/// \param[in] _filename Name of the SDF file
/// \param[in] _sdf Pointer to an SDF object.
/// \param[in] _convert Convert to the latest version if true.
/// \param[out] _errors Parsing errors will be appended to this variable.
/// \return True if successful.
bool readFileInternal(
const std::string &_filename,
SDFPtr _sdf,
const bool _convert,
Errors &_errors);

/// \brief Internal helper for readString, which populates the SDF values
/// from a string
///
/// This populates the sdf pointer from a string. If the string is from a URDF
/// file it is converted to SDF first. Conversion to the latest
/// SDF version is controlled by a function parameter.
/// \param[in] _xmlString XML string to be parsed.
/// \param[in] _sdf Pointer to an SDF object.
/// \param[in] _convert Convert to the latest version if true.
/// \param[out] _errors Parsing errors will be appended to this variable.
/// \return True if successful.
bool readStringInternal(
const std::string &_xmlString,
SDFPtr _sdf,
const bool _convert,
Errors &_errors);

//////////////////////////////////////////////////
template <typename TPtr>
static inline bool _initFile(const std::string &_filename, TPtr _sdf)
Expand Down Expand Up @@ -328,6 +363,20 @@ bool readFile(const std::string &_filename, SDFPtr _sdf)

//////////////////////////////////////////////////
bool readFile(const std::string &_filename, SDFPtr _sdf, Errors &_errors)
{
return readFileInternal(_filename, _sdf, true, _errors);
}

//////////////////////////////////////////////////
bool readFileWithoutConversion(
const std::string &_filename, SDFPtr _sdf, Errors &_errors)
{
return readFileInternal(_filename, _sdf, false, _errors);
}

//////////////////////////////////////////////////
bool readFileInternal(const std::string &_filename, SDFPtr _sdf,
const bool _convert, Errors &_errors)
{
TiXmlDocument xmlDoc;
std::string filename = sdf::findFile(_filename, true, true);
Expand Down Expand Up @@ -356,15 +405,15 @@ bool readFile(const std::string &_filename, SDFPtr _sdf, Errors &_errors)
return false;
}

if (readDoc(&xmlDoc, _sdf, filename, true, _errors))
if (readDoc(&xmlDoc, _sdf, filename, _convert, _errors))
{
return true;
}
else if (sdf::URDF2SDF::IsURDF(filename))
{
sdf::URDF2SDF u2g;
TiXmlDocument doc = u2g.InitModelFile(filename);
if (sdf::readDoc(&doc, _sdf, "urdf file", true, _errors))
if (sdf::readDoc(&doc, _sdf, "urdf file", _convert, _errors))
{
sdfdbg << "parse from urdf file [" << _filename << "].\n";
return true;
Expand Down Expand Up @@ -394,6 +443,20 @@ bool readString(const std::string &_xmlString, SDFPtr _sdf)

//////////////////////////////////////////////////
bool readString(const std::string &_xmlString, SDFPtr _sdf, Errors &_errors)
{
return readStringInternal(_xmlString, _sdf, true, _errors);
}

//////////////////////////////////////////////////
bool readStringWithoutConversion(
const std::string &_filename, SDFPtr _sdf, Errors &_errors)
{
return readStringInternal(_filename, _sdf, false, _errors);
}

//////////////////////////////////////////////////
bool readStringInternal(const std::string &_xmlString, SDFPtr _sdf,
const bool _convert, Errors &_errors)
{
TiXmlDocument xmlDoc;
xmlDoc.Parse(_xmlString.c_str());
Expand All @@ -402,15 +465,15 @@ bool readString(const std::string &_xmlString, SDFPtr _sdf, Errors &_errors)
sdferr << "Error parsing XML from string: " << xmlDoc.ErrorDesc() << '\n';
return false;
}
if (readDoc(&xmlDoc, _sdf, "data-string", true, _errors))
if (readDoc(&xmlDoc, _sdf, "data-string", _convert, _errors))
{
return true;
}
else
{
sdf::URDF2SDF u2g;
TiXmlDocument doc = u2g.InitModelString(_xmlString);
if (sdf::readDoc(&doc, _sdf, "urdf string", true, _errors))
if (sdf::readDoc(&doc, _sdf, "urdf string", _convert, _errors))
{
sdfdbg << "Parsing from urdf.\n";
return true;
Expand Down
27 changes: 27 additions & 0 deletions src/parser_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,33 @@ TEST(Parser, ReusedSDFVersion)
EXPECT_EQ("1.6", sdf->Root()->OriginalVersion());
}

/////////////////////////////////////////////////
TEST(Parser, readFileConversions)
{
std::string pathBase = PROJECT_SOURCE_PATH;
pathBase += "/test/sdf";
const std::string path = pathBase +"/joint_complete.sdf";

// Call readFile API that always converts
{
sdf::SDFPtr sdf = InitSDF();
EXPECT_TRUE(sdf::readFile(path, sdf));
EXPECT_EQ("1.7", sdf->Root()->Get<std::string>("version"));
EXPECT_EQ("1.6", sdf->OriginalVersion());
EXPECT_EQ("1.6", sdf->Root()->OriginalVersion());
}

// Call readFile API that does not convert
{
sdf::Errors errors;
sdf::SDFPtr sdf = InitSDF();
EXPECT_TRUE(sdf::readFileWithoutConversion(path, sdf, errors));
EXPECT_EQ("1.6", sdf->Root()->Get<std::string>("version"));
EXPECT_EQ("1.6", sdf->OriginalVersion());
EXPECT_EQ("1.6", sdf->Root()->OriginalVersion());
}
}

/////////////////////////////////////////////////
TEST(Parser, NameUniqueness)
{
Expand Down
76 changes: 76 additions & 0 deletions test/integration/joint_axis_frame.cc
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,77 @@ TEST(JointAxisFrame, Version_1_4_missing)
ASSERT_NE(nullptr, xyz);
ASSERT_TRUE(xyz->HasAttribute("expressed_in"));
EXPECT_EQ("__model__", xyz->Get<std::string>("expressed_in"));

// Try to load DOM object and expect it to succeed with no errors
sdf::Root root;
auto errors = root.Load(model);
EXPECT_EQ(0u, errors.size());
}

////////////////////////////////////////
// sdf model, version 1.4, use_parent_model_frame tag should
// not be added when reading without converting.
TEST(JointAxisFrame, Version_1_4_no_convert)
{
sdf::Errors errors;
sdf::SDFPtr model(new sdf::SDF());
sdf::init(model);
ASSERT_TRUE(
sdf::readStringWithoutConversion(get_sdf_string("1.4"), model, errors));

EXPECT_EQ("1.4", model->Root()->Get<std::string>("version"));
sdf::ElementPtr joint = model->Root()->GetElement(
"model")->GetElement("joint");
sdf::ElementPtr axis = joint->GetElement("axis");
ASSERT_NE(nullptr, axis);

axis->PrintValues("");
EXPECT_FALSE(axis->HasElement("use_parent_model_frame"));

// Try to load DOM object and expect it to fail since SDF is not updated
sdf::Root root;
errors = root.Load(model);
ASSERT_FALSE(errors.empty());
EXPECT_EQ(1u, errors.size());
EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::ATTRIBUTE_INVALID);
EXPECT_TRUE(errors[0].Message().find(
"SDF version attribute[1.4] should match the latest version[1.7] when "
"loading DOM objects.") !=
std::string::npos)
<< errors[0].Message();
}

////////////////////////////////////////
// sdf model, version 1.4, use_parent_model_frame tag should
// be added when converted to 1.5.
TEST(JointAxisFrame, Version_1_4_to_1_5)
{
sdf::Errors errors;
sdf::SDFPtr model(new sdf::SDF());
sdf::init(model);
ASSERT_TRUE(sdf::convertString(get_sdf_string("1.4"), "1.5", model));

EXPECT_EQ("1.5", model->Root()->Get<std::string>("version"));
sdf::ElementPtr joint = model->Root()->GetElement(
"model")->GetElement("joint");
sdf::ElementPtr axis = joint->GetElement("axis");
ASSERT_NE(nullptr, axis);

axis->PrintValues("");
EXPECT_TRUE(axis->HasElement("use_parent_model_frame"));
EXPECT_TRUE(axis->Get<bool>("use_parent_model_frame"));

// Try to load DOM object and expect it to fail since SDF is not updated
sdf::Root root;
errors = root.Load(model);
ASSERT_FALSE(errors.empty());
EXPECT_EQ(1u, errors.size());
EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::ATTRIBUTE_INVALID);
EXPECT_TRUE(errors[0].Message().find(
"SDF version attribute[1.5] should match the latest version[1.7] when "
"loading DOM objects.") !=
std::string::npos)
<< errors[0].Message();
}

////////////////////////////////////////
Expand All @@ -78,4 +149,9 @@ TEST(JointAxisFrame, Version_1_5_missing)
"model")->GetElement("joint");
sdf::ElementPtr axis = joint->GetElement("axis");
EXPECT_FALSE(axis->HasElement("use_parent_model_frame"));

// Try to load DOM object and expect it to succeed with no errors
sdf::Root root;
auto errors = root.Load(model);
EXPECT_EQ(0u, errors.size());
}

0 comments on commit f39f2f5

Please sign in to comment.