Skip to content

Commit

Permalink
Added line number support to Element
Browse files Browse the repository at this point in the history
Signed-off-by: Aaron Chong <[email protected]>
  • Loading branch information
aaronchongth committed May 3, 2021
1 parent ece5cb0 commit 1ae7778
Show file tree
Hide file tree
Showing 4 changed files with 44 additions and 1 deletion.
12 changes: 12 additions & 0 deletions include/sdf/Element.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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<int> 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"])
Expand Down Expand Up @@ -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<int> lineNumber;

/// \brief XML path of this element.
public: std::string xmlPath;

Expand Down
2 changes: 1 addition & 1 deletion include/sdf/Error.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string> FilePath() const;
Expand Down
15 changes: 15 additions & 0 deletions src/Element.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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();
}

Expand Down Expand Up @@ -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<int> Element::LineNumber() const
{
return this->dataPtr->lineNumber;
}

/////////////////////////////////////////////////
void Element::SetXmlPath(const std::string &_path)
{
Expand Down
16 changes: 16 additions & 0 deletions src/Element_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ TEST(Element, Child)
sdf::Element child;
sdf::ElementPtr parent = std::make_shared<sdf::Element>();
parent->SetFilePath("/parent/path/model.sdf");
parent->SetLineNumber(12);
parent->SetXmlPath("/sdf/world[@name=\"default\"");
parent->SetOriginalVersion("1.5");

Expand Down Expand Up @@ -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");

Expand All @@ -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);
Expand All @@ -318,12 +322,15 @@ TEST(Element, ClearElements)
sdf::ElementPtr child = std::make_shared<sdf::Element>();

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);
Expand All @@ -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());
}

Expand All @@ -344,12 +353,15 @@ TEST(Element, Clear)
sdf::ElementPtr child = std::make_shared<sdf::Element>();

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);
Expand All @@ -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());
}
Expand Down Expand Up @@ -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");
Expand All @@ -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());

Expand Down

0 comments on commit 1ae7778

Please sign in to comment.