From c60e8f3d295e3d2d045711021a1f0dfe8e1dcb27 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Marco=20A=2E=20Guti=C3=A9rrez?= Date: Fri, 18 Jun 2021 02:37:51 +0800 Subject: [PATCH 1/8] Making PrintValues() and ToString() able to not print default elements (#575) Now PrintValues() and ToString() will not output the elements that were added by default during parsing. There's also the option to call them with a boolean flag that will allow the caller to decide weather they want defaults in the output or not. Signed-off-by: Marco A. Gutierrez Co-authored-by: Addisu Z. Taddese --- include/sdf/Element.hh | 28 +++++++ src/Element.cc | 111 +++++++++++++++++++-------- src/Element_TEST.cc | 70 ++++++++++++++++- test/integration/default_elements.cc | 104 ++++++++++++++++++++++++- test/sdf/empty_road_sph_coords.sdf | 2 +- 5 files changed, 275 insertions(+), 40 deletions(-) diff --git a/include/sdf/Element.hh b/include/sdf/Element.hh index 6064abf3a..798f7828e 100644 --- a/include/sdf/Element.hh +++ b/include/sdf/Element.hh @@ -149,6 +149,14 @@ namespace sdf /// \param[in] _prefix String value to prefix to the output. public: void PrintValues(std::string _prefix) const; + /// \brief Output Element's values to stdout. + /// \param[in] _prefix String value to prefix to the output. + /// \param[in] _includeDefaultElements flag to print default elements. + /// \param[in] _includeDefaultAttributes flag to print default attributes. + public: void PrintValues(const std::string &_prefix, + bool _includeDefaultElements, + bool _includeDefaultAttributes) const; + /// \brief Helper function for SDF::PrintDoc /// /// This generates the SDF html documentation. @@ -171,6 +179,18 @@ namespace sdf /// \return The string representation. public: std::string ToString(const std::string &_prefix) const; + /// \brief Convert the element values to a string representation. + /// Current behavior of ToString(const std::string &_prefix) can be + /// achieved by calling this function with _includeDefaultElements=true + /// and _includeDefaultAttributes=false + /// \param[in] _prefix String value to prefix to the output. + /// \param[in] _includeDefaultElements flag to include default elements. + /// \param[in] _includeDefaultAttributes flag to include default attributes. + /// \return The string representation. + public: std::string ToString(const std::string &_prefix, + bool _includeDefaultElements, + bool _includeDefaultAttributes) const; + /// \brief Add an attribute value. /// \param[in] _key Key value. /// \param[in] _type Type of data the attribute will hold. @@ -422,14 +442,22 @@ namespace sdf /// \brief Generate a string (XML) representation of this object. /// \param[in] _prefix arbitrary prefix to put on the string. + /// \param[in] _includeDefaultElements flag to include default elements. + /// \param[in] _includeDefaultAttributes flag to include default attributes. /// \param[out] _out the std::ostreamstream to write output to. private: void ToString(const std::string &_prefix, + bool _includeDefaultElements, + bool _includeDefaultAttributes, std::ostringstream &_out) const; /// \brief Generate a string (XML) representation of this object. /// \param[in] _prefix arbitrary prefix to put on the string. + /// \param[in] _includeDefaultElements flag to include default elements. + /// \param[in] _includeDefaultAttributes flag to include default attributes. /// \param[out] _out the std::ostreamstream to write output to. private: void PrintValuesImpl(const std::string &_prefix, + bool _includeDefaultElements, + bool _includeDefaultAttributes, std::ostringstream &_out) const; /// \brief Create a new Param object and return it. diff --git a/src/Element.cc b/src/Element.cc index 7df8928df..4f3326215 100644 --- a/src/Element.cc +++ b/src/Element.cc @@ -442,47 +442,59 @@ void Element::PrintDocLeftPane(std::string &_html, int _spacing, } void Element::PrintValuesImpl(const std::string &_prefix, + bool _includeDefaultElements, + bool _includeDefaultAttributes, std::ostringstream &_out) const { - _out << _prefix << "<" << this->dataPtr->name; - - Param_V::const_iterator aiter; - for (aiter = this->dataPtr->attributes.begin(); - aiter != this->dataPtr->attributes.end(); ++aiter) + if (this->GetExplicitlySetInFile() || _includeDefaultElements) { - // Only print attribute values if they were set - // TODO(anyone): GetRequired is added here to support up-conversions where a - // new required attribute with a default value is added. We would have - // better separation of concerns if the conversion process set the required - // attributes with their default values. - if ((*aiter)->GetSet() || (*aiter)->GetRequired()) - { - _out << " " << (*aiter)->GetKey() << "='" - << (*aiter)->GetAsString() << "'"; - } - } + _out << _prefix << "<" << this->dataPtr->name; - if (this->dataPtr->elements.size() > 0) - { - _out << ">\n"; - ElementPtr_V::const_iterator eiter; - for (eiter = this->dataPtr->elements.begin(); - eiter != this->dataPtr->elements.end(); ++eiter) + Param_V::const_iterator aiter; + for (aiter = this->dataPtr->attributes.begin(); + aiter != this->dataPtr->attributes.end(); ++aiter) { - (*eiter)->ToString(_prefix + " ", _out); + // Only print attribute values if they were set + // TODO(anyone): GetRequired is added here to support up-conversions where + // a new required attribute with a default value is added. We would have + // better separation of concerns if the conversion process set the + // required attributes with their default values. + if ((*aiter)->GetSet() || (*aiter)->GetRequired() || + _includeDefaultAttributes) + { + _out << " " << (*aiter)->GetKey() << "='" + << (*aiter)->GetAsString() << "'"; + } } - _out << _prefix << "dataPtr->name << ">\n"; - } - else - { - if (this->dataPtr->value) + + if (this->dataPtr->elements.size() > 0) { - _out << ">" << this->dataPtr->value->GetAsString() - << "dataPtr->name << ">\n"; + _out << ">\n"; + ElementPtr_V::const_iterator eiter; + for (eiter = this->dataPtr->elements.begin(); + eiter != this->dataPtr->elements.end(); ++eiter) + { + if ((*eiter)->GetExplicitlySetInFile() || _includeDefaultElements) + { + (*eiter)->ToString(_prefix + " ", + _includeDefaultElements, + _includeDefaultAttributes, + _out); + } + } + _out << _prefix << "dataPtr->name << ">\n"; } else { - _out << "/>\n"; + if (this->dataPtr->value) + { + _out << ">" << this->dataPtr->value->GetAsString() + << "dataPtr->name << ">\n"; + } + else + { + _out << "/>\n"; + } } } } @@ -491,7 +503,20 @@ void Element::PrintValuesImpl(const std::string &_prefix, void Element::PrintValues(std::string _prefix) const { std::ostringstream ss; - PrintValuesImpl(_prefix, ss); + PrintValuesImpl(_prefix, true, false, ss); + std::cout << ss.str(); +} + +///////////////////////////////////////////////// +void Element::PrintValues(const std::string &_prefix, + bool _includeDefaultElements, + bool _includeDefaultAttributes) const +{ + std::ostringstream ss; + PrintValuesImpl(_prefix, + _includeDefaultElements, + _includeDefaultAttributes, + ss); std::cout << ss.str(); } @@ -499,17 +524,35 @@ void Element::PrintValues(std::string _prefix) const std::string Element::ToString(const std::string &_prefix) const { std::ostringstream out; - this->ToString(_prefix, out); + this->ToString(_prefix, true, false, out); + return out.str(); +} + +///////////////////////////////////////////////// +std::string Element::ToString(const std::string &_prefix, + bool _includeDefaultElements, + bool _includeDefaultAttributes) const +{ + std::ostringstream out; + this->ToString(_prefix, + _includeDefaultElements, + _includeDefaultAttributes, + out); return out.str(); } ///////////////////////////////////////////////// void Element::ToString(const std::string &_prefix, + bool _includeDefaultElements, + bool _includeDefaultAttributes, std::ostringstream &_out) const { if (this->dataPtr->includeFilename.empty()) { - PrintValuesImpl(_prefix, _out); + PrintValuesImpl(_prefix, + _includeDefaultElements, + _includeDefaultAttributes, + _out); } else { diff --git a/src/Element_TEST.cc b/src/Element_TEST.cc index ec7897a11..046843004 100644 --- a/src/Element_TEST.cc +++ b/src/Element_TEST.cc @@ -540,7 +540,6 @@ TEST(Element, ToStringValue) "myprefix< test='foo'>val\n"); } - ///////////////////////////////////////////////// TEST(Element, ToStringClonedElement) { @@ -575,6 +574,75 @@ TEST(Element, ToStringInclude) ASSERT_EQ(stringval, "myprefix\n"); } +///////////////////////////////////////////////// +TEST(Element, ToStringDefaultElements) +{ + sdf::ElementPtr parent = std::make_shared(); + parent->SetName("parent"); + sdf::ElementPtr elem = std::make_shared(); + elem->SetName("elem"); + elem->SetParent(parent); + parent->InsertElement(elem); + sdf::ElementPtr elem2 = std::make_shared(); + elem2->SetName("elem2"); + elem2->SetParent(parent); + parent->InsertElement(elem2); + + std::ostringstream stream; + stream + << "\n" + << " \n" + << " \n" + << "\n"; + + EXPECT_EQ(parent->ToString("", false, false), stream.str()); + EXPECT_EQ(parent->ToString(""), stream.str()); + EXPECT_EQ(parent->ToString("", true, false), stream.str()); + + elem->SetExplicitlySetInFile(false); + + std::ostringstream stream2; + stream2 + << "\n" + << " \n" + << "\n"; + + EXPECT_EQ(parent->ToString("", false, false), stream2.str()); + EXPECT_EQ(parent->ToString(""), stream.str()); + EXPECT_EQ(parent->ToString("", true, false), stream.str()); + + parent->SetExplicitlySetInFile(false); + + EXPECT_EQ(parent->ToString("", false, false), ""); + EXPECT_EQ(parent->ToString(""), stream.str()); + EXPECT_EQ(parent->ToString("", true, false), stream.str()); +} + +///////////////////////////////////////////////// +TEST(Element, ToStringDefaultAttributes) +{ + sdf::ElementPtr element = std::make_shared(); + element->SetName("foo"); + element->AddAttribute("test", "string", "foo", false, "foo description"); + element->AddAttribute("test2", "string", "bar", true, "bar description"); + + EXPECT_EQ(element->ToString(""), element->ToString("", true, false)); + EXPECT_EQ(element->ToString(""), element->ToString("", false, false)); + + std::ostringstream stream; + stream << "\n"; + + EXPECT_EQ(element->ToString(""), stream.str()); + EXPECT_EQ(element->ToString("", true, false), stream.str()); + EXPECT_EQ(element->ToString("", false, false), stream.str()); + + std::ostringstream stream2; + stream2 << "\n"; + + EXPECT_EQ(element->ToString("", true, true), stream2.str()); + EXPECT_EQ(element->ToString("", false, true), stream2.str()); +} + ///////////////////////////////////////////////// TEST(Element, DocLeftPane) { diff --git a/test/integration/default_elements.cc b/test/integration/default_elements.cc index e8dcfbac1..970e26db4 100644 --- a/test/integration/default_elements.cc +++ b/test/integration/default_elements.cc @@ -31,12 +31,12 @@ ////////////////////////////////////////////////// TEST(ExplicitlySetInFile, EmptyRoadSphCoords) { - const std::string test_file = + const std::string testFile = sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf", "empty_road_sph_coords.sdf"); sdf::Root root; - sdf::Errors errors = root.Load(test_file); + sdf::Errors errors = root.Load(testFile); EXPECT_TRUE(errors.empty()); sdf::ElementPtr rootPtr = root.Element(); @@ -109,12 +109,12 @@ TEST(ExplicitlySetInFile, EmptyRoadSphCoords) ////////////////////////////////////////////////// TEST(ExplicitlySetInFile, EmptyAxis) { - const std::string test_file = + const std::string testFile = sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf", "empty_axis.sdf"); sdf::Root root; - sdf::Errors errors = root.Load(test_file); + sdf::Errors errors = root.Load(testFile); EXPECT_TRUE(errors.empty()); sdf::ElementPtr rootPtr = root.Element(); @@ -153,3 +153,99 @@ TEST(ExplicitlySetInFile, EmptyAxis) sdf::ElementPtr upperLimitPtr = lowerLimitPtr->GetNextElement(); EXPECT_FALSE(upperLimitPtr->GetExplicitlySetInFile()); } + +////////////////////////////////////////////////// +TEST(ExplicitlySetInFile, ToString) +{ + const std::string testFile = + sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf", + "empty_road_sph_coords.sdf"); + + sdf::Root root; + sdf::Errors errors = root.Load(testFile); + EXPECT_TRUE(errors.empty()); + + EXPECT_EQ(root.Element()->ToString(""), + root.Element()->ToString("", true, false)); + + std::ostringstream stream; + std::string version = "1.7"; + stream + << "\n" + << " \n" + << " \n" + << " \n" + << " \n" + << " \n" + << " \n" + << "\n"; + + EXPECT_EQ(root.Element()->ToString("", false, false), stream.str()); + + stream.str(std::string()); + stream + << "\n" + << " \n" + << " \n" + << " 1\n" + << " 0 0 0\n" + << " \n" + << " \n" + << " EARTH_WGS84\n" + << " 0\n" + << " 0\n" + << " 0\n" + << " 0\n" + << " \n" + << " 0 0 -9.8\n" + << " 6e-06 2.3e-05 -4.2e-05\n" + << " \n" + << " \n" + << " 0.001\n" + << " 1\n" + << " 1000\n" + << " \n" + << " \n" + << " 0.4 0.4 0.4 1\n" + << " 0.7 0.7 0.7 1\n" + << " 1\n" + << " \n" + << " \n" + << "\n"; + + EXPECT_EQ(root.Element()->ToString(""), stream.str()); + EXPECT_EQ(root.Element()->ToString("", true, false), stream.str()); + + stream.str(std::string()); + stream + << "\n" + << " \n" + << " \n" + << " 1\n" + << " 0 0 0\n" + << " \n" + << " \n" + << " EARTH_WGS84\n" + << " 0\n" + << " 0\n" + << " 0\n" + << " 0\n" + << " \n" + << " 0 0 -9.8\n" + << " 6e-06 2.3e-05 -4.2e-05\n" + << " \n" + << " \n" + << " 0.001\n" + << " 1\n" + << " 1000\n" + << " \n" + << " \n" + << " 0.4 0.4 0.4 1\n" + << " 0.7 0.7 0.7 1\n" + << " 1\n" + << " \n" + << " \n" + << "\n"; + + EXPECT_EQ(root.Element()->ToString("", true, true), stream.str()); +} diff --git a/test/sdf/empty_road_sph_coords.sdf b/test/sdf/empty_road_sph_coords.sdf index f9d720d1c..eef134246 100644 --- a/test/sdf/empty_road_sph_coords.sdf +++ b/test/sdf/empty_road_sph_coords.sdf @@ -16,7 +16,7 @@ + + + + 0.2 + 0.3 + + + + + + + + + 0.2 + 0.3 + + + + + + + 0 0 1 1 + 0 0 1 1 + + + + + 0.1 0.2 0.3 0 0 0 + top/cam + 20 + + + + 1280 + + + 50 + 0.05 + + + + + + + + + 0.5 + + 0.05 + 0.05 + 0.05 + + + + + + 0.8 + + + + 1 1 1 1 + + + + + + 0.8 + + + + + + + 1 1 1 0 0 0 + + + + + + foo + + + + + + + bar + + + + + + + + + diff --git a/test/integration/include_custom_model_expected_output.sdf b/test/integration/include_custom_model_expected_output.sdf new file mode 100644 index 000000000..9076b37bf --- /dev/null +++ b/test/integration/include_custom_model_expected_output.sdf @@ -0,0 +1,475 @@ + + + + + + 0 0 0.325 0 -0 0 + + + + -0.151427 -0 0.175 0 -0 0 + + 1.14395 + + 0.126164 + 0 + 0 + 0.416519 + 0 + 0.481014 + + + + + + 2.01142 1 0.568726 + + + + 0.5 0.5 1 1 + 0.5 0.5 1 1 + 0 0 1 1 + + + + + + 2.01142 1 0.568726 + + + + + + + + + -1.06 0 0 0 -0 3.14 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + + + + + 30 + chassis/camera + + + + + -1.06 0 0 0 -0 3.14 + + + 0.1 0.1 0.1 + + + + + + + 0.6 0 0.7 0 -0 0 + + + + + 0.65 + + + + + + + + + + + + 1 0.5 0.5 + + + + + + + 0 0 1 1 + 0 0 1 1 + + + + + + + + + + + + + + + -0.2 0 0.3 0 -0 3.14 + + + + 0.05 + + + + + + + 0 0 1 1 + 0 0 0 1 + + + + + + + + + + 0.5 + + + + + + + 0.1 0.2 0.3 0 -0 0 + + + + 1.047 + + 1280 + + + 240 + + + 0.05 + 50 + + + + + 1 + 20 + + + 1 + top/cam + + + + + + + vehicle::chassis + vehicle::top + + + 0.554283 0.625029 -0.025 -1.5707 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + + 0.2 + 0.3 + + + + + + + + + 0.554282 -0.625029 -0.025 -1.5707 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + + 0.2 + 0.3 + + + + + + + + + 0 0 0 0 0 0 + + + + 0.5 + + + + 0.05 + + + 0 + 0 + 0.05 + + + 0 + 0.05 + + + + + + + + 0.8 + + + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 1 1 1 1 + + + + + + + + 0.8 + + + + + + + + vehicle::chassis + vehicle::left_wheel + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + vehicle::chassis + vehicle::right_wheel + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + vehicle::chassis + vehicle::caster + + + + 1 1 1 0 -0 0 + + + + + + + + + + 0.1 0.1 0.1 + + + + + + + + + + + 0 0 0 0 -0 0 + + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + 1 + + + + + + 0 0 0 0 -0 0 + + bar + + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + diff --git a/test/integration/include_custom_nested_model_expected_output.sdf b/test/integration/include_custom_nested_model_expected_output.sdf new file mode 100644 index 000000000..533528b8b --- /dev/null +++ b/test/integration/include_custom_nested_model_expected_output.sdf @@ -0,0 +1,352 @@ + + + + + 0 0 0.325 0 -0 0 + + + -0.151427 -0 0.175 0 -0 0 + + 1.14395 + + 0.126164 + 0 + 0 + 0.416519 + 0 + 0.481014 + + + + + + 2.01142 1 0.568726 + + + + 0.5 0.5 1 1 + 0.5 0.5 1 1 + 0 0 1 1 + + + + + + 2.01142 1 0.568726 + + + + + + + + + + + + -1.06 0 0 0 -0 3.14 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + 1 + chassis/camera + + + + + -1.06 0 0 0 -0 3.14 + + + 0.1 0.1 0.1 + + + + + + 0 0 0 0 -0 0 + + + 0.6 0 0.7 0 -0 0 + + + + 0.5 1 0.5 + + + + + + + 0.5 1 0.5 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + 0 0 0 0 -0 0 + + + + -0.2 0 0.3 0 -0 3.14 + + + 0.05 + + + + + + 0 0 1 1 + 0 0 1 1 + + + 0.5 0.5 0.5 1 + + + + 0 0 0 0 -0 3.14 + + + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 60 + + + 1 + top/camera + + 0 0 0 0 -0 0 + + + + -0.2 0 0.3 0 0 3.14 + + + 0.05 + + + + + + base::top_model::top + base::top_model::top_camera::top_camera_link + + + base::chassis + base::top_model::top + + + 0.554283 0.625029 -0.025 -1.5707 0 0 + + + 0 0 0 0 -0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + 0.554282 -0.625029 -0.025 -1.5707 0 0 + + + 0 0 0 0 -0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + -0.957138 -0 -0.025 0 -0 0 + + + 0 0 0 0 -0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + base::chassis + base::left_wheel::wheel_link + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + base::chassis + base::right_wheel::wheel_link + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + base::chassis + base::caster::wheel_link + + + 0 0 -9.8 + 6e-06 2.3e-05 -4.2e-05 + + + 0.001 + 1 + 1000 + + + 0.4 0.4 0.4 1 + 0.7 0.7 0.7 1 + 1 + + + diff --git a/test/integration/include_invalid_custom_model.sdf b/test/integration/include_invalid_custom_model.sdf new file mode 100644 index 000000000..c1a95f3b7 --- /dev/null +++ b/test/integration/include_invalid_custom_model.sdf @@ -0,0 +1,133 @@ + + + + + + robot + + + + + + -1.06 0 0 0 0 3.14 + + + 0.1 0.1 0.1 + + + + + + + + 0.1 0.1 0.1 + + + + + + + + 0.1 0.1 0.1 + + + + + + + + + 0.2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 1 1 + + + + + + + + + + + + + + + + + + + 0.5 + + + + + + + 0.5 0.5 + + + + + + + + + + + + + diff --git a/test/integration/include_model.sdf b/test/integration/include_model.sdf new file mode 100644 index 000000000..f644f6cc7 --- /dev/null +++ b/test/integration/include_model.sdf @@ -0,0 +1,10 @@ + + + + + + robot + + + + diff --git a/test/integration/model/nested_include/base/base.sdf b/test/integration/model/nested_include/base/base.sdf new file mode 100644 index 000000000..18827b3b2 --- /dev/null +++ b/test/integration/model/nested_include/base/base.sdf @@ -0,0 +1,158 @@ + + + + 0 0 0.325 0 -0 0 + + + -0.151427 -0 0.175 0 -0 0 + + 1.14395 + + 0.126164 + 0 + 0 + 0.416519 + 0 + 0.481014 + + + + + + 2.01142 1 0.568726 + + + + 0.5 0.5 1.0 1 + 0.5 0.5 1.0 1 + 0.0 0.0 1.0 1 + + + + + + 2.01142 1 0.568726 + + + + + + -0.8 0 0.41 0 0 0 + + + 0.1 + 0.25 + + + + + + -0.8 0 0.41 0 0 0 + lidar + 10 + + + + 640 + 1 + -1.396263 + 1.396263 + + + 16 + 1 + -0.261799 + 0.261799 + + + + 0.08 + 10.0 + 0.01 + + + 1 + true + + + + -1.06 0 0 0 0 3.14 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + chassis/camera + + + + + + top_model + + + + chassis + top_model::top + + + + wheel + 0.554283 0.625029 -0.025 -1.5707 0 0 + left_wheel + + + + wheel + 0.554282 -0.625029 -0.025 -1.5707 0 0 + right_wheel + + + + wheel + -0.957138 -0 -0.025 0 -0 0 + caster + + + + + chassis + left_wheel::wheel_link + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + + + chassis + right_wheel::wheel_link + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + + chassis + caster::wheel_link + + + + diff --git a/test/integration/model/nested_include/base/model.config b/test/integration/model/nested_include/base/model.config new file mode 100644 index 000000000..9cad6b4e0 --- /dev/null +++ b/test/integration/model/nested_include/base/model.config @@ -0,0 +1,6 @@ + + + base + base.sdf + + diff --git a/test/integration/model/nested_include/test_nested_include.sdf b/test/integration/model/nested_include/test_nested_include.sdf new file mode 100644 index 000000000..744d3f294 --- /dev/null +++ b/test/integration/model/nested_include/test_nested_include.sdf @@ -0,0 +1,52 @@ + + + + + + base + + + + + + + -1.06 0 0 0 0 3.14 + + + 0.1 0.1 0.1 + + + + + + 0 0 0 0 0 3.14 + 60 + + + + + + 0.05 + + + + + 0 0 1 1 + 0 0 1 1 + + + + + -0.2 0 0.3 0 0 3.14 + + + 0.05 + + + + + + + + + diff --git a/test/integration/model/nested_include/top_camera/model.config b/test/integration/model/nested_include/top_camera/model.config new file mode 100644 index 000000000..19b6749b2 --- /dev/null +++ b/test/integration/model/nested_include/top_camera/model.config @@ -0,0 +1,6 @@ + + + top_camera + top_camera.sdf + + diff --git a/test/integration/model/nested_include/top_camera/top_camera.sdf b/test/integration/model/nested_include/top_camera/top_camera.sdf new file mode 100644 index 000000000..b871cbfdf --- /dev/null +++ b/test/integration/model/nested_include/top_camera/top_camera.sdf @@ -0,0 +1,40 @@ + + + + + + + -0.2 0 0.3 0 0 3.14 + + + 0.1 0.1 0.1 + + + + 0 1 0 1 + 0 1 0 1 + 0.5 0.5 0.5 1 + + + + + -0.2 0 0.3 0 0.0 0 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + top/camera + + + + diff --git a/test/integration/model/nested_include/top_model/model.config b/test/integration/model/nested_include/top_model/model.config new file mode 100644 index 000000000..fbe7b28ad --- /dev/null +++ b/test/integration/model/nested_include/top_model/model.config @@ -0,0 +1,5 @@ + + + top_model + top_model.sdf + diff --git a/test/integration/model/nested_include/top_model/top_model.sdf b/test/integration/model/nested_include/top_model/top_model.sdf new file mode 100644 index 000000000..19131e51b --- /dev/null +++ b/test/integration/model/nested_include/top_model/top_model.sdf @@ -0,0 +1,39 @@ + + + + + + 0.6 0 0.7 0 0 0 + + + + 0.5 1 0.5 + + + + + + + 0.5 1 0.5 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + top_camera + 0 0 0 0 0 0 + + + + top + top_camera::top_camera_link + + + + diff --git a/test/integration/model/nested_include/wheel/model.config b/test/integration/model/nested_include/wheel/model.config new file mode 100644 index 000000000..1ef2c97c3 --- /dev/null +++ b/test/integration/model/nested_include/wheel/model.config @@ -0,0 +1,6 @@ + + + wheel + wheel.sdf + + diff --git a/test/integration/model/nested_include/wheel/wheel.sdf b/test/integration/model/nested_include/wheel/wheel.sdf new file mode 100644 index 000000000..7556007ce --- /dev/null +++ b/test/integration/model/nested_include/wheel/wheel.sdf @@ -0,0 +1,38 @@ + + + + + 0 0 0 0 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + diff --git a/test/integration/model/robot/model.config b/test/integration/model/robot/model.config new file mode 100644 index 000000000..04a17df92 --- /dev/null +++ b/test/integration/model/robot/model.config @@ -0,0 +1,5 @@ + + + robot + model.sdf + diff --git a/test/integration/model/robot/model.sdf b/test/integration/model/robot/model.sdf new file mode 100644 index 000000000..ec02e8359 --- /dev/null +++ b/test/integration/model/robot/model.sdf @@ -0,0 +1,315 @@ + + + + 0 0 0.325 0 -0 0 + + + -0.151427 -0 0.175 0 -0 0 + + 1.14395 + + 0.126164 + 0 + 0 + 0.416519 + 0 + 0.481014 + + + + + + 2.01142 1 0.568726 + + + + 0.5 0.5 1.0 1 + 0.5 0.5 1.0 1 + 0.0 0.0 1.0 1 + + + + + + 2.01142 1 0.568726 + + + + + + -0.8 0 0.41 0 0 0 + + + 0.1 + 0.25 + + + + + + -0.8 0 0.41 0 0 0 + lidar + 10 + + + + 640 + 1 + -1.396263 + 1.396263 + + + 16 + 1 + -0.261799 + 0.261799 + + + + 0.08 + 10.0 + 0.01 + + + 1 + true + + + + -1.06 0 0 0 0 3.14 + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + true + 30 + chassis/camera + + + + + + 0.6 0 0.7 0 0 0 + + + + 0.5 1 0.5 + + + + + + + 0.5 1 0.5 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + 0.5 + 1 + + + + + + + -0.2 0 0.3 0 0 3.14 + + + 0.1 0.1 0.1 + + + + + + -0.2 0 0.3 0 0 3.14 + + + 0.1 0.1 0.1 + + + + 0 1 0 1 + 0 1 0 1 + 0.5 0.5 0.5 1 + 1 + + + + + + -0.2 0 0.3 0 0.0 0 + + 2 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + top/camera + + + + + + chassis + top + + + + 0.554283 0.625029 -0.025 -1.5707 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + + 0.554282 -0.625029 -0.025 -1.5707 0 0 + + 2 + + 0.145833 + 0 + 0 + 0.145833 + 0 + 0.125 + + + + + + 0.3 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.3 + + + + + + + -0.957138 -0 -0.125 0 -0 0 + + 1 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + + 0.2 + + + + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + 0.2 0.2 0.2 1 + + + + + + 0.2 + + + + + + + chassis + left_wheel + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + + chassis + right_wheel + + 0 0 1 + + -1.79769e+308 + 1.79769e+308 + + + + + + chassis + caster + + + + 0 0 0 0 0 0 + + + + + + diff --git a/test/integration/param_passing.cc b/test/integration/param_passing.cc new file mode 100644 index 000000000..44a40ed1e --- /dev/null +++ b/test/integration/param_passing.cc @@ -0,0 +1,165 @@ +/* + * Copyright 2020 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 +#include +#include "sdf/Filesystem.hh" +#include "sdf/Root.hh" +#include "test_config.h" + +void PrintErrors(sdf::Errors &_errors) +{ + for (sdf::Error e : _errors) + std::cout << e.Message() << std::endl; +} + +///////////////////////////////////////////////// +TEST(ParamPassingTest, ExperimentalParamsTag) +{ + const std::string modelRootPath = + sdf::testing::TestFile("integration", "model"); + sdf::setFindCallback( + [&](const std::string &_file) + { + return sdf::filesystem::append(modelRootPath, _file); + }); + + // checks normal (w/o ) + std::string testFile = + sdf::testing::TestFile("integration", "include_model.sdf"); + sdf::Root root; + sdf::Errors errors = root.Load(testFile); + PrintErrors(errors); + EXPECT_TRUE(errors.empty()); + + // checks containing w/ correctly specified + // elements + testFile = sdf::testing::TestFile("integration", "include_custom_model.sdf"); + errors = root.Load(testFile); + PrintErrors(errors); + EXPECT_TRUE(errors.empty()); + + // compare with expected output + testFile = sdf::testing::TestFile("integration", + "include_custom_model_expected_output.sdf"); + sdf::Root expectedRoot; + errors = expectedRoot.Load(testFile); + PrintErrors(errors); + EXPECT_TRUE(errors.empty()); + EXPECT_EQ(root.Element()->ToString(""), expectedRoot.Element()->ToString("")) + << "ACTUAL:\n" << root.Element()->ToString("\t") + << "\nEXPECTED:\n" << expectedRoot.Element()->ToString("\t"); + + // Expected errors + testFile = sdf::testing::TestFile("integration", + "include_invalid_custom_model.sdf"); + errors = root.Load(testFile); + PrintErrors(errors); + EXPECT_FALSE(errors.empty()); + ASSERT_EQ(errors.size(), 29u); + + int i = -1; + // missing element_id attribute + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_MISSING); + // element does not exist in included model + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // element already exists in included model + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::DUPLICATE_NAME); + // for add action, parent of specified element does not exist + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // missing name after double colons + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_INVALID); + // missing action attribute + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_MISSING); + // incorrect schema (missing required attributes; in children of element_id) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_MISSING); + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_INVALID); + // not defined sdf element (in children of where element_id is defined) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_INVALID); + // not defined sdf element (where element_id is defined) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_INVALID); + // missing 'name' attribute where element_id is with action="add" + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_MISSING); + // 'name' attribute is empty (where element_id is with action="add") + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_INVALID); + // incorrect schema (missing required attributes; where element_id defined) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_MISSING); + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_INVALID); + // invalid action + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_INVALID); + // invalid child action + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_INVALID); + // child element does not exist + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // child (child of ) does not exist + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // child element (w/ name attribute) does not exist + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // child element does not exist (replace action) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // missing 'name' attribute (replace action) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_MISSING); + // invalid attribute (modify action) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_INVALID); + // element missing (modify action) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // incorrect schema (missing required attributes; where element_id defined) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_MISSING); + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_INVALID); + // invalid attribute (modify action) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ATTRIBUTE_INVALID); + // element missing (modify action) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // element missing (modify action) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_MISSING); + // element has invalid value (modify action) + EXPECT_EQ(errors[++i].Code(), sdf::ErrorCode::ELEMENT_INVALID); +} + +///////////////////////////////////////////////// +TEST(ParamPassingTest, NestedInclude) +{ + const std::string modelRootPath = + sdf::testing::TestFile("integration", "model", "nested_include"); + sdf::setFindCallback( + [&](const std::string &_file) + { + return sdf::filesystem::append(modelRootPath, _file); + }); + + // checks correctly specified elements in + // at top-level include, which has several nested includes + // e.g., When model A includes B and B includes C. The top-level A + // specifies elements of C + std::string testFile = + sdf::testing::TestFile("integration", "model", + "nested_include", "test_nested_include.sdf"); + sdf::Root root; + sdf::Errors errors = root.Load(testFile); + PrintErrors(errors); + EXPECT_TRUE(errors.empty()); + + // compare with expected output + testFile = sdf::testing::TestFile("integration", + "include_custom_nested_model_expected_output.sdf"); + sdf::Root expectedRoot; + errors = expectedRoot.Load(testFile); + PrintErrors(errors); + EXPECT_TRUE(errors.empty()); + EXPECT_EQ(root.Element()->ToString(""), expectedRoot.Element()->ToString("")) + << "ACTUAL:\n" << root.Element()->ToString("\t") + << "\nEXPECTED:\n" << expectedRoot.Element()->ToString("\t"); +} From 01bb85f06ea3baa7715a2c5a71ac84d12e0fd81d Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Mon, 28 Jun 2021 21:45:09 -0500 Subject: [PATCH 4/8] Fix ABI break (#605) This moves the recently added data member `explicitlySetInFile` to the end of the `ElementPrivate` class Signed-off-by: Addisu Z. Taddese --- include/sdf/Element.hh | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/include/sdf/Element.hh b/include/sdf/Element.hh index 798f7828e..27f3cc239 100644 --- a/include/sdf/Element.hh +++ b/include/sdf/Element.hh @@ -489,9 +489,6 @@ namespace sdf /// \brief True if element is required public: std::string required; - /// \brief True if the element was set in the SDF file. - public: bool explicitlySetInFile; - /// \brief Element description public: std::string description; @@ -524,6 +521,9 @@ namespace sdf /// \brief Spec version that this was originally parsed from. public: std::string originalVersion; + + /// \brief True if the element was set in the SDF file. + public: bool explicitlySetInFile; }; /////////////////////////////////////////////// From 18f908b67d2c408538dc10422c4ccf8b8d6f6103 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 30 Jun 2021 17:10:29 -0700 Subject: [PATCH 5/8] Add ValidateGraphs methods to Model/World (sdf9) (#602) The graph data is private, so expose methods for checking that the graphs are valid. * Add tests showing graph errors Load an sdf::World or sdf::Model instead of an sdf::Root to see the graph errors. Signed-off-by: Steve Peters --- include/sdf/Model.hh | 6 ++ include/sdf/World.hh | 6 ++ src/FrameSemantics.cc | 2 +- src/Model.cc | 29 ++++++++ src/Model_TEST.cc | 11 +++ src/World.cc | 29 ++++++++ src/World_TEST.cc | 11 +++ test/integration/frame.cc | 127 +++++++++++++++++++++++++++++++++- test/integration/model_dom.cc | 3 + test/integration/world_dom.cc | 2 + 10 files changed, 223 insertions(+), 3 deletions(-) diff --git a/include/sdf/Model.hh b/include/sdf/Model.hh index cfa25454e..454eb99c3 100644 --- a/include/sdf/Model.hh +++ b/include/sdf/Model.hh @@ -74,6 +74,12 @@ namespace sdf /// an error code and message. An empty vector indicates no error. public: Errors Load(ElementPtr _sdf); + /// \brief Check that the FrameAttachedToGraph and PoseRelativeToGraph + /// are valid. + /// \return Errors, which is a vector of Error objects. Each Error includes + /// an error code and message. An empty vector indicates no error. + public: Errors ValidateGraphs() const; + /// \brief Get the name of the model. /// The name of the model should be unique within the scope of a World. /// \return Name of the model. diff --git a/include/sdf/World.hh b/include/sdf/World.hh index 2f513eaaa..3e333a104 100644 --- a/include/sdf/World.hh +++ b/include/sdf/World.hh @@ -76,6 +76,12 @@ namespace sdf /// an error code and message. An empty vector indicates no error. public: Errors Load(ElementPtr _sdf); + /// \brief Check that the FrameAttachedToGraph and PoseRelativeToGraph + /// are valid. + /// \return Errors, which is a vector of Error objects. Each Error includes + /// an error code and message. An empty vector indicates no error. + public: Errors ValidateGraphs() const; + /// \brief Get the name of the world. /// \return Name of the world. public: std::string Name() const; diff --git a/src/FrameSemantics.cc b/src/FrameSemantics.cc index 57a0fe30a..323303001 100644 --- a/src/FrameSemantics.cc +++ b/src/FrameSemantics.cc @@ -1346,7 +1346,7 @@ Errors resolveFrameAttachedToBody( { errors.push_back({ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR, "Graph has __model__ scope but sink vertex named [" + - sinkVertex.Name() + "] does not have FrameType LINK OR MODEL " + sinkVertex.Name() + "] does not have FrameType LINK or MODEL " "when starting from vertex with name [" + _vertexName + "]."}); return errors; } diff --git a/src/Model.cc b/src/Model.cc index 03629a798..e7e1ce759 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -409,6 +409,35 @@ Errors Model::Load(ElementPtr _sdf) return errors; } +///////////////////////////////////////////////// +Errors Model::ValidateGraphs() const +{ + Errors errors; + if (!this->dataPtr->frameAttachedToGraph) + { + errors.push_back({ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR, + "FrameAttachedToGraph pointer is null."}); + } + else + { + errors = validateFrameAttachedToGraph(*this->dataPtr->frameAttachedToGraph); + } + + if (!this->dataPtr->poseGraph) + { + errors.push_back({ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR, + "PoseRelativeToGraph pointer is null."}); + } + else + { + Errors poseErrors = + validatePoseRelativeToGraph(*this->dataPtr->poseGraph); + errors.insert(errors.end(), poseErrors.begin(), poseErrors.end()); + } + + return errors; +} + ///////////////////////////////////////////////// std::string Model::Name() const { diff --git a/src/Model_TEST.cc b/src/Model_TEST.cc index 86584b4a5..7172d53e0 100644 --- a/src/Model_TEST.cc +++ b/src/Model_TEST.cc @@ -109,6 +109,17 @@ TEST(DOMModel, Construction) // expect errors when trying to resolve pose EXPECT_FALSE(semanticPose.Resolve(pose).empty()); } + + auto errors = model.ValidateGraphs(); + EXPECT_EQ(2u, errors.size()); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "FrameAttachedToGraph pointer is null")); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find( + "PoseRelativeToGraph pointer is null")); } ///////////////////////////////////////////////// diff --git a/src/World.cc b/src/World.cc index 38ac9c1b3..47342a460 100644 --- a/src/World.cc +++ b/src/World.cc @@ -386,6 +386,35 @@ Errors World::Load(sdf::ElementPtr _sdf) return errors; } +///////////////////////////////////////////////// +Errors World::ValidateGraphs() const +{ + Errors errors; + if (!this->dataPtr->frameAttachedToGraph) + { + errors.push_back({ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR, + "FrameAttachedToGraph pointer is null."}); + } + else + { + errors = validateFrameAttachedToGraph(*this->dataPtr->frameAttachedToGraph); + } + + if (!this->dataPtr->poseRelativeToGraph) + { + errors.push_back({ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR, + "PoseRelativeToGraph pointer is null."}); + } + else + { + Errors poseErrors = + validatePoseRelativeToGraph(*this->dataPtr->poseRelativeToGraph); + errors.insert(errors.end(), poseErrors.begin(), poseErrors.end()); + } + + return errors; +} + ///////////////////////////////////////////////// std::string World::Name() const { diff --git a/src/World_TEST.cc b/src/World_TEST.cc index eb608ae3e..ba9b52a31 100644 --- a/src/World_TEST.cc +++ b/src/World_TEST.cc @@ -53,6 +53,17 @@ TEST(DOMWorld, Construction) EXPECT_FALSE(world.FrameNameExists("default")); EXPECT_EQ(1u, world.PhysicsCount()); + + auto errors = world.ValidateGraphs(); + EXPECT_EQ(2u, errors.size()); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "FrameAttachedToGraph pointer is null")); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find( + "PoseRelativeToGraph pointer is null")); } ///////////////////////////////////////////////// diff --git a/test/integration/frame.cc b/test/integration/frame.cc index 02542f232..52238aa14 100644 --- a/test/integration/frame.cc +++ b/test/integration/frame.cc @@ -510,7 +510,67 @@ TEST(DOMFrame, LoadModelFramesInvalidAttachedTo) "causing a graph cycle")); // errors[7] // errors[8] - // errors[9] + EXPECT_EQ(errors[9].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_CYCLE); + EXPECT_NE(std::string::npos, + errors[9].Message().find( + "PoseRelativeToGraph cycle detected, " + "already visited vertex [F4]")); + + // Try loading sdf::Model object + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readFile(testFile, sdfParsed)); + + auto rootElem = sdfParsed->Root(); + ASSERT_NE(nullptr, rootElem); + ASSERT_TRUE(rootElem->HasElement("model")); + auto modelElem = rootElem->GetElement("model"); + ASSERT_NE(nullptr, modelElem); + + // the first 10 errors from loading an sdf::Model match the first 10 errors + // from loading an sdf::Root + sdf::Model model; + auto modelLoadErrors = model.Load(modelElem); + ASSERT_EQ(10u, modelLoadErrors.size()); + for (int i = 0; i < 10; ++i) + { + EXPECT_EQ(errors[i].Code(), modelLoadErrors[i].Code()); + EXPECT_EQ(errors[i].Message(), modelLoadErrors[i].Message()); + } + + errors = model.ValidateGraphs(); + EXPECT_EQ(6u, errors.size()); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "FrameAttachedToGraph error, Non-LINK vertex with name [F3] is " + "disconnected; it should have 1 outgoing edge in MODEL attached_to " + "graph.")) << errors[0]; + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find( + "Graph has __model__ scope but sink vertex named [F3] does not have " + "FrameType LINK or MODEL when starting from vertex with name [F3]")) + << errors[1]; + EXPECT_EQ(errors[2].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_CYCLE); + EXPECT_NE(std::string::npos, + errors[2].Message().find( + "cycle detected, already visited vertex [F4]")) << errors[2]; + EXPECT_EQ(errors[3].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[3].Message().find( + "Vertex with name [F3] is disconnected; it should have " + "1 incoming edge in MODEL relative_to graph")) << errors[3]; + EXPECT_EQ(errors[4].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[4].Message().find( + "frame with name [F3] is disconnected; its source vertex has name [F3], " + "but its source name should be __model__")) << errors[4]; + EXPECT_EQ(errors[5].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_CYCLE); + EXPECT_NE(std::string::npos, + errors[5].Message().find( + "PoseRelativeToGraph cycle detected, " + "already visited vertex [F4]")) << errors[5]; } ///////////////////////////////////////////////// @@ -720,6 +780,7 @@ TEST(DOMFrame, LoadWorldFramesInvalidAttachedTo) "causing a graph cycle")); // errors[2] // errors[3] + // errors[4] EXPECT_EQ(errors[5].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_INVALID); EXPECT_NE(std::string::npos, errors[5].Message().find( @@ -730,9 +791,71 @@ TEST(DOMFrame, LoadWorldFramesInvalidAttachedTo) errors[6].Message().find( "relative_to name[self_cycle] is identical to frame name[self_cycle], " "causing a graph cycle")); - // errors[6] // errors[7] // errors[8] + EXPECT_EQ(errors[9].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_CYCLE); + EXPECT_NE(std::string::npos, + errors[9].Message().find( + "PoseRelativeToGraph cycle detected, " + "already visited vertex [self_cycle]")); + EXPECT_EQ(errors[10].Code(), sdf::ErrorCode::ELEMENT_INVALID); + EXPECT_NE(std::string::npos, + errors[10].Message().find( + "Failed to load a world")); + + // Try loading sdf::World object + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readFile(testFile, sdfParsed)); + + auto rootElem = sdfParsed->Root(); + ASSERT_NE(nullptr, rootElem); + ASSERT_TRUE(rootElem->HasElement("world")); + auto worldElem = rootElem->GetElement("world"); + ASSERT_NE(nullptr, worldElem); + + // the first 10 errors from loading an sdf::World match the first 10 errors + // from loading an sdf::Root + sdf::World world; + auto worldLoadErrors = world.Load(worldElem); + ASSERT_EQ(10u, worldLoadErrors.size()); + for (int i = 0; i < 10; ++i) + { + EXPECT_EQ(errors[i].Code(), worldLoadErrors[i].Code()); + EXPECT_EQ(errors[i].Message(), worldLoadErrors[i].Message()); + } + + errors = world.ValidateGraphs(); + EXPECT_EQ(6u, errors.size()); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "FrameAttachedToGraph error, FRAME vertices in WORLD attached_to graph " + "should have 1 outgoing edge")); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find( + "Graph has world scope but sink vertex named [F] does not have " + "FrameType WORLD or MODEL when starting from vertex with name [F]")); + EXPECT_EQ(errors[2].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_CYCLE); + EXPECT_NE(std::string::npos, + errors[2].Message().find( + "cycle detected, already visited vertex [self_cycle]")); + EXPECT_EQ(errors[3].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[3].Message().find( + "MODEL / FRAME vertex with name [F] is disconnected; it should have " + "1 incoming edge in WORLD relative_to graph")); + EXPECT_EQ(errors[4].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[4].Message().find( + "frame with name [F] is disconnected; its source vertex has name [F], " + "but its source name should be world")); + EXPECT_EQ(errors[5].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_CYCLE); + EXPECT_NE(std::string::npos, + errors[5].Message().find( + "PoseRelativeToGraph cycle detected, " + "already visited vertex [self_cycle]")); } ///////////////////////////////////////////////// diff --git a/test/integration/model_dom.cc b/test/integration/model_dom.cc index 713d4cab0..6bab729d4 100644 --- a/test/integration/model_dom.cc +++ b/test/integration/model_dom.cc @@ -144,6 +144,9 @@ TEST(DOMRoot, LoadDoublePendulum) EXPECT_TRUE(model->JointNameExists("upper_joint")); EXPECT_TRUE(model->JointNameExists("lower_joint")); + + auto graphErrors = model->ValidateGraphs(); + EXPECT_EQ(0u, graphErrors.size()); } ///////////////////////////////////////////////// diff --git a/test/integration/world_dom.cc b/test/integration/world_dom.cc index a59c482ec..878a74f0b 100644 --- a/test/integration/world_dom.cc +++ b/test/integration/world_dom.cc @@ -102,6 +102,8 @@ TEST(DOMWorld, Load) EXPECT_EQ(world->Gravity(), ignition::math::Vector3d(1, 2, 3)); EXPECT_EQ(world->MagneticField(), ignition::math::Vector3d(-1, 0.5, 10)); EXPECT_EQ(testFile, world->Element()->FilePath()); + auto graphErrors = world->ValidateGraphs(); + EXPECT_EQ(0u, graphErrors.size()); const sdf::Atmosphere *atmosphere = world->Atmosphere(); ASSERT_NE(nullptr, atmosphere); From fd84096c6920564acfae88ad13ce0e8a78c74c6f Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Wed, 30 Jun 2021 17:12:13 -0700 Subject: [PATCH 6/8] Add ValidateGraphs methods to Model/World (#601) The graph data is private, so expose methods for checking that the graphs are valid. * Add tests showing graph errors Load an sdf::World or sdf::Model instead of an sdf::Root to see the graph errors. Signed-off-by: Steve Peters --- include/sdf/Model.hh | 6 +++ include/sdf/World.hh | 6 +++ src/FrameSemantics.cc | 18 ++++++++- src/Model.cc | 11 ++++++ src/Model_TEST.cc | 13 +++++++ src/World.cc | 11 ++++++ src/World_TEST.cc | 11 ++++++ test/integration/frame.cc | 73 ++++++++++++++++++++++++++++++++++- test/integration/model_dom.cc | 3 ++ test/integration/world_dom.cc | 2 + 10 files changed, 151 insertions(+), 3 deletions(-) diff --git a/include/sdf/Model.hh b/include/sdf/Model.hh index f9f3f83af..aa85a7b3e 100644 --- a/include/sdf/Model.hh +++ b/include/sdf/Model.hh @@ -67,6 +67,12 @@ namespace sdf /// an error code and message. An empty vector indicates no error. public: Errors Load(sdf::ElementPtr _sdf, const ParserConfig &_config); + /// \brief Check that the FrameAttachedToGraph and PoseRelativeToGraph + /// are valid. + /// \return Errors, which is a vector of Error objects. Each Error includes + /// an error code and message. An empty vector indicates no error. + public: Errors ValidateGraphs() const; + /// \brief Get the name of the model. /// The name of the model should be unique within the scope of a World. /// \return Name of the model. diff --git a/include/sdf/World.hh b/include/sdf/World.hh index 82fa00c97..183e83e2e 100644 --- a/include/sdf/World.hh +++ b/include/sdf/World.hh @@ -70,6 +70,12 @@ namespace sdf /// an error code and message. An empty vector indicates no error. public: Errors Load(sdf::ElementPtr _sdf, const ParserConfig &_config); + /// \brief Check that the FrameAttachedToGraph and PoseRelativeToGraph + /// are valid. + /// \return Errors, which is a vector of Error objects. Each Error includes + /// an error code and message. An empty vector indicates no error. + public: Errors ValidateGraphs() const; + /// \brief Get the name of the world. /// \return Name of the world. public: std::string Name() const; diff --git a/src/FrameSemantics.cc b/src/FrameSemantics.cc index 5b290e7af..496111f18 100644 --- a/src/FrameSemantics.cc +++ b/src/FrameSemantics.cc @@ -1611,6 +1611,14 @@ Errors validateFrameAttachedToGraph( { Errors errors; + // Check if scope points to a valid graph + if (!_in) + { + errors.push_back({ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR, + "FrameAttachedToGraph error: scope does not point to a valid graph."}); + return errors; + } + // Expect ScopeContextName to be either "__model__" or "world" if (_in.ScopeContextName() != "__model__" && _in.ScopeContextName() != "world") @@ -1837,6 +1845,14 @@ Errors validatePoseRelativeToGraph( { Errors errors; + // Check if scope points to a valid graph + if (!_in) + { + errors.push_back({ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR, + "PoseRelativeToGraph error: scope does not point to a valid graph."}); + return errors; + } + // Expect scopeContextName to be either "__model__" or "world" if (_in.ScopeContextName() != "__model__" && _in.ScopeContextName() != "world") @@ -2089,7 +2105,7 @@ Errors resolveFrameAttachedToBody( { errors.push_back({ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR, "Graph has __model__ scope but sink vertex named [" + - sinkVertex.Name() + "] does not have FrameType LINK OR STATIC_MODEL " + sinkVertex.Name() + "] does not have FrameType LINK or STATIC_MODEL " "when starting from vertex with name [" + _vertexName + "]."}); return errors; } diff --git a/src/Model.cc b/src/Model.cc index 8d0bbe1e2..1aa981069 100644 --- a/src/Model.cc +++ b/src/Model.cc @@ -326,6 +326,17 @@ Errors Model::Load(sdf::ElementPtr _sdf, const ParserConfig &_config) return errors; } +///////////////////////////////////////////////// +Errors Model::ValidateGraphs() const +{ + Errors errors = + validateFrameAttachedToGraph(this->dataPtr->frameAttachedToGraph); + Errors poseErrors = + validatePoseRelativeToGraph(this->dataPtr->poseGraph); + errors.insert(errors.end(), poseErrors.begin(), poseErrors.end()); + return errors; +} + ///////////////////////////////////////////////// std::string Model::Name() const { diff --git a/src/Model_TEST.cc b/src/Model_TEST.cc index 837f100ba..06cc2e881 100644 --- a/src/Model_TEST.cc +++ b/src/Model_TEST.cc @@ -138,6 +138,19 @@ TEST(DOMModel, Construction) // expect errors when trying to resolve pose EXPECT_FALSE(semanticPose.Resolve(pose).empty()); } + + auto errors = model.ValidateGraphs(); + EXPECT_EQ(2u, errors.size()); + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "FrameAttachedToGraph error: scope does not point to a valid graph")) + << errors[0]; + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find( + "PoseRelativeToGraph error: scope does not point to a valid graph")) + << errors[1]; } ///////////////////////////////////////////////// diff --git a/src/World.cc b/src/World.cc index bd0822076..d3041cb49 100644 --- a/src/World.cc +++ b/src/World.cc @@ -279,6 +279,17 @@ Errors World::Load(sdf::ElementPtr _sdf, const ParserConfig &_config) return errors; } +///////////////////////////////////////////////// +Errors World::ValidateGraphs() const +{ + Errors errors = + validateFrameAttachedToGraph(this->dataPtr->frameAttachedToGraph); + Errors poseErrors = + validatePoseRelativeToGraph(this->dataPtr->poseRelativeToGraph); + errors.insert(errors.end(), poseErrors.begin(), poseErrors.end()); + return errors; +} + ///////////////////////////////////////////////// std::string World::Name() const { diff --git a/src/World_TEST.cc b/src/World_TEST.cc index 987eed93e..f48e0eca2 100644 --- a/src/World_TEST.cc +++ b/src/World_TEST.cc @@ -59,6 +59,17 @@ TEST(DOMWorld, Construction) EXPECT_FALSE(world.FrameNameExists("default")); EXPECT_EQ(1u, world.PhysicsCount()); + + auto errors = world.ValidateGraphs(); + EXPECT_EQ(2u, errors.size()) << errors; + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "FrameAttachedToGraph error: scope does not point to a valid graph")); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find( + "PoseRelativeToGraph error: scope does not point to a valid graph")); } ///////////////////////////////////////////////// diff --git a/test/integration/frame.cc b/test/integration/frame.cc index 316f27ff3..c5ae76113 100644 --- a/test/integration/frame.cc +++ b/test/integration/frame.cc @@ -507,7 +507,39 @@ TEST(DOMFrame, LoadModelFramesInvalidAttachedTo) "causing a graph cycle")); // errors[7] // errors[8] - // errors[9] + EXPECT_EQ(errors[9].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_CYCLE); + EXPECT_NE(std::string::npos, + errors[9].Message().find( + "PoseRelativeToGraph cycle detected, " + "already visited vertex [model_frame_invalid_attached_to::F4]")); + + // Try loading sdf::Model object + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readFile(testFile, sdfParsed)); + + auto rootElem = sdfParsed->Root(); + ASSERT_NE(nullptr, rootElem); + ASSERT_TRUE(rootElem->HasElement("model")); + auto modelElem = rootElem->GetElement("model"); + ASSERT_NE(nullptr, modelElem); + + // there are no errors when loading an sdf::Model directly since it doesn't + // build graphs + sdf::Model model; + auto modelLoadErrors = model.Load(modelElem); + EXPECT_EQ(0u, modelLoadErrors.size()) << modelLoadErrors; + + errors = model.ValidateGraphs(); + ASSERT_EQ(2u, errors.size()) << errors; + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "FrameAttachedToGraph error: scope does not point to a valid graph")); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find( + "PoseRelativeToGraph error: scope does not point to a valid graph")); } ///////////////////////////////////////////////// @@ -718,6 +750,7 @@ TEST(DOMFrame, LoadWorldFramesInvalidAttachedTo) "causing a graph cycle")); // errors[2] // errors[3] + // errors[4] EXPECT_EQ(errors[5].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_INVALID); EXPECT_NE(std::string::npos, errors[5].Message().find( @@ -728,9 +761,45 @@ TEST(DOMFrame, LoadWorldFramesInvalidAttachedTo) errors[6].Message().find( "relative_to name[self_cycle] is identical to frame name[self_cycle], " "causing a graph cycle")); - // errors[6] // errors[7] // errors[8] + EXPECT_EQ(errors[9].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_CYCLE); + EXPECT_NE(std::string::npos, + errors[9].Message().find( + "PoseRelativeToGraph cycle detected, " + "already visited vertex [self_cycle]")); + EXPECT_EQ(errors[10].Code(), sdf::ErrorCode::ELEMENT_INVALID); + EXPECT_NE(std::string::npos, + errors[10].Message().find( + "Failed to load a world")); + + // Try loading sdf::World object + sdf::SDFPtr sdfParsed(new sdf::SDF()); + sdf::init(sdfParsed); + ASSERT_TRUE(sdf::readFile(testFile, sdfParsed)); + + auto rootElem = sdfParsed->Root(); + ASSERT_NE(nullptr, rootElem); + ASSERT_TRUE(rootElem->HasElement("world")); + auto worldElem = rootElem->GetElement("world"); + ASSERT_NE(nullptr, worldElem); + + // there are no errors when loading an sdf::World directly since it doesn't + // build graphs + sdf::World world; + auto worldLoadErrors = world.Load(worldElem); + EXPECT_EQ(0u, worldLoadErrors.size()) << worldLoadErrors; + + errors = world.ValidateGraphs(); + ASSERT_EQ(2u, errors.size()) << errors; + EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::FRAME_ATTACHED_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[0].Message().find( + "FrameAttachedToGraph error: scope does not point to a valid graph")); + EXPECT_EQ(errors[1].Code(), sdf::ErrorCode::POSE_RELATIVE_TO_GRAPH_ERROR); + EXPECT_NE(std::string::npos, + errors[1].Message().find( + "PoseRelativeToGraph error: scope does not point to a valid graph")); } ///////////////////////////////////////////////// diff --git a/test/integration/model_dom.cc b/test/integration/model_dom.cc index e8931eb0c..ff46d7ec6 100644 --- a/test/integration/model_dom.cc +++ b/test/integration/model_dom.cc @@ -140,6 +140,9 @@ TEST(DOMRoot, LoadDoublePendulum) EXPECT_TRUE(model->JointNameExists("upper_joint")); EXPECT_TRUE(model->JointNameExists("lower_joint")); + + auto graphErrors = model->ValidateGraphs(); + EXPECT_EQ(0u, graphErrors.size()); } ///////////////////////////////////////////////// diff --git a/test/integration/world_dom.cc b/test/integration/world_dom.cc index c119aa246..1e1aa1ab7 100644 --- a/test/integration/world_dom.cc +++ b/test/integration/world_dom.cc @@ -97,6 +97,8 @@ TEST(DOMWorld, Load) EXPECT_EQ(world->Gravity(), ignition::math::Vector3d(1, 2, 3)); EXPECT_EQ(world->MagneticField(), ignition::math::Vector3d(-1, 0.5, 10)); EXPECT_EQ(testFile, world->Element()->FilePath()); + auto graphErrors = world->ValidateGraphs(); + EXPECT_EQ(0u, graphErrors.size()); const sdf::Atmosphere *atmosphere = world->Atmosphere(); ASSERT_NE(nullptr, atmosphere); From 4e9f2eb3244e1c218f9fe31284ecf92a93379bff Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Thu, 1 Jul 2021 17:10:42 -0500 Subject: [PATCH 7/8] =?UTF-8?q?=F0=9F=8E=88=2011.2.2=20(#616)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Prepare for 11.2.2 Signed-off-by: Steven Peters Co-authored-by: Steve Peters --- CMakeLists.txt | 2 +- Changelog.md | 11 +++++++++++ 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8acbd36ea..368d9252a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -28,7 +28,7 @@ set (SDF_PROTOCOL_VERSION 1.8) set (SDF_MAJOR_VERSION 11) set (SDF_MINOR_VERSION 2) -set (SDF_PATCH_VERSION 1) +set (SDF_PATCH_VERSION 2) set (SDF_VERSION ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}) set (SDF_VERSION_FULL ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}.${SDF_PATCH_VERSION}) diff --git a/Changelog.md b/Changelog.md index 9dd94e68f..319a43a82 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,6 +2,17 @@ ### libsdformat 11.X.X (202X-XX-XX) +### libsdformat 11.2.2 (2021-07-01) + +1. Fix segfault when checking for required elements in joint + * [Pull request #610](https://github.com/ignitionrobotics/sdformat/pull/610) + +1. Add ValidateGraphs methods to Model/World + * [Pull request #601](https://github.com/ignitionrobotics/sdformat/pull/601) + +1. Making `PrintValues()` and `ToString()` able to not print default elements + * [Pull request #575](https://github.com/ignitionrobotics/sdformat/pull/575) + ### libsdformat 11.2.1 (2021-06-28) 1. Fix ABI break on sdf11 From cb6cd03eadcca179ab6a35e5d3da2d48a7250fa7 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Tue, 13 Jul 2021 12:24:14 -0700 Subject: [PATCH 8/8] Error: move << operator from .hh to .cc file (#623) * Error: move << operator from .hh to .cc file Signed-off-by: Steven Peters * Fix visibility Signed-off-by: Addisu Z. Taddese Co-authored-by: Addisu Z. Taddese --- include/sdf/Error.hh | 26 ++------------------------ src/Error.cc | 33 +++++++++++++++++++++++++++++++++ 2 files changed, 35 insertions(+), 24 deletions(-) diff --git a/include/sdf/Error.hh b/include/sdf/Error.hh index 5d8cfe101..420626109 100644 --- a/include/sdf/Error.hh +++ b/include/sdf/Error.hh @@ -221,30 +221,8 @@ namespace sdf /// \param[in,out] _out The output stream. /// \param[in] _err The error to output. /// \return Reference to the given output stream - public: friend std::ostream &operator<<(std::ostream &_out, - const sdf::Error &_err) - { - std::string pathInfo = ""; - - if (_err.XmlPath().has_value()) - pathInfo += _err.XmlPath().value(); - - if (_err.FilePath().has_value()) - pathInfo += ":" + _err.FilePath().value(); - - if (_err.LineNumber().has_value()) - pathInfo += ":L" + std::to_string(_err.LineNumber().value()); - - if (!pathInfo.empty()) - pathInfo = "[" + pathInfo + "]: "; - - _out << "Error Code " - << static_cast::type>( - _err.Code()) << ": " - << pathInfo - << "Msg: " << _err.Message(); - return _out; - } + public: friend SDFORMAT_VISIBLE std::ostream &operator<<( + std::ostream &_out, const sdf::Error &_err); /// \brief Private data pointer. IGN_UTILS_IMPL_PTR(dataPtr) diff --git a/src/Error.cc b/src/Error.cc index 578857c0c..de8ea66de 100644 --- a/src/Error.cc +++ b/src/Error.cc @@ -120,3 +120,36 @@ bool Error::operator==(const bool _value) const return ((this->dataPtr->code != ErrorCode::NONE) && _value) || ((this->dataPtr->code == ErrorCode::NONE) && !_value); } + +namespace sdf +{ +// Inline bracket to help doxygen filtering. +inline namespace SDF_VERSION_NAMESPACE { + +///////////////////////////////////////////////// +// cppcheck-suppress unusedFunction +std::ostream &operator<<(std::ostream &_out, const sdf::Error &_err) +{ + std::string pathInfo = ""; + + if (_err.XmlPath().has_value()) + pathInfo += _err.XmlPath().value(); + + if (_err.FilePath().has_value()) + pathInfo += ":" + _err.FilePath().value(); + + if (_err.LineNumber().has_value()) + pathInfo += ":L" + std::to_string(_err.LineNumber().value()); + + if (!pathInfo.empty()) + pathInfo = "[" + pathInfo + "]: "; + + _out << "Error Code " + << static_cast::type>( + _err.Code()) << ": " + << pathInfo + << "Msg: " << _err.Message(); + return _out; +} +} +}