From 1ae7778af7d727359a936b627beb52ef2e865ee8 Mon Sep 17 00:00:00 2001 From: Aaron Chong Date: Mon, 3 May 2021 19:54:30 +0800 Subject: [PATCH] Added line number support to Element Signed-off-by: Aaron Chong --- include/sdf/Element.hh | 12 ++++++++++++ include/sdf/Error.hh | 2 +- src/Element.cc | 15 +++++++++++++++ src/Element_TEST.cc | 16 ++++++++++++++++ 4 files changed, 44 insertions(+), 1 deletion(-) diff --git a/include/sdf/Element.hh b/include/sdf/Element.hh index 7a474ace9..024505c85 100644 --- a/include/sdf/Element.hh +++ b/include/sdf/Element.hh @@ -405,6 +405,15 @@ namespace sdf /// \return Full path to SDF document. public: const std::string &FilePath() const; + /// \brief Set the line number of this element within the SDF document. + /// \param[in] _lineNumber Line number of element. + public: void SetLineNumber(int _lineNumber); + + /// \brief Get the line number of this element within the SDF document. + /// \return Line number of this element if it has been set, nullopt + /// otherwise. + public: std::optional LineNumber() const; + /// \brief Set the XML path of this element. /// \param[in] _path Full XML path to the SDF element. (e.g. /// /sdf/world[@name="default"]/model[@name="robot1"]/link[@name="link"]) @@ -532,6 +541,9 @@ namespace sdf /// \brief Path to file where this element came from public: std::string path; + /// \brief Line number in file where this element came from + public: std::optional lineNumber; + /// \brief XML path of this element. public: std::string xmlPath; diff --git a/include/sdf/Error.hh b/include/sdf/Error.hh index 2e9186ba4..11e6c243a 100644 --- a/include/sdf/Error.hh +++ b/include/sdf/Error.hh @@ -183,7 +183,7 @@ namespace sdf /// \return Error message. public: std::string Message() const; - /// \brief Get the file path that is associated with this error. + /// \brief Get the file path associated with this error. /// \return Returns the path of the file that this error is related to, /// nullopt otherwise. public: std::optional FilePath() const; diff --git a/src/Element.cc b/src/Element.cc index a82bd15c9..c71991ad9 100644 --- a/src/Element.cc +++ b/src/Element.cc @@ -167,6 +167,7 @@ ElementPtr Element::Clone() const clone->dataPtr->includeFilename = this->dataPtr->includeFilename; clone->dataPtr->referenceSDF = this->dataPtr->referenceSDF; clone->dataPtr->path = this->dataPtr->path; + clone->dataPtr->lineNumber = this->dataPtr->lineNumber; clone->dataPtr->xmlPath = this->dataPtr->xmlPath; clone->dataPtr->originalVersion = this->dataPtr->originalVersion; @@ -215,6 +216,7 @@ void Element::Copy(const ElementPtr _elem) this->dataPtr->referenceSDF = _elem->ReferenceSDF(); this->dataPtr->originalVersion = _elem->OriginalVersion(); this->dataPtr->path = _elem->FilePath(); + this->dataPtr->lineNumber = _elem->LineNumber(); this->dataPtr->xmlPath = _elem->XmlPath(); for (Param_V::iterator iter = _elem->dataPtr->attributes.begin(); @@ -848,6 +850,7 @@ void Element::Clear() this->ClearElements(); this->dataPtr->originalVersion.clear(); this->dataPtr->path.clear(); + this->dataPtr->lineNumber = std::nullopt; this->dataPtr->xmlPath.clear(); } @@ -956,6 +959,18 @@ const std::string &Element::FilePath() const return this->dataPtr->path; } +///////////////////////////////////////////////// +void Element::SetLineNumber(int _lineNumber) +{ + this->dataPtr->lineNumber = _lineNumber; +} + +///////////////////////////////////////////////// +std::optional Element::LineNumber() const +{ + return this->dataPtr->lineNumber; +} + ///////////////////////////////////////////////// void Element::SetXmlPath(const std::string &_path) { diff --git a/src/Element_TEST.cc b/src/Element_TEST.cc index 2ac57ac88..ddc9c1476 100644 --- a/src/Element_TEST.cc +++ b/src/Element_TEST.cc @@ -37,6 +37,7 @@ TEST(Element, Child) sdf::Element child; sdf::ElementPtr parent = std::make_shared(); parent->SetFilePath("/parent/path/model.sdf"); + parent->SetLineNumber(12); parent->SetXmlPath("/sdf/world[@name=\"default\""); parent->SetOriginalVersion("1.5"); @@ -292,6 +293,7 @@ TEST(Element, Clone) parent->AddValue("string", "foo", false, "foo description"); parent->SetFilePath("/path/to/file.sdf"); + parent->SetLineNumber(12); parent->SetXmlPath("/sdf/world[@name=\"default\""); parent->SetOriginalVersion("1.5"); @@ -302,6 +304,8 @@ TEST(Element, Clone) sdf::ElementPtr newelem = parent->Clone(); EXPECT_EQ("/path/to/file.sdf", newelem->FilePath()); + ASSERT_TRUE(newelem->LineNumber().has_value()); + EXPECT_EQ(12, newelem->LineNumber().value()); EXPECT_EQ("/sdf/world[@name=\"default\"", newelem->XmlPath()); EXPECT_EQ("1.5", newelem->OriginalVersion()); ASSERT_NE(newelem->GetFirstElement(), nullptr); @@ -318,12 +322,15 @@ TEST(Element, ClearElements) sdf::ElementPtr child = std::make_shared(); parent->SetFilePath("/path/to/file.sdf"); + parent->SetLineNumber(12); parent->SetXmlPath("/sdf/world[@name=\"default\""); parent->SetOriginalVersion("1.5"); child->SetParent(parent); parent->InsertElement(child); EXPECT_EQ("/path/to/file.sdf", parent->FilePath()); + ASSERT_TRUE(parent->LineNumber().has_value()); + EXPECT_EQ(12, parent->LineNumber().value()); EXPECT_EQ("/sdf/world[@name=\"default\"", parent->XmlPath()); EXPECT_EQ("1.5", parent->OriginalVersion()); ASSERT_NE(parent->GetFirstElement(), nullptr); @@ -334,6 +341,8 @@ TEST(Element, ClearElements) ASSERT_EQ(parent->GetFirstElement(), nullptr); EXPECT_EQ("/path/to/file.sdf", parent->FilePath()); + ASSERT_TRUE(parent->LineNumber().has_value()); + EXPECT_EQ(12, parent->LineNumber().value()); EXPECT_EQ("1.5", parent->OriginalVersion()); } @@ -344,12 +353,15 @@ TEST(Element, Clear) sdf::ElementPtr child = std::make_shared(); parent->SetFilePath("/path/to/file.sdf"); + parent->SetLineNumber(12); parent->SetXmlPath("/sdf/world[@name=\"default\""); parent->SetOriginalVersion("1.5"); child->SetParent(parent); parent->InsertElement(child); EXPECT_EQ("/path/to/file.sdf", parent->FilePath()); + ASSERT_TRUE(parent->LineNumber().has_value()); + EXPECT_EQ(12, parent->LineNumber().value()); EXPECT_EQ("/sdf/world[@name=\"default\"", parent->XmlPath()); EXPECT_EQ("1.5", parent->OriginalVersion()); ASSERT_NE(parent->GetFirstElement(), nullptr); @@ -360,6 +372,7 @@ TEST(Element, Clear) ASSERT_EQ(parent->GetFirstElement(), nullptr); EXPECT_TRUE(parent->FilePath().empty()); + EXPECT_FALSE(parent->LineNumber().has_value()); EXPECT_TRUE(parent->XmlPath().empty()); EXPECT_TRUE(parent->OriginalVersion().empty()); } @@ -575,6 +588,7 @@ TEST(Element, Copy) src->SetName("test"); src->SetFilePath("/path/to/file.sdf"); + src->SetLineNumber(12); src->SetXmlPath("/sdf/world[@name=\"default\""); src->SetOriginalVersion("1.5"); src->AddValue("string", "val", false, "val description"); @@ -588,6 +602,8 @@ TEST(Element, Copy) dest->Copy(src); EXPECT_EQ("/path/to/file.sdf", dest->FilePath()); + ASSERT_TRUE(dest->LineNumber().has_value()); + EXPECT_EQ(12, dest->LineNumber().value()); EXPECT_EQ("/sdf/world[@name=\"default\"", dest->XmlPath()); EXPECT_EQ("1.5", dest->OriginalVersion());