Skip to content

Commit

Permalink
9 ➡️ 10 (#593)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Jun 16, 2021
2 parents bf1c809 + a721338 commit d0e195f
Show file tree
Hide file tree
Showing 9 changed files with 338 additions and 2 deletions.
14 changes: 14 additions & 0 deletions include/sdf/Element.hh
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,17 @@ namespace sdf
/// \sa Element::SetRequired
public: const std::string &GetRequired() const;

/// \brief Set if the element and children where set or default
/// in the original file. This is meant to be used by the parser to
/// indicate whether the element was set by the user in the original
/// file or added by default during parsing.
/// \param[in] _value True if the element was set
public: void SetExplicitlySetInFile(const bool _value);

/// \brief Return if the element was been explicitly set in the file
/// \return True if the element was set in the file
public: bool GetExplicitlySetInFile() const;

/// \brief Set whether this element should copy its child elements
/// during parsing.
/// \param[in] _value True to copy Element's children.
Expand Down Expand Up @@ -465,6 +476,9 @@ 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;

Expand Down
22 changes: 22 additions & 0 deletions src/Element.cc
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ Element::Element()
{
this->dataPtr->copyChildren = false;
this->dataPtr->referenceSDF = "";
this->dataPtr->explicitlySetInFile = true;
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -93,6 +94,25 @@ void Element::SetCopyChildren(bool _value)
this->dataPtr->copyChildren = _value;
}

/////////////////////////////////////////////////
void Element::SetExplicitlySetInFile(const bool _value)
{
this->dataPtr->explicitlySetInFile = _value;

ElementPtr_V::const_iterator eiter;
for (eiter = this->dataPtr->elements.begin();
eiter != this->dataPtr->elements.end(); ++eiter)
{
(*eiter)->SetExplicitlySetInFile(_value);
}
}

/////////////////////////////////////////////////
bool Element::GetExplicitlySetInFile() const
{
return this->dataPtr->explicitlySetInFile;
}

/////////////////////////////////////////////////
bool Element::GetCopyChildren() const
{
Expand Down Expand Up @@ -168,6 +188,7 @@ ElementPtr Element::Clone() const
clone->dataPtr->referenceSDF = this->dataPtr->referenceSDF;
clone->dataPtr->path = this->dataPtr->path;
clone->dataPtr->originalVersion = this->dataPtr->originalVersion;
clone->dataPtr->explicitlySetInFile = this->dataPtr->explicitlySetInFile;

Param_V::const_iterator aiter;
for (aiter = this->dataPtr->attributes.begin();
Expand Down Expand Up @@ -209,6 +230,7 @@ void Element::Copy(const ElementPtr _elem)
this->dataPtr->referenceSDF = _elem->ReferenceSDF();
this->dataPtr->originalVersion = _elem->OriginalVersion();
this->dataPtr->path = _elem->FilePath();
this->dataPtr->explicitlySetInFile = _elem->GetExplicitlySetInFile();

for (Param_V::iterator iter = _elem->dataPtr->attributes.begin();
iter != _elem->dataPtr->attributes.end(); ++iter)
Expand Down
94 changes: 94 additions & 0 deletions src/Element_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,98 @@ TEST(Element, Required)
ASSERT_EQ(elem.GetRequired(), "1");
}

/////////////////////////////////////////////////
TEST(Element, SetExplicitlySetInFile)
{
// The heirarchy in xml:
// <parent>
// <elem>
// <child>
// <child2>
// <grandChild/>
// <child2>
// </child>
// <sibling/>
// <sibling2/>
// </elem>
// <elem2/>
// </parent>

sdf::ElementPtr parent = std::make_shared<sdf::Element>();
sdf::ElementPtr elem = std::make_shared<sdf::Element>();
elem->SetParent(parent);
parent->InsertElement(elem);
sdf::ElementPtr elem2 = std::make_shared<sdf::Element>();
elem2->SetParent(parent);
parent->InsertElement(elem2);

EXPECT_TRUE(elem->GetExplicitlySetInFile());

elem->SetExplicitlySetInFile(false);

EXPECT_FALSE(elem->GetExplicitlySetInFile());

elem->SetExplicitlySetInFile(true);

EXPECT_TRUE(elem->GetExplicitlySetInFile());

// the childs and siblings of the element should all be
// set to the same value when using this function
sdf::ElementPtr child = std::make_shared<sdf::Element>();
child->SetParent(elem);
elem->InsertElement(child);

sdf::ElementPtr sibling = std::make_shared<sdf::Element>();
sibling->SetParent(elem);
elem->InsertElement(sibling);

sdf::ElementPtr sibling2 = std::make_shared<sdf::Element>();
sibling2->SetParent(elem);
elem->InsertElement(sibling2);

sdf::ElementPtr child2 = std::make_shared<sdf::Element>();
child2->SetParent(child);
child->InsertElement(child2);

sdf::ElementPtr grandChild = std::make_shared<sdf::Element>();
grandChild->SetParent(child);
child->InsertElement(grandChild);

EXPECT_TRUE(elem->GetExplicitlySetInFile());
EXPECT_TRUE(child->GetExplicitlySetInFile());
EXPECT_TRUE(sibling->GetExplicitlySetInFile());
EXPECT_TRUE(sibling2->GetExplicitlySetInFile());
EXPECT_TRUE(child2->GetExplicitlySetInFile());
EXPECT_TRUE(grandChild->GetExplicitlySetInFile());
EXPECT_TRUE(elem2->GetExplicitlySetInFile());

elem->SetExplicitlySetInFile(false);
EXPECT_FALSE(elem->GetExplicitlySetInFile());
EXPECT_FALSE(child->GetExplicitlySetInFile());
EXPECT_FALSE(sibling->GetExplicitlySetInFile());
EXPECT_FALSE(sibling2->GetExplicitlySetInFile());
EXPECT_FALSE(child2->GetExplicitlySetInFile());
EXPECT_FALSE(grandChild->GetExplicitlySetInFile());

// SetExplicitlySetInFile(false) is be called only on `elem`. We expect
// GetExplicitlySetInFile() to be false for all children and grandchildren of
// `elem`, but true for `elem2`, which is a sibling of `elem`.
EXPECT_TRUE(elem2->GetExplicitlySetInFile());
}

/////////////////////////////////////////////////
TEST(Element, SetExplicitlySetInFileWithInsert)
{
sdf::ElementPtr parent = std::make_shared<sdf::Element>();
parent->SetExplicitlySetInFile(false);
sdf::ElementPtr child = std::make_shared<sdf::Element>();
child->SetParent(parent);
parent->InsertElement(child);

EXPECT_FALSE(parent->GetExplicitlySetInFile());
EXPECT_TRUE(child->GetExplicitlySetInFile());
}

/////////////////////////////////////////////////
TEST(Element, CopyChildren)
{
Expand Down Expand Up @@ -317,6 +409,7 @@ TEST(Element, Clone)
ASSERT_NE(newelem->GetFirstElement(), nullptr);
ASSERT_EQ(newelem->GetElementDescriptionCount(), 1UL);
ASSERT_EQ(newelem->GetAttributeCount(), 1UL);
ASSERT_TRUE(newelem->GetExplicitlySetInFile());
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -594,6 +687,7 @@ TEST(Element, Copy)
ASSERT_EQ(param->GetDescription(), "val description");

ASSERT_EQ(dest->GetAttributeCount(), 1UL);
ASSERT_TRUE(dest->GetExplicitlySetInFile());
param = dest->GetAttribute("test");
ASSERT_TRUE(param->IsType<std::string>());
ASSERT_EQ(param->GetKey(), "test");
Expand Down
3 changes: 2 additions & 1 deletion src/parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1160,7 +1160,8 @@ bool readXml(tinyxml2::XMLElement *_xml, ElementPtr _sdf, Errors &_errors)
else
{
// Add default element
_sdf->AddElement(elemDesc->GetName());
ElementPtr defaultElement = _sdf->AddElement(elemDesc->GetName());
defaultElement->SetExplicitlySetInFile(false);
}
}
}
Expand Down
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ set(tests
cfm_damping_implicit_spring_damper.cc
collision_dom.cc
converter.cc
default_elements.cc
deprecated_specs.cc
disable_fixed_joint_reduction.cc
fixed_joint_reduction.cc
Expand Down
155 changes: 155 additions & 0 deletions test/integration/default_elements.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
/*
* Copyright 2017 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 <iostream>
#include <string>
#include <gtest/gtest.h>

#include "sdf/SDFImpl.hh"
#include "sdf/parser.hh"
#include "sdf/Frame.hh"
#include "sdf/Model.hh"
#include "sdf/Root.hh"
#include "sdf/World.hh"
#include "sdf/Filesystem.hh"
#include "test_config.h"

//////////////////////////////////////////////////
TEST(ExplicitlySetInFile, EmptyRoadSphCoords)
{
const std::string test_file =
sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf",
"empty_road_sph_coords.sdf");

sdf::Root root;
sdf::Errors errors = root.Load(test_file);
EXPECT_TRUE(errors.empty());

sdf::ElementPtr rootPtr = root.Element();
EXPECT_TRUE(rootPtr->GetExplicitlySetInFile());

sdf::ElementPtr worldPtr = rootPtr->GetFirstElement();
EXPECT_TRUE(worldPtr->GetExplicitlySetInFile());

sdf::ElementPtr roadPtr = worldPtr->GetFirstElement();
EXPECT_TRUE(roadPtr->GetExplicitlySetInFile());

sdf::ElementPtr roadWidthPtr = roadPtr->GetFirstElement();
EXPECT_FALSE(roadWidthPtr->GetExplicitlySetInFile());

sdf::ElementPtr roadPointPtr = roadWidthPtr->GetNextElement();
EXPECT_FALSE(roadPointPtr->GetExplicitlySetInFile());

sdf::ElementPtr sphericalCoordsPtr = roadPtr->GetNextElement();
EXPECT_TRUE(sphericalCoordsPtr->GetExplicitlySetInFile());

sdf::ElementPtr surfaceModel = sphericalCoordsPtr->GetFirstElement();
EXPECT_FALSE(surfaceModel->GetExplicitlySetInFile());

sdf::ElementPtr latitudeDegPtr = surfaceModel->GetNextElement();
EXPECT_FALSE(latitudeDegPtr->GetExplicitlySetInFile());

sdf::ElementPtr longitudeDegPtr = latitudeDegPtr->GetNextElement();
EXPECT_FALSE(longitudeDegPtr->GetExplicitlySetInFile());

sdf::ElementPtr elevationPtr = longitudeDegPtr->GetNextElement();
EXPECT_FALSE(elevationPtr->GetExplicitlySetInFile());

sdf::ElementPtr headingDegPtr = elevationPtr->GetNextElement();
EXPECT_FALSE(headingDegPtr->GetExplicitlySetInFile());

sdf::ElementPtr gravityPtr = sphericalCoordsPtr->GetNextElement();
EXPECT_FALSE(gravityPtr->GetExplicitlySetInFile());

sdf::ElementPtr magneticFieldPtr = gravityPtr->GetNextElement();
EXPECT_FALSE(magneticFieldPtr->GetExplicitlySetInFile());

sdf::ElementPtr atmosphereTypePtr = magneticFieldPtr->GetNextElement();
EXPECT_FALSE(atmosphereTypePtr->GetExplicitlySetInFile());

sdf::ElementPtr physicsPtr = atmosphereTypePtr->GetNextElement();
EXPECT_FALSE(physicsPtr->GetExplicitlySetInFile());

sdf::ElementPtr maxStepSizePtr = physicsPtr->GetFirstElement();
EXPECT_FALSE(maxStepSizePtr->GetExplicitlySetInFile());

sdf::ElementPtr realTimeFactorPtr = maxStepSizePtr->GetNextElement();
EXPECT_FALSE(realTimeFactorPtr->GetExplicitlySetInFile());

sdf::ElementPtr realTimeUpdate = realTimeFactorPtr->GetNextElement();
EXPECT_FALSE(realTimeUpdate->GetExplicitlySetInFile());

sdf::ElementPtr scenePtr = physicsPtr->GetNextElement();
EXPECT_FALSE(scenePtr->GetExplicitlySetInFile());

sdf::ElementPtr ambientPtr = scenePtr->GetFirstElement();
EXPECT_FALSE(ambientPtr->GetExplicitlySetInFile());

sdf::ElementPtr backgroundPtr = ambientPtr->GetNextElement();
EXPECT_FALSE(backgroundPtr->GetExplicitlySetInFile());

sdf::ElementPtr shadowsPtr = backgroundPtr->GetNextElement();
EXPECT_FALSE(shadowsPtr->GetExplicitlySetInFile());
}

//////////////////////////////////////////////////
TEST(ExplicitlySetInFile, EmptyAxis)
{
const std::string test_file =
sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf",
"empty_axis.sdf");

sdf::Root root;
sdf::Errors errors = root.Load(test_file);
EXPECT_TRUE(errors.empty());

sdf::ElementPtr rootPtr = root.Element();
EXPECT_TRUE(rootPtr->GetExplicitlySetInFile());

sdf::ElementPtr modelPtr = rootPtr->GetFirstElement();
EXPECT_TRUE(modelPtr->GetExplicitlySetInFile());

sdf::ElementPtr link1Ptr = modelPtr->GetFirstElement();
EXPECT_TRUE(link1Ptr->GetExplicitlySetInFile());

sdf::ElementPtr link2Ptr = link1Ptr->GetNextElement();
EXPECT_TRUE(link2Ptr->GetExplicitlySetInFile());

sdf::ElementPtr jointPtr = link2Ptr->GetNextElement();
EXPECT_TRUE(jointPtr->GetExplicitlySetInFile());

sdf::ElementPtr parentPtr = jointPtr->GetFirstElement();
EXPECT_TRUE(parentPtr->GetExplicitlySetInFile());

sdf::ElementPtr childPtr = parentPtr->GetNextElement();
EXPECT_TRUE(childPtr->GetExplicitlySetInFile());

sdf::ElementPtr axisPtr = childPtr->GetNextElement();
EXPECT_TRUE(axisPtr->GetExplicitlySetInFile());

sdf::ElementPtr xyzPtr = axisPtr->GetFirstElement();
EXPECT_FALSE(xyzPtr->GetExplicitlySetInFile());

sdf::ElementPtr limitPtr = xyzPtr->GetNextElement();
EXPECT_FALSE(limitPtr->GetExplicitlySetInFile());

sdf::ElementPtr lowerLimitPtr = limitPtr->GetFirstElement();
EXPECT_FALSE(lowerLimitPtr->GetExplicitlySetInFile());

sdf::ElementPtr upperLimitPtr = lowerLimitPtr->GetNextElement();
EXPECT_FALSE(upperLimitPtr->GetExplicitlySetInFile());
}
19 changes: 19 additions & 0 deletions test/sdf/empty_axis.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0" ?>
<!--Commented elements are defaults that will be added during parsing-->
<sdf version="1.6">
<model name="empty_axis">
<link name="link1" />
<link name="link2" />
<joint name="joint" type="fixed">
<parent>link1</parent>
<child>link2</child>
<axis>
<!-- <xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit> -->
</axis>
</joint>
</model>
</sdf>
Loading

0 comments on commit d0e195f

Please sign in to comment.