diff --git a/Changelog.md b/Changelog.md
index 09e991292..4988ea99d 100644
--- a/Changelog.md
+++ b/Changelog.md
@@ -167,6 +167,17 @@
## libsdformat 10.X
+### libsdformat 10.5.0 (2021-05-17)
+
+1. Add scatter ratio parameter to Particle Emitter DOM.
+ + [Pull request 547](https://github.com/osrf/sdformat/pull/547)
+
+1. Methods for removing attributes from an element.
+ + [Pull request 555](https://github.com/osrf/sdformat/pull/555)
+
+1. Improve docs of collision bitmask.
+ + [Pull request 521](https://github.com/osrf/sdformat/pull/521)
+
### libsdformat 10.4.0 (2021-04-06)
1. Added particle emitter.
diff --git a/include/sdf/Element.hh b/include/sdf/Element.hh
index 23e8e0497..41d2c51e5 100644
--- a/include/sdf/Element.hh
+++ b/include/sdf/Element.hh
@@ -113,6 +113,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.
@@ -508,6 +519,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;
diff --git a/include/sdf/ParticleEmitter.hh b/include/sdf/ParticleEmitter.hh
index c5fa6450e..9f5e58ecf 100644
--- a/include/sdf/ParticleEmitter.hh
+++ b/include/sdf/ParticleEmitter.hh
@@ -254,6 +254,17 @@ namespace sdf
/// \param[in] _topic The topic used to update the particle emitter.
public: void SetTopic(const std::string &_topic);
+ /// \brief Get the particle scatter ratio. This is used to determine the
+ /// ratio of particles that will be detected by sensors.
+ /// \return Particle scatter ratio
+ /// \sa SetScatterRatio
+ public: float ScatterRatio() const;
+
+ /// \brief Set the particle scatter ratio. This is used to determine the
+ /// ratio of particles that will be detected by sensors.
+ /// \param[in] _ratio Scatter ratio.
+ public: void SetScatterRatio(float _ratio);
+
/// \brief Get the pose of the particle emitter. This is the pose of the
/// emitter as specified in SDF
/// ( ... ).
diff --git a/sdf/1.7/particle_emitter.sdf b/sdf/1.7/particle_emitter.sdf
index 428ed251e..d6a2fdf7e 100644
--- a/sdf/1.7/particle_emitter.sdf
+++ b/sdf/1.7/particle_emitter.sdf
@@ -104,6 +104,17 @@
+
+
+ This is used to determine the ratio of particles that will be detected
+ by sensors. Increasing the ratio means there is a higher chance of
+ particles reflecting and interfering with depth sensing, making the
+ emitter appear more dense. Decreasing the ratio decreases the chance
+ of particles reflecting and interfering with depth sensing, making it
+ appear less dense.
+
+
+
diff --git a/src/Element.cc b/src/Element.cc
index e9e68fb13..b1383dcd6 100644
--- a/src/Element.cc
+++ b/src/Element.cc
@@ -31,6 +31,7 @@ Element::Element()
{
this->dataPtr->copyChildren = false;
this->dataPtr->referenceSDF = "";
+ this->dataPtr->explicitlySetInFile = true;
}
/////////////////////////////////////////////////
@@ -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
{
@@ -170,6 +190,7 @@ ElementPtr Element::Clone() const
clone->dataPtr->lineNumber = this->dataPtr->lineNumber;
clone->dataPtr->xmlPath = this->dataPtr->xmlPath;
clone->dataPtr->originalVersion = this->dataPtr->originalVersion;
+ clone->dataPtr->explicitlySetInFile = this->dataPtr->explicitlySetInFile;
Param_V::const_iterator aiter;
for (aiter = this->dataPtr->attributes.begin();
@@ -218,6 +239,7 @@ void Element::Copy(const ElementPtr _elem)
this->dataPtr->path = _elem->FilePath();
this->dataPtr->lineNumber = _elem->LineNumber();
this->dataPtr->xmlPath = _elem->XmlPath();
+ this->dataPtr->explicitlySetInFile = _elem->GetExplicitlySetInFile();
for (Param_V::iterator iter = _elem->dataPtr->attributes.begin();
iter != _elem->dataPtr->attributes.end(); ++iter)
diff --git a/src/Element_TEST.cc b/src/Element_TEST.cc
index 47eb5ad08..2e2404a59 100644
--- a/src/Element_TEST.cc
+++ b/src/Element_TEST.cc
@@ -72,6 +72,98 @@ TEST(Element, Required)
ASSERT_EQ(elem.GetRequired(), "1");
}
+/////////////////////////////////////////////////
+TEST(Element, SetExplicitlySetInFile)
+{
+ // The heirarchy in xml:
+ //
+ //
+ //
+ //
+ //
+ //
+ //
+ //
+ //
+ //
+ //
+ //
+
+ sdf::ElementPtr parent = std::make_shared();
+ sdf::ElementPtr elem = std::make_shared();
+ elem->SetParent(parent);
+ parent->InsertElement(elem);
+ sdf::ElementPtr elem2 = std::make_shared();
+ 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();
+ child->SetParent(elem);
+ elem->InsertElement(child);
+
+ sdf::ElementPtr sibling = std::make_shared();
+ sibling->SetParent(elem);
+ elem->InsertElement(sibling);
+
+ sdf::ElementPtr sibling2 = std::make_shared();
+ sibling2->SetParent(elem);
+ elem->InsertElement(sibling2);
+
+ sdf::ElementPtr child2 = std::make_shared();
+ child2->SetParent(child);
+ child->InsertElement(child2);
+
+ sdf::ElementPtr grandChild = std::make_shared();
+ 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();
+ parent->SetExplicitlySetInFile(false);
+ sdf::ElementPtr child = std::make_shared();
+ child->SetParent(parent);
+ parent->InsertElement(child);
+
+ EXPECT_FALSE(parent->GetExplicitlySetInFile());
+ EXPECT_TRUE(child->GetExplicitlySetInFile());
+}
+
/////////////////////////////////////////////////
TEST(Element, CopyChildren)
{
@@ -345,6 +437,7 @@ TEST(Element, Clone)
ASSERT_EQ(newelem->GetAttributeCount(), 1UL);
ASSERT_NE(newelem->GetIncludeElement(), nullptr);
EXPECT_EQ("include", newelem->GetIncludeElement()->GetName());
+ ASSERT_TRUE(newelem->GetExplicitlySetInFile());
}
/////////////////////////////////////////////////
@@ -647,6 +740,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());
ASSERT_EQ(param->GetKey(), "test");
diff --git a/src/ParticleEmitter.cc b/src/ParticleEmitter.cc
index 782cee6ef..f1e353a66 100644
--- a/src/ParticleEmitter.cc
+++ b/src/ParticleEmitter.cc
@@ -88,6 +88,14 @@ class sdf::ParticleEmitter::Implementation
/// \brief Topic used to update particle emitter properties at runtime.
public: std::string topic = "";
+ /// \brief Particle scatter ratio. This is used to determine the ratio of
+ /// particles that will be detected by sensors. Increasing the ratio
+ /// means there is a higher chance of particles reflecting and interfering
+ /// with depth sensing, making the emitter appear more dense. Decreasing
+ /// the ratio decreases the chance of particles reflecting and interfering
+ /// with depth sensing, making it appear less dense.
+ public: float scatterRatio = 0.65f;
+
/// \brief Pose of the emitter
public: ignition::math::Pose3d pose = ignition::math::Pose3d::Zero;
@@ -201,6 +209,9 @@ Errors ParticleEmitter::Load(ElementPtr _sdf)
this->dataPtr->topic = _sdf->Get(
"topic", this->dataPtr->topic).first;
+ this->dataPtr->scatterRatio = _sdf->Get(
+ "particle_scatter_ratio", this->dataPtr->scatterRatio).first;
+
if (_sdf->HasElement("material"))
{
this->dataPtr->material.emplace();
@@ -416,6 +427,18 @@ void ParticleEmitter::SetTopic(const std::string &_topic)
this->dataPtr->topic = _topic;
}
+/////////////////////////////////////////////////
+void ParticleEmitter::SetScatterRatio(float _ratio)
+{
+ this->dataPtr->scatterRatio = _ratio;
+}
+
+/////////////////////////////////////////////////
+float ParticleEmitter::ScatterRatio() const
+{
+ return this->dataPtr->scatterRatio;
+}
+
/////////////////////////////////////////////////
const ignition::math::Pose3d &ParticleEmitter::RawPose() const
{
diff --git a/src/ParticleEmitter_TEST.cc b/src/ParticleEmitter_TEST.cc
index 8dc350de3..3cc03c85c 100644
--- a/src/ParticleEmitter_TEST.cc
+++ b/src/ParticleEmitter_TEST.cc
@@ -104,6 +104,10 @@ TEST(DOMParticleEmitter, Construction)
emitter.SetTopic("/test/topic");
EXPECT_EQ("/test/topic", emitter.Topic());
+ EXPECT_FLOAT_EQ(0.65f, emitter.ScatterRatio());
+ emitter.SetScatterRatio(0.5f);
+ EXPECT_FLOAT_EQ(0.5f, emitter.ScatterRatio());
+
EXPECT_EQ(ignition::math::Pose3d::Zero, emitter.RawPose());
emitter.SetRawPose(ignition::math::Pose3d(1, 2, 3, 0, 0, 1.5707));
EXPECT_EQ(ignition::math::Pose3d(1, 2, 3, 0, 0, 1.5707), emitter.RawPose());
diff --git a/src/parser.cc b/src/parser.cc
index d96f4c5e6..441dcaa6d 100644
--- a/src/parser.cc
+++ b/src/parser.cc
@@ -1507,7 +1507,8 @@ bool readXml(tinyxml2::XMLElement *_xml, ElementPtr _sdf,
else
{
// Add default element
- _sdf->AddElement(elemDesc->GetName());
+ ElementPtr defaultElement = _sdf->AddElement(elemDesc->GetName());
+ defaultElement->SetExplicitlySetInFile(false);
}
}
}
diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt
index 0d61a09e0..849e7b2de 100644
--- a/test/integration/CMakeLists.txt
+++ b/test/integration/CMakeLists.txt
@@ -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
element_tracing.cc
diff --git a/test/integration/default_elements.cc b/test/integration/default_elements.cc
new file mode 100644
index 000000000..e8dcfbac1
--- /dev/null
+++ b/test/integration/default_elements.cc
@@ -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
+#include
+#include
+
+#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());
+}
diff --git a/test/integration/particle_emitter_dom.cc b/test/integration/particle_emitter_dom.cc
index 05dba54a3..eeaf5ccd1 100644
--- a/test/integration/particle_emitter_dom.cc
+++ b/test/integration/particle_emitter_dom.cc
@@ -78,6 +78,7 @@ TEST(DOMWorld, LoadParticleEmitter)
EXPECT_DOUBLE_EQ(0.2, linkEmitter->MaxVelocity());
EXPECT_DOUBLE_EQ(0.5, linkEmitter->ScaleRate());
EXPECT_DOUBLE_EQ(5, linkEmitter->Rate());
+ EXPECT_FLOAT_EQ(0.2f, linkEmitter->ScatterRatio());
const sdf::Material *mat = linkEmitter->Material();
ASSERT_NE(nullptr, mat);
diff --git a/test/sdf/empty_axis.sdf b/test/sdf/empty_axis.sdf
new file mode 100644
index 000000000..6e6f42e3d
--- /dev/null
+++ b/test/sdf/empty_axis.sdf
@@ -0,0 +1,19 @@
+
+
+
+
+
+
+
+ link1
+ link2
+
+
+
+
+
+
diff --git a/test/sdf/empty_road_sph_coords.sdf b/test/sdf/empty_road_sph_coords.sdf
new file mode 100644
index 000000000..f9d720d1c
--- /dev/null
+++ b/test/sdf/empty_road_sph_coords.sdf
@@ -0,0 +1,30 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/test/sdf/world_complete.sdf b/test/sdf/world_complete.sdf
index 3bf45e4d5..57957c1ef 100644
--- a/test/sdf/world_complete.sdf
+++ b/test/sdf/world_complete.sdf
@@ -91,6 +91,7 @@
materials/textures/fogcolors.png
+ 0.2