From 12e68974e77e6499f00a00a48cbec445e4388988 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 5 May 2021 20:36:59 -0700 Subject: [PATCH 1/3] Add scatter ratio parameter to Particle Emitter DOM (#547) * add particle scatter ratio? Signed-off-by: Ian Chen * update field name Signed-off-by: Ian Chen * update doc Signed-off-by: Ian Chen --- include/sdf/ParticleEmitter.hh | 11 +++++++++++ sdf/1.7/particle_emitter.sdf | 11 +++++++++++ src/ParticleEmitter.cc | 24 ++++++++++++++++++++++++ src/ParticleEmitter_TEST.cc | 4 ++++ test/integration/particle_emitter_dom.cc | 1 + test/sdf/world_complete.sdf | 1 + 6 files changed, 52 insertions(+) diff --git a/include/sdf/ParticleEmitter.hh b/include/sdf/ParticleEmitter.hh index 251b4ff60..ae1dae9a8 100644 --- a/include/sdf/ParticleEmitter.hh +++ b/include/sdf/ParticleEmitter.hh @@ -276,6 +276,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/ParticleEmitter.cc b/src/ParticleEmitter.cc index e343077e3..195bd09ae 100644 --- a/src/ParticleEmitter.cc +++ b/src/ParticleEmitter.cc @@ -96,6 +96,14 @@ class sdf::ParticleEmitterPrivate /// \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; @@ -136,6 +144,7 @@ ParticleEmitterPrivate::ParticleEmitterPrivate( colorEnd(_private.colorEnd), colorRangeImage(_private.colorRangeImage), topic(_private.topic), + scatterRatio(_private.scatterRatio), pose(_private.pose), poseRelativeTo(_private.poseRelativeTo), xmlParentName(_private.xmlParentName), @@ -272,6 +281,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.reset(new sdf::Material()); @@ -487,6 +499,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/test/integration/particle_emitter_dom.cc b/test/integration/particle_emitter_dom.cc index 6071ac184..4590a84cb 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()); sdf::Material *mat = linkEmitter->Material(); ASSERT_NE(nullptr, mat); diff --git a/test/sdf/world_complete.sdf b/test/sdf/world_complete.sdf index 955b4268d..211c7f148 100644 --- a/test/sdf/world_complete.sdf +++ b/test/sdf/world_complete.sdf @@ -90,6 +90,7 @@ materials/textures/fogcolors.png + 0.2 From bf1c809f20eec80003f7525641410c590cf5760c Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 17 May 2021 17:09:42 -0700 Subject: [PATCH 2/3] Prepare for 10.5.0 release (#569) * prepare for 10.5.0 release Signed-off-by: Ian Chen * more changelog Signed-off-by: Steve 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 51d563971..ff0998b53 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -27,7 +27,7 @@ project (sdformat10) set (SDF_PROTOCOL_VERSION 1.7) set (SDF_MAJOR_VERSION 10) -set (SDF_MINOR_VERSION 4) +set (SDF_MINOR_VERSION 5) set (SDF_PATCH_VERSION 0) set (SDF_VERSION ${SDF_MAJOR_VERSION}.${SDF_MINOR_VERSION}) diff --git a/Changelog.md b/Changelog.md index faa51c61a..472a9d9d2 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,5 +1,16 @@ ## 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. From 9876a6089c88ac39408e658b6b4b2928abab8377 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Marco=20A=2E=20Guti=C3=A9rrez?= Date: Wed, 19 May 2021 04:45:21 +0800 Subject: [PATCH 3/3] Add API for determining if an element was set by the user (#542) There's already a way to do this for the Attribute class so adding a similar function for the Element class. To keep consistency with the code from in the Attribute class, we set it to true if the element was set, and false if it was created by default. Signed-off-by: Marco A. Gutierrez Co-authored-by: Addisu Z. Taddese --- include/sdf/Element.hh | 14 +++ src/Element.cc | 22 ++++ src/Element_TEST.cc | 94 ++++++++++++++++ src/parser.cc | 3 +- test/integration/CMakeLists.txt | 1 + test/integration/default_elements.cc | 155 +++++++++++++++++++++++++++ test/sdf/empty_axis.sdf | 19 ++++ test/sdf/empty_road_sph_coords.sdf | 30 ++++++ tools/code_check.sh | 2 +- 9 files changed, 338 insertions(+), 2 deletions(-) create mode 100644 test/integration/default_elements.cc create mode 100644 test/sdf/empty_axis.sdf create mode 100644 test/sdf/empty_road_sph_coords.sdf diff --git a/include/sdf/Element.hh b/include/sdf/Element.hh index 92ef562ed..6064abf3a 100644 --- a/include/sdf/Element.hh +++ b/include/sdf/Element.hh @@ -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. @@ -450,6 +461,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/src/Element.cc b/src/Element.cc index fe181a960..7df8928df 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 { @@ -155,6 +175,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(); @@ -196,6 +217,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) diff --git a/src/Element_TEST.cc b/src/Element_TEST.cc index f5504f87d..ec7897a11 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) { @@ -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()); } ///////////////////////////////////////////////// @@ -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()); ASSERT_EQ(param->GetKey(), "test"); diff --git a/src/parser.cc b/src/parser.cc index b94d08222..06a3b89f5 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -1131,7 +1131,8 @@ bool readXml(TiXmlElement *_xml, ElementPtr _sdf, Errors &_errors) 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 1bb4d3719..9dcd39b55 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 fixed_joint_reduction.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/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/tools/code_check.sh b/tools/code_check.sh index 9754e4b81..bd24da512 100755 --- a/tools/code_check.sh +++ b/tools/code_check.sh @@ -28,7 +28,7 @@ CHECK_FILE_DIRS="./src ./include ./examples ./test/performance ./test/integratio CPPCHECK_BASE="cppcheck -q --suppressions-list=$SUPPRESS --inline-suppr" CPPCHECK_BASE2="cppcheck -q --suppressions-list=$SUPPRESS2 --inline-suppr" CPPCHECK_FILES=`find $CHECK_FILE_DIRS -name "*.cc"` -CPPCHECK_INCLUDES="-I include -I . -I $builddir -I $builddir/include" +CPPCHECK_INCLUDES="-I include -I test -I . -I $builddir -I $builddir/include" CPPCHECK_COMMAND1="-j 4 --enable=style,performance,portability,information $CPPCHECK_FILES" # Unused function checking must happen in one job CPPCHECK_COMMAND2="--enable=unusedFunction $CPPCHECK_FILES"