From 263f88fce604122d0828d563da11115e405b7844 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 15 Jan 2020 10:49:00 -0800 Subject: [PATCH 1/9] Add readFile and readString overloads to parser.hh that have a boolean argument for whether to conver to the latest version or not --- include/sdf/parser.hh | 54 ++++++++++++++++++++++++++++ src/parser.cc | 22 +++++++++--- src/parser_TEST.cc | 37 +++++++++++++++++++ test/integration/joint_axis_frame.cc | 41 +++++++++++++++++++++ 4 files changed, 150 insertions(+), 4 deletions(-) diff --git a/include/sdf/parser.hh b/include/sdf/parser.hh index d79f1ee5d..5ec349287 100644 --- a/include/sdf/parser.hh +++ b/include/sdf/parser.hh @@ -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. @@ -81,6 +89,23 @@ namespace sdf SDFORMAT_VISIBLE bool readFile(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 + /// file it is converted to SDF first. Conversion of files 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. + SDFORMAT_VISIBLE + bool readFile( + const std::string &_filename, + SDFPtr _sdf, + const bool _convert, + 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 @@ -97,7 +122,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); @@ -106,6 +134,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); @@ -114,16 +145,39 @@ 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 + /// + /// This populates the sdf pointer from a string. If the string is a URDF + /// file it is converted to SDF first. Conversion of files 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. + SDFORMAT_VISIBLE + bool readString( + const std::string &_xmlString, + SDFPtr _sdf, + const bool _convert, + 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); diff --git a/src/parser.cc b/src/parser.cc index 7be38e08c..735dcc32a 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -328,6 +328,13 @@ bool readFile(const std::string &_filename, SDFPtr _sdf) ////////////////////////////////////////////////// bool readFile(const std::string &_filename, SDFPtr _sdf, Errors &_errors) +{ + return readFile(_filename, _sdf, true, _errors); +} + +////////////////////////////////////////////////// +bool readFile(const std::string &_filename, SDFPtr _sdf, + const bool _convert, Errors &_errors) { TiXmlDocument xmlDoc; std::string filename = sdf::findFile(_filename, true, true); @@ -356,7 +363,7 @@ 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; } @@ -364,7 +371,7 @@ bool readFile(const std::string &_filename, SDFPtr _sdf, Errors &_errors) { 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; @@ -394,6 +401,13 @@ bool readString(const std::string &_xmlString, SDFPtr _sdf) ////////////////////////////////////////////////// bool readString(const std::string &_xmlString, SDFPtr _sdf, Errors &_errors) +{ + return readString(_xmlString, _sdf, true, _errors); +} + +////////////////////////////////////////////////// +bool readString(const std::string &_xmlString, SDFPtr _sdf, + const bool _convert, Errors &_errors) { TiXmlDocument xmlDoc; xmlDoc.Parse(_xmlString.c_str()); @@ -402,7 +416,7 @@ 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; } @@ -410,7 +424,7 @@ bool readString(const std::string &_xmlString, SDFPtr _sdf, Errors &_errors) { 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; diff --git a/src/parser_TEST.cc b/src/parser_TEST.cc index c1ad1298a..3230e7e12 100644 --- a/src/parser_TEST.cc +++ b/src/parser_TEST.cc @@ -59,6 +59,43 @@ sdf::SDFPtr InitSDF() return sdf; } +///////////////////////////////////////////////// +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("version")); + EXPECT_EQ("1.6", sdf->OriginalVersion()); + EXPECT_EQ("1.6", sdf->Root()->OriginalVersion()); + } + + // Call readFile API that explicitly converts + { + sdf::Errors errors; + sdf::SDFPtr sdf = InitSDF(); + EXPECT_TRUE(sdf::readFile(path, sdf, true, errors)); + EXPECT_EQ("1.7", sdf->Root()->Get("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::readFile(path, sdf, false, errors)); + EXPECT_EQ("1.6", sdf->Root()->Get("version")); + EXPECT_EQ("1.6", sdf->OriginalVersion()); + EXPECT_EQ("1.6", sdf->Root()->OriginalVersion()); + } +} + ///////////////////////////////////////////////// TEST(Parser, NameUniqueness) { diff --git a/test/integration/joint_axis_frame.cc b/test/integration/joint_axis_frame.cc index a29ba6464..517949e81 100644 --- a/test/integration/joint_axis_frame.cc +++ b/test/integration/joint_axis_frame.cc @@ -65,6 +65,47 @@ TEST(JointAxisFrame, Version_1_4_missing) EXPECT_EQ("__model__", xyz->Get("expressed_in")); } +//////////////////////////////////////// +// 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::readString(get_sdf_string("1.4"), model, false, errors)); + + EXPECT_EQ("1.4", model->Root()->Get("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")); +} + +//////////////////////////////////////// +// 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("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("use_parent_model_frame")); +} + //////////////////////////////////////// // sdf model, version 1.5, use_parent_model_frame tag should // be removed when converted to 1.7. From bdc8b8733dd7bf8ea4fe0a89c400d7e0f4bce2ca Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 15 Jan 2020 10:52:51 -0800 Subject: [PATCH 2/9] changelog --- Changelog.md | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Changelog.md b/Changelog.md index 3f1c1e371..d0bf1cdca 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,12 +2,15 @@ ### SDFormat 9.X.X (201X-XX-XX) +### 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) -### SDFormat 9.1.0 (201X-XX-XX) - 1. sdf 1.7: remove `//world/joint` element since it has never been used. * [Pull request 637](https://bitbucket.org/osrf/sdformat/pull-requests/637) From 81a3135109be8f0ef38ad8be2496c621d1d7a2f5 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Tue, 21 Jan 2020 14:35:49 -0800 Subject: [PATCH 3/9] throw error when loading sdf::Root DOM object if sdf version isn't the latest (currently hard-coded to 1.7) --- src/Root.cc | 10 ++++++++ test/integration/joint_axis_frame.cc | 34 ++++++++++++++++++++++++++++ 2 files changed, 44 insertions(+) diff --git a/src/Root.cc b/src/Root.cc index 952bd69e2..e359c4ae8 100644 --- a/src/Root.cc +++ b/src/Root.cc @@ -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 diff --git a/test/integration/joint_axis_frame.cc b/test/integration/joint_axis_frame.cc index 517949e81..b1f882c3e 100644 --- a/test/integration/joint_axis_frame.cc +++ b/test/integration/joint_axis_frame.cc @@ -63,6 +63,11 @@ TEST(JointAxisFrame, Version_1_4_missing) ASSERT_NE(nullptr, xyz); ASSERT_TRUE(xyz->HasAttribute("expressed_in")); EXPECT_EQ("__model__", xyz->Get("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()); } //////////////////////////////////////// @@ -83,6 +88,18 @@ TEST(JointAxisFrame, Version_1_4_no_convert) 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(); } //////////////////////////////////////// @@ -104,6 +121,18 @@ TEST(JointAxisFrame, Version_1_4_to_1_5) axis->PrintValues(""); EXPECT_TRUE(axis->HasElement("use_parent_model_frame")); EXPECT_TRUE(axis->Get("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(); } //////////////////////////////////////// @@ -119,4 +148,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()); } From 8471c70a780b1450eac39ee2a506b04c9adff962 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 22 Jan 2020 16:56:07 -0800 Subject: [PATCH 4/9] rename new readFile overload to readFileWithoutConversion --- include/sdf/parser.hh | 16 +++++++--------- src/parser.cc | 29 +++++++++++++++++++++++++++-- src/parser_TEST.cc | 12 +----------- 3 files changed, 35 insertions(+), 22 deletions(-) diff --git a/include/sdf/parser.hh b/include/sdf/parser.hh index 5ec349287..177303ccc 100644 --- a/include/sdf/parser.hh +++ b/include/sdf/parser.hh @@ -89,22 +89,20 @@ namespace sdf SDFORMAT_VISIBLE bool readFile(const std::string &_filename, SDFPtr _sdf, Errors &_errors); - /// \brief Populate the SDF values from a file + /// \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. Conversion of files to the latest - /// SDF version is controlled by a function parameter. + /// 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[in] _convert Convert to the latest version if true. /// \param[out] _errors Parsing errors will be appended to this variable. /// \return True if successful. SDFORMAT_VISIBLE - bool readFile( - const std::string &_filename, - SDFPtr _sdf, - const bool _convert, - Errors &_errors); + bool readFileWithoutConversion( + const std::string &_filename, SDFPtr _sdf, Errors &_errors); /// \brief Populate the SDF values from a file /// diff --git a/src/parser.cc b/src/parser.cc index a4c1efc49..1fa54c91b 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -43,6 +43,24 @@ 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 of files 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); + ////////////////////////////////////////////////// template static inline bool _initFile(const std::string &_filename, TPtr _sdf) @@ -329,11 +347,18 @@ bool readFile(const std::string &_filename, SDFPtr _sdf) ////////////////////////////////////////////////// bool readFile(const std::string &_filename, SDFPtr _sdf, Errors &_errors) { - return readFile(_filename, _sdf, true, _errors); + return readFileInternal(_filename, _sdf, true, _errors); +} + +////////////////////////////////////////////////// +bool readFileWithoutConversion( + const std::string &_filename, SDFPtr _sdf, Errors &_errors) +{ + return readFileInternal(_filename, _sdf, false, _errors); } ////////////////////////////////////////////////// -bool readFile(const std::string &_filename, SDFPtr _sdf, +bool readFileInternal(const std::string &_filename, SDFPtr _sdf, const bool _convert, Errors &_errors) { TiXmlDocument xmlDoc; diff --git a/src/parser_TEST.cc b/src/parser_TEST.cc index 5a061a060..0ac1f45f7 100644 --- a/src/parser_TEST.cc +++ b/src/parser_TEST.cc @@ -98,21 +98,11 @@ TEST(Parser, readFileConversions) EXPECT_EQ("1.6", sdf->Root()->OriginalVersion()); } - // Call readFile API that explicitly converts - { - sdf::Errors errors; - sdf::SDFPtr sdf = InitSDF(); - EXPECT_TRUE(sdf::readFile(path, sdf, true, errors)); - EXPECT_EQ("1.7", sdf->Root()->Get("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::readFile(path, sdf, false, errors)); + EXPECT_TRUE(sdf::readFileWithoutConversion(path, sdf, errors)); EXPECT_EQ("1.6", sdf->Root()->Get("version")); EXPECT_EQ("1.6", sdf->OriginalVersion()); EXPECT_EQ("1.6", sdf->Root()->OriginalVersion()); From 6a023c15b9ed7cfc9890d7ee970a19a9e8c2caed Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 22 Jan 2020 17:04:24 -0800 Subject: [PATCH 5/9] rename new readString overload to readStringWithoutConversion --- include/sdf/parser.hh | 16 +++++++-------- src/parser.cc | 29 +++++++++++++++++++++++++--- test/integration/joint_axis_frame.cc | 3 ++- 3 files changed, 35 insertions(+), 13 deletions(-) diff --git a/include/sdf/parser.hh b/include/sdf/parser.hh index 177303ccc..936c7e069 100644 --- a/include/sdf/parser.hh +++ b/include/sdf/parser.hh @@ -151,22 +151,20 @@ namespace sdf bool readString(const std::string &_xmlString, ElementPtr _sdf, Errors &_errors); - /// \brief Populate the SDF values from a string + /// \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. Conversion of files to the latest - /// SDF version is controlled by a function parameter. + /// 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[in] _convert Convert to the latest version if true. /// \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, - const bool _convert, - Errors &_errors); + bool readStringWithoutConversion( + const std::string &_xmlString, SDFPtr _sdf, Errors &_errors); /// \brief Populate the SDF values from a string /// diff --git a/src/parser.cc b/src/parser.cc index 1fa54c91b..df33306dc 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -48,7 +48,7 @@ inline namespace SDF_VERSION_NAMESPACE { /// 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 of files to the latest +/// 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. @@ -61,6 +61,22 @@ bool readFileInternal( const bool _convert, Errors &_errors); +/// \brief Populate 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 static inline bool _initFile(const std::string &_filename, TPtr _sdf) @@ -427,11 +443,18 @@ bool readString(const std::string &_xmlString, SDFPtr _sdf) ////////////////////////////////////////////////// bool readString(const std::string &_xmlString, SDFPtr _sdf, Errors &_errors) { - return readString(_xmlString, _sdf, true, _errors); + return readStringInternal(_xmlString, _sdf, true, _errors); +} + +////////////////////////////////////////////////// +bool readStringWithoutConversion( + const std::string &_filename, SDFPtr _sdf, Errors &_errors) +{ + return readStringInternal(_filename, _sdf, false, _errors); } ////////////////////////////////////////////////// -bool readString(const std::string &_xmlString, SDFPtr _sdf, +bool readStringInternal(const std::string &_xmlString, SDFPtr _sdf, const bool _convert, Errors &_errors) { TiXmlDocument xmlDoc; diff --git a/test/integration/joint_axis_frame.cc b/test/integration/joint_axis_frame.cc index b1f882c3e..9ea0220f3 100644 --- a/test/integration/joint_axis_frame.cc +++ b/test/integration/joint_axis_frame.cc @@ -78,7 +78,8 @@ TEST(JointAxisFrame, Version_1_4_no_convert) sdf::Errors errors; sdf::SDFPtr model(new sdf::SDF()); sdf::init(model); - ASSERT_TRUE(sdf::readString(get_sdf_string("1.4"), model, false, errors)); + ASSERT_TRUE( + sdf::readStringWithoutConversion(get_sdf_string("1.4"), model, errors)); EXPECT_EQ("1.4", model->Root()->Get("version")); sdf::ElementPtr joint = model->Root()->GetElement( From 293f6e28a367c106b3186ba20ef77b3f41832d99 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 22 Jan 2020 21:55:20 -0800 Subject: [PATCH 6/9] Close branch parser_read_convert_rename From f5f0c503a445e5ed53e855d3b5476e0241b3690b Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Thu, 23 Jan 2020 05:58:49 +0000 Subject: [PATCH 7/9] parser.cc: fix comment about internal helper function --- src/parser.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/parser.cc b/src/parser.cc index df33306dc..99724ea1d 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -61,7 +61,8 @@ bool readFileInternal( const bool _convert, Errors &_errors); -/// \brief Populate the SDF values from a string +/// \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 From e5559e1a74b02f7b42cc3db7b28b540983e60923 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Thu, 23 Jan 2020 06:20:39 +0000 Subject: [PATCH 8/9] bump to 9.1.0~pre1 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ab53d7216..08e2809c4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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}) From f3922b6cd6e6c5a597e1ce1d2e3cd278e79f0b52 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Thu, 23 Jan 2020 06:34:58 +0000 Subject: [PATCH 9/9] Close branch parser_read_convert