diff --git a/include/sdf/Root.hh b/include/sdf/Root.hh index a37f44ea1..f9e7b80c9 100644 --- a/include/sdf/Root.hh +++ b/include/sdf/Root.hh @@ -127,51 +127,15 @@ namespace sdf /// \brief Get the number of models that are immediate (not nested) children /// of this Root object. /// \return Number of models contained in this Root object. - public: uint64_t ModelCount() const; - - /// \brief Get a model based on an index. - /// \param[in] _index Index of the model. The index should be in the - /// range [0..ModelCount()). - /// \return Pointer to the model. Nullptr if the index does not exist. - /// \sa uint64_t ModelCount() const - public: const Model *ModelByIndex(const uint64_t _index) const; - - /// \brief Get whether a model name exists. - /// \param[in] _name Name of the model to check. - /// \return True if there exists a model with the given name. - public: bool ModelNameExists(const std::string &_name) const; + public: const sdf::Model *Model() const; /// \brief Get the number of lights. /// \return Number of lights contained in this Root object. - public: uint64_t LightCount() const; - - /// \brief Get a light based on an index. - /// \param[in] _index Index of the light. The index should be in the - /// range [0..LightCount()). - /// \return Pointer to the light. Nullptr if the index does not exist. - /// \sa uint64_t LightCount() const - public: const Light *LightByIndex(const uint64_t _index) const; - - /// \brief Get whether a light name exists. - /// \param[in] _name Name of the light to check. - /// \return True if there exists a light with the given name. - public: bool LightNameExists(const std::string &_name) const; + public: const sdf::Light *Light() const; /// \brief Get the number of actors. /// \return Number of actors contained in this Root object. - public: uint64_t ActorCount() const; - - /// \brief Get an actor based on an index. - /// \param[in] _index Index of the actor. The actor should be in the - /// range [0..ActorCount()). - /// \return Pointer to the actor. Nullptr if the index does not exist. - /// \sa uint64_t ActorCount() const - public: const Actor *ActorByIndex(const uint64_t _index) const; - - /// \brief Get whether an actor name exists. - /// \param[in] _name Name of the actor to check. - /// \return True if there exists an actor with the given name. - public: bool ActorNameExists(const std::string &_name) const; + public: const sdf::Actor *Actor() const; /// \brief Get a pointer to the SDF element that was generated during /// load. diff --git a/src/FrameSemantics_TEST.cc b/src/FrameSemantics_TEST.cc index 752033610..415cdb662 100644 --- a/src/FrameSemantics_TEST.cc +++ b/src/FrameSemantics_TEST.cc @@ -48,7 +48,7 @@ TEST(FrameSemantics, buildFrameAttachedToGraph_Model) EXPECT_TRUE(errors.empty()) << errors; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); auto ownedGraph = std::make_shared(); sdf::ScopedGraph graph(ownedGraph); @@ -217,7 +217,7 @@ TEST(FrameSemantics, buildPoseRelativeToGraph) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); auto ownedGraph = std::make_shared(); sdf::ScopedGraph graph(ownedGraph); @@ -313,7 +313,7 @@ TEST(NestedFrameSemantics, buildFrameAttachedToGraph_Model) EXPECT_TRUE(errors.empty()) << errors; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); auto ownedGraph = std::make_shared(); sdf::ScopedGraph graph(ownedGraph); @@ -592,7 +592,7 @@ TEST(NestedFrameSemantics, ModelWithoutLinksWithNestedStaticModel) auto errors = root.Load(testFile); EXPECT_TRUE(errors.empty()) << errors; - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); auto ownedModelGraph = std::make_shared(); diff --git a/src/Root.cc b/src/Root.cc index 30a08203c..5e1660086 100644 --- a/src/Root.cc +++ b/src/Root.cc @@ -42,29 +42,27 @@ class sdf::RootPrivate public: std::vector worlds; /// \brief The models specified under the root SDF element - public: std::vector models; + public: std::unique_ptr model; /// \brief The lights specified under the root SDF element - public: std::vector lights; + public: std::unique_ptr light; /// \brief The actors specified under the root SDF element - public: std::vector actors; + public: std::unique_ptr actor; /// \brief Frame Attached-To Graphs constructed when loading Worlds. public: std::vector> worldFrameAttachedToGraphs; - /// \brief Frame Attached-To Graphs constructed when loading Models. - public: std::vector> - modelFrameAttachedToGraphs; + /// \brief Frame Attached-To Graph constructed when loading Models. + public: sdf::ScopedGraph modelFrameAttachedToGraph; /// \brief Pose Relative-To Graphs constructed when loading Worlds. public: std::vector> worldPoseRelativeToGraphs; - /// \brief Pose Relative-To Graphs constructed when loading Models. - public: std::vector> - modelPoseRelativeToGraphs; + /// \brief Pose Relative-To Graph constructed when loading Models. + public: sdf::ScopedGraph modelPoseRelativeToGraph; /// \brief The SDF element pointer generated during load. public: sdf::ElementPtr sdf; @@ -253,33 +251,66 @@ Errors Root::Load(SDFPtr _sdf) } } - // Load all the models. - Errors modelLoadErrors = loadUniqueRepeated( - this->dataPtr->sdf, "model", this->dataPtr->models); - errors.insert(errors.end(), modelLoadErrors.begin(), modelLoadErrors.end()); - - // Build the graphs. - for (sdf::Model &model : this->dataPtr->models) + if (this->dataPtr->sdf->HasElement("model")) { - auto frameAttachedToGraph = addFrameAttachedToGraph( - this->dataPtr->modelFrameAttachedToGraphs, model, errors); - - model.SetFrameAttachedToGraph(frameAttachedToGraph); - - auto poseRelativeToGraph = addPoseRelativeToGraph( - this->dataPtr->modelPoseRelativeToGraphs, model, errors); - model.SetPoseRelativeToGraph(poseRelativeToGraph); + sdf::ElementPtr model = this->dataPtr->sdf->GetElement("model"); + this->dataPtr->model = std::make_unique(); + sdf::Errors loadErrors = this->dataPtr->model->Load(model); + errors.insert(errors.end(), loadErrors.begin(), loadErrors.end()); + + this->dataPtr->modelFrameAttachedToGraph = + sdf::ScopedGraph(std::make_shared()); + + sdf::Errors buildErrors = + sdf::buildFrameAttachedToGraph( + this->dataPtr->modelFrameAttachedToGraph, + this->dataPtr->model.get()); + errors.insert(errors.end(), buildErrors.begin(), buildErrors.end()); + + sdf::Errors validateErrors = + sdf::validateFrameAttachedToGraph( + this->dataPtr->modelFrameAttachedToGraph); + errors.insert(errors.end(), validateErrors.begin(), validateErrors.end()); + + this->dataPtr->model->SetFrameAttachedToGraph( + this->dataPtr->modelFrameAttachedToGraph); + + this->dataPtr->modelPoseRelativeToGraph = + sdf::ScopedGraph(std::make_shared()); + + Errors buildPoseErrors = + buildPoseRelativeToGraph( + this->dataPtr->modelPoseRelativeToGraph, + this->dataPtr->model.get()); + errors.insert( + errors.end(), buildPoseErrors.begin(), buildPoseErrors.end()); + + Errors validatePoseErrors = + validatePoseRelativeToGraph( + this->dataPtr->modelPoseRelativeToGraph); + errors.insert( + errors.end(), validatePoseErrors.begin(), validatePoseErrors.end()); + + this->dataPtr->model->SetPoseRelativeToGraph( + this->dataPtr->modelPoseRelativeToGraph); } // Load all the lights. - Errors lightLoadErrors = loadUniqueRepeated(this->dataPtr->sdf, - "light", this->dataPtr->lights); - errors.insert(errors.end(), lightLoadErrors.begin(), lightLoadErrors.end()); + if (this->dataPtr->sdf->HasElement("light")) + { + sdf::ElementPtr lightPtr = this->dataPtr->sdf->GetElement("light"); + this->dataPtr->light = std::make_unique(); + sdf::Errors buildErrors = this->dataPtr->light->Load(lightPtr); + errors.insert(errors.end(), buildErrors.begin(), buildErrors.end()); + } - // Load all the actors. - Errors actorLoadErrors = loadUniqueRepeated(this->dataPtr->sdf, - "actor", this->dataPtr->actors); - errors.insert(errors.end(), actorLoadErrors.begin(), actorLoadErrors.end()); + if (this->dataPtr->sdf->HasElement("actor")) + { + sdf::ElementPtr actorPtr = this->dataPtr->sdf->GetElement("actor"); + this->dataPtr->actor = std::make_unique(); + sdf::Errors buildErrors = this->dataPtr->actor->Load(actorPtr); + errors.insert(errors.end(), buildErrors.begin(), buildErrors.end()); + } return errors; } @@ -324,84 +355,21 @@ bool Root::WorldNameExists(const std::string &_name) const } ///////////////////////////////////////////////// -uint64_t Root::ModelCount() const -{ - return this->dataPtr->models.size(); -} - -///////////////////////////////////////////////// -const Model *Root::ModelByIndex(const uint64_t _index) const -{ - if (_index < this->dataPtr->models.size()) - return &this->dataPtr->models[_index]; - return nullptr; -} - -///////////////////////////////////////////////// -bool Root::ModelNameExists(const std::string &_name) const -{ - for (auto const &m : this->dataPtr->models) - { - if (m.Name() == _name) - { - return true; - } - } - return false; -} - -///////////////////////////////////////////////// -uint64_t Root::LightCount() const +const Model *Root::Model() const { - return this->dataPtr->lights.size(); + return this->dataPtr->model.get(); } ///////////////////////////////////////////////// -const Light *Root::LightByIndex(const uint64_t _index) const +const Light *Root::Light() const { - if (_index < this->dataPtr->lights.size()) - return &this->dataPtr->lights[_index]; - return nullptr; -} - -///////////////////////////////////////////////// -bool Root::LightNameExists(const std::string &_name) const -{ - for (auto const &m : this->dataPtr->lights) - { - if (m.Name() == _name) - { - return true; - } - } - return false; + return this->dataPtr->light.get(); } ///////////////////////////////////////////////// -uint64_t Root::ActorCount() const +const Actor *Root::Actor() const { - return this->dataPtr->actors.size(); -} - -///////////////////////////////////////////////// -const Actor *Root::ActorByIndex(const uint64_t _index) const -{ - if (_index < this->dataPtr->actors.size()) - return &this->dataPtr->actors[_index]; - return nullptr; -} - -///////////////////////////////////////////////// -bool Root::ActorNameExists(const std::string &_name) const -{ - for (auto const &m : this->dataPtr->actors) - { - if (m.Name() == _name) - { - return true; - } - } - return false; + return this->dataPtr->actor.get(); } ///////////////////////////////////////////////// diff --git a/src/Root_TEST.cc b/src/Root_TEST.cc index 60e2e3746..d687f6e2b 100644 --- a/src/Root_TEST.cc +++ b/src/Root_TEST.cc @@ -39,23 +39,9 @@ TEST(DOMRoot, Construction) EXPECT_TRUE(root.WorldByIndex(0) == nullptr); EXPECT_TRUE(root.WorldByIndex(1) == nullptr); - EXPECT_FALSE(root.ModelNameExists("default")); - EXPECT_FALSE(root.ModelNameExists("")); - EXPECT_EQ(0u, root.ModelCount()); - EXPECT_TRUE(root.ModelByIndex(0) == nullptr); - EXPECT_TRUE(root.ModelByIndex(1) == nullptr); - - EXPECT_FALSE(root.LightNameExists("default")); - EXPECT_FALSE(root.LightNameExists("")); - EXPECT_EQ(0u, root.LightCount()); - EXPECT_TRUE(root.LightByIndex(0) == nullptr); - EXPECT_TRUE(root.LightByIndex(1) == nullptr); - - EXPECT_FALSE(root.ActorNameExists("default")); - EXPECT_FALSE(root.ActorNameExists("")); - EXPECT_EQ(0u, root.ActorCount()); - EXPECT_TRUE(root.ActorByIndex(0) == nullptr); - EXPECT_TRUE(root.ActorByIndex(1) == nullptr); + EXPECT_EQ(nullptr, root.Model()); + EXPECT_EQ(nullptr, root.Light()); + EXPECT_EQ(nullptr, root.Actor()); } ///////////////////////////////////////////////// @@ -80,10 +66,10 @@ TEST(DOMRoot, MoveAssignmentOperator) } ///////////////////////////////////////////////// -TEST(DOMRoot, StringParse) +TEST(DOMRoot, StringModelSdfParse) { std::string sdf = "" - " " + " " " " " " " " @@ -95,36 +81,14 @@ TEST(DOMRoot, StringParse) " " " " " " - " " - " -0.5 0.1 -0.9" - " " - " " - " 0 0 1.0 0 0 0" - " " - " /fake/path/to/mesh.dae" - " 1.0" - " " - " " - " /fake/path/to/mesh.dae" - " 0.055" - " true" - " " - " " - " " " "; sdf::Root root; sdf::Errors errors = root.LoadSdfString(sdf); EXPECT_TRUE(errors.empty()); - EXPECT_EQ(1u, root.ModelCount()); - EXPECT_EQ(1u, root.LightCount()); EXPECT_NE(nullptr, root.Element()); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_NE(nullptr, model->Element()); @@ -142,17 +106,72 @@ TEST(DOMRoot, StringParse) EXPECT_NE(nullptr, collision->Element()); EXPECT_EQ("box_col", collision->Name()); - EXPECT_TRUE(root.LightNameExists("sun")); - EXPECT_EQ(1u, root.LightCount()); - const sdf::Light *light = root.LightByIndex(0); + EXPECT_EQ(nullptr, root.Light()); + EXPECT_EQ(nullptr, root.Actor()); + EXPECT_EQ(0u, root.WorldCount()); +} + +///////////////////////////////////////////////// +TEST(DOMRoot, StringLightSdfParse) +{ + std::string sdf = "" + " " + " " + " -0.5 0.1 -0.9" + " " + " "; + + sdf::Root root; + sdf::Errors errors = root.LoadSdfString(sdf); + EXPECT_TRUE(errors.empty()); + EXPECT_NE(nullptr, root.Element()); + + const sdf::Light *light = root.Light(); ASSERT_NE(nullptr, light); + EXPECT_EQ("sun", light->Name()); EXPECT_NE(nullptr, light->Element()); - EXPECT_TRUE(root.ActorNameExists("actor_test")); - EXPECT_EQ(1u, root.ActorCount()); - const sdf::Actor *actor = root.ActorByIndex(0); + EXPECT_EQ(nullptr, root.Model()); + EXPECT_EQ(nullptr, root.Actor()); + EXPECT_EQ(0u, root.WorldCount()); +} + +///////////////////////////////////////////////// +TEST(DOMRoot, StringActorSdfParse) +{ + std::string sdf = "" + " " + " " + " 0 0 1.0 0 0 0" + " " + " /fake/path/to/mesh.dae" + " 1.0" + " " + " " + " /fake/path/to/mesh.dae" + " 0.055" + " true" + " " + " " + " " + " "; + + sdf::Root root; + sdf::Errors errors = root.LoadSdfString(sdf); + EXPECT_TRUE(errors.empty()); + + const sdf::Actor *actor = root.Actor(); ASSERT_NE(nullptr, actor); + EXPECT_EQ("actor_test", actor->Name()); EXPECT_NE(nullptr, actor->Element()); + + EXPECT_EQ(nullptr, root.Model()); + EXPECT_EQ(nullptr, root.Light()); + EXPECT_EQ(0u, root.WorldCount()); } ///////////////////////////////////////////////// diff --git a/src/ign.cc b/src/ign.cc index dfef44a81..de66011eb 100644 --- a/src/ign.cc +++ b/src/ign.cc @@ -187,9 +187,10 @@ extern "C" SDFORMAT_VISIBLE int cmdGraph( { errors = sdf::buildPoseRelativeToGraph(graph, root.WorldByIndex(0)); } - else if (root.ModelCount() > 0) + else if (root.Model() != nullptr) { - errors = sdf::buildPoseRelativeToGraph(graph, root.ModelByIndex(0)); + errors = + sdf::buildPoseRelativeToGraph(graph, root.Model()); } if (!errors.empty()) @@ -206,9 +207,10 @@ extern "C" SDFORMAT_VISIBLE int cmdGraph( { errors = sdf::buildFrameAttachedToGraph(graph, root.WorldByIndex(0)); } - else if (root.ModelCount() > 0) + else if (root.Model() != nullptr) { - errors = sdf::buildFrameAttachedToGraph(graph, root.ModelByIndex(0)); + errors = + sdf::buildFrameAttachedToGraph(graph, root.Model()); } if (!errors.empty()) diff --git a/src/parser.cc b/src/parser.cc index f16c6290f..6e4a897f7 100644 --- a/src/parser.cc +++ b/src/parser.cc @@ -1393,10 +1393,9 @@ bool checkCanonicalLinkNames(const sdf::Root *_root) return modelResult; }; - for (uint64_t m = 0; m < _root->ModelCount(); ++m) + if (_root->Model()) { - auto model = _root->ModelByIndex(m); - result = checkModelCanonicalLinkName(model) && result; + result = checkModelCanonicalLinkName(_root->Model()) && result; } for (uint64_t w = 0; w < _root->WorldCount(); ++w) @@ -1530,10 +1529,9 @@ bool checkFrameAttachedToNames(const sdf::Root *_root) return worldResult; }; - for (uint64_t m = 0; m < _root->ModelCount(); ++m) + if (_root->Model()) { - auto model = _root->ModelByIndex(m); - result = checkModelFrameAttachedToNames(model) && result; + result = checkModelFrameAttachedToNames(_root->Model()) && result; } for (uint64_t w = 0; w < _root->WorldCount(); ++w) @@ -1668,10 +1666,9 @@ bool checkFrameAttachedToGraph(const sdf::Root *_root) return worldResult; }; - for (uint64_t m = 0; m < _root->ModelCount(); ++m) + if (_root->Model()) { - auto model = _root->ModelByIndex(m); - result = checkModelFrameAttachedToGraph(model) && result; + result = checkModelFrameAttachedToGraph(_root->Model()) && result; } for (uint64_t w = 0; w < _root->WorldCount(); ++w) @@ -1751,10 +1748,9 @@ bool checkPoseRelativeToGraph(const sdf::Root *_root) return worldResult; }; - for (uint64_t m = 0; m < _root->ModelCount(); ++m) + if (_root->Model()) { - auto model = _root->ModelByIndex(m); - result = checkModelPoseRelativeToGraph(model) && result; + result = checkModelPoseRelativeToGraph(_root->Model()) && result; } for (uint64_t w = 0; w < _root->WorldCount(); ++w) @@ -1879,10 +1875,9 @@ bool checkJointParentChildLinkNames(const sdf::Root *_root) return modelResult; }; - for (uint64_t m = 0; m < _root->ModelCount(); ++m) + if (_root->Model()) { - auto model = _root->ModelByIndex(m); - result = checkModelJointParentChildNames(model) && result; + result = checkModelJointParentChildNames(_root->Model()) && result; } for (uint64_t w = 0; w < _root->WorldCount(); ++w) diff --git a/test/integration/collision_dom.cc b/test/integration/collision_dom.cc index 06ea0b23e..1d5894b9e 100644 --- a/test/integration/collision_dom.cc +++ b/test/integration/collision_dom.cc @@ -71,7 +71,7 @@ TEST(DOMCollision, DoublePendulum) sdf::Root root; EXPECT_TRUE(root.Load(testFile).empty()); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_TRUE(model != nullptr); const sdf::Link *baseLink = model->LinkByIndex(0); @@ -105,7 +105,7 @@ TEST(DOMCollision, LoadModelFramesRelativeToJoint) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_frame_relative_to_joint", model->Name()); EXPECT_EQ(2u, model->LinkCount()); @@ -284,4 +284,3 @@ TEST(DOMCollision, LoadModelFramesRelativeToJoint) linkC->CollisionByName("F4")->SemanticPose().Resolve(pose).empty()); EXPECT_EQ(Pose(-18, 3, 4, 0, -IGN_PI/2, 0), pose); } - diff --git a/test/integration/frame.cc b/test/integration/frame.cc index 989710673..cb0ffd5b5 100644 --- a/test/integration/frame.cc +++ b/test/integration/frame.cc @@ -423,7 +423,7 @@ TEST(DOMFrame, LoadModelFramesAttachedTo) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_frame_attached_to", model->Name()); EXPECT_EQ(1u, model->LinkCount()); @@ -525,7 +525,7 @@ TEST(DOMFrame, LoadModelFramesAttachedToJoint) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_frame_attached_to_joint", model->Name()); EXPECT_EQ(2u, model->LinkCount()); @@ -591,7 +591,7 @@ TEST(DOMFrame, LoadModelFramesAttachedToNestedModel) EXPECT_TRUE(errors.empty()) << errors; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_frame_attached_to_nested_model", model->Name()); EXPECT_EQ(1u, model->LinkCount()); @@ -750,7 +750,7 @@ TEST(DOMFrame, LoadModelFramesRelativeTo) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_frame_relative_to", model->Name()); EXPECT_EQ(1u, model->LinkCount()); @@ -911,7 +911,7 @@ TEST(DOMFrame, LoadModelFramesRelativeToJoint) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_frame_relative_to_joint", model->Name()); EXPECT_EQ(2u, model->LinkCount()); diff --git a/test/integration/geometry_dom.cc b/test/integration/geometry_dom.cc index 3f1e44f21..5ec4662a9 100644 --- a/test/integration/geometry_dom.cc +++ b/test/integration/geometry_dom.cc @@ -47,7 +47,7 @@ TEST(DOMGeometry, Shapes) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); const sdf::Link *link = model->LinkByIndex(0); diff --git a/test/integration/joint_axis_dom.cc b/test/integration/joint_axis_dom.cc index da3624258..f331984d8 100644 --- a/test/integration/joint_axis_dom.cc +++ b/test/integration/joint_axis_dom.cc @@ -42,7 +42,7 @@ TEST(DOMJointAxis, Complete) EXPECT_TRUE(errors.empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); // The model should have nine joints. @@ -132,7 +132,7 @@ TEST(DOMJointAxis, XyzExpressedIn) using Vector3 = ignition::math::Vector3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_joint_axis_expressed_in", model->Name()); EXPECT_EQ(4u, model->LinkCount()); @@ -244,7 +244,7 @@ TEST(DOMJointAxis, XyzNormalization) using ignition::math::Vector3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); { diff --git a/test/integration/joint_dom.cc b/test/integration/joint_dom.cc index da51264ea..777f48f3d 100644 --- a/test/integration/joint_dom.cc +++ b/test/integration/joint_dom.cc @@ -72,7 +72,7 @@ TEST(DOMJoint, DoublePendulum) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); // The double pendulum should have two joints. @@ -127,7 +127,7 @@ TEST(DOMJoint, Complete) EXPECT_TRUE(errors.empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); std::vector jointPoses = @@ -171,7 +171,7 @@ TEST(DOMJoint, LoadJointParentWorld) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("joint_parent_world", model->Name()); EXPECT_EQ(1u, model->LinkCount()); @@ -220,8 +220,7 @@ TEST(DOMJoint, LoadInvalidJointChildWorld) auto errors = root.Load(testFile); for (auto e : errors) std::cout << e << std::endl; - EXPECT_FALSE(errors.empty()); - EXPECT_EQ(7u, errors.size()); + ASSERT_EQ(7u, errors.size()); EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::JOINT_CHILD_LINK_INVALID); EXPECT_NE(std::string::npos, errors[0].Message().find( @@ -247,7 +246,7 @@ TEST(DOMJoint, LoadJointParentFrame) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("joint_parent_frame", model->Name()); EXPECT_EQ(2u, model->LinkCount()); @@ -340,7 +339,7 @@ TEST(DOMJoint, LoadJointChildFrame) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("joint_child_frame", model->Name()); EXPECT_EQ(2u, model->LinkCount()); @@ -433,7 +432,7 @@ TEST(DOMJoint, LoadJointPoseRelativeTo) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_joint_relative_to", model->Name()); EXPECT_EQ(4u, model->LinkCount()); @@ -621,7 +620,7 @@ TEST(DOMJoint, LoadLinkJointSameName16Valid) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("link_joint_same_name", model->Name()); EXPECT_EQ(2u, model->LinkCount()); @@ -701,7 +700,7 @@ TEST(DOMJoint, LoadURDFJointPoseRelativeTo) using Vector3 = ignition::math::Vector3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("provide_feedback_test", model->Name()); EXPECT_EQ(3u, model->LinkCount()); @@ -782,7 +781,7 @@ TEST(DOMJoint, LoadJointNestedParentChild) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); { diff --git a/test/integration/link_dom.cc b/test/integration/link_dom.cc index 19b018da5..c3188063d 100644 --- a/test/integration/link_dom.cc +++ b/test/integration/link_dom.cc @@ -122,7 +122,7 @@ TEST(DOMLink, InertialDoublePendulum) sdf::Root root; EXPECT_TRUE(root.Load(testFile).empty()); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); const sdf::Link *baseLink = model->LinkByIndex(0); @@ -177,7 +177,7 @@ TEST(DOMLink, InertialComplete) sdf::Root root; EXPECT_TRUE(root.Load(testFile).empty()); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); const sdf::Link *link = model->LinkByIndex(0); @@ -215,7 +215,7 @@ TEST(DOMLink, InertialInvalid) EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::LINK_INERTIA_INVALID); EXPECT_EQ(errors[0].Message(), "A link named link has invalid inertia."); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); ASSERT_EQ(1u, model->LinkCount()); @@ -239,7 +239,7 @@ TEST(DOMLink, Sensors) EXPECT_TRUE(errors.empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model", model->Name()); @@ -591,7 +591,7 @@ TEST(DOMLink, LoadLinkPoseRelativeTo) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_link_relative_to", model->Name()); EXPECT_EQ(3u, model->LinkCount()); diff --git a/test/integration/material_pbr.cc b/test/integration/material_pbr.cc index 4eb8f6b3d..2585e456d 100644 --- a/test/integration/material_pbr.cc +++ b/test/integration/material_pbr.cc @@ -34,7 +34,7 @@ TEST(Material, PbrDOM) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); // Get the first link @@ -541,5 +541,3 @@ TEST(Material, MaterialPBR) } } } - - diff --git a/test/integration/model_dom.cc b/test/integration/model_dom.cc index 28fe7dcb6..258fcdfd9 100644 --- a/test/integration/model_dom.cc +++ b/test/integration/model_dom.cc @@ -121,7 +121,7 @@ TEST(DOMRoot, LoadDoublePendulum) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("double_pendulum_with_base", model->Name()); EXPECT_EQ(3u, model->LinkCount()); @@ -157,10 +157,8 @@ TEST(DOMRoot, NestedModel) auto errors = root.Load(testFile); EXPECT_TRUE(errors.empty()) << errors; - EXPECT_EQ(1u, root.ModelCount()); - // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("top_level_model", model->Name()); EXPECT_EQ(2u, model->LinkCount()); @@ -216,10 +214,8 @@ TEST(DOMRoot, MultiNestedModel) auto errors = root.Load(testFile); EXPECT_TRUE(errors.empty()); - EXPECT_EQ(1u, root.ModelCount()); - // Get the outer model - const sdf::Model *outerModel = root.ModelByIndex(0); + const sdf::Model *outerModel = root.Model(); ASSERT_NE(nullptr, outerModel); EXPECT_EQ("outer_model", outerModel->Name()); EXPECT_EQ(1u, outerModel->LinkCount()); @@ -318,7 +314,7 @@ TEST(DOMLink, NestedModelPoseRelativeTo) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_nested_model_relative_to", model->Name()); EXPECT_EQ(1u, model->LinkCount()); @@ -399,7 +395,7 @@ TEST(DOMRoot, LoadCanonicalLink) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_canonical_link", model->Name()); EXPECT_EQ(2u, model->LinkCount()); @@ -441,7 +437,7 @@ TEST(DOMRoot, LoadNestedCanonicalLink) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("top", model->Name()); EXPECT_EQ(0u, model->LinkCount()); @@ -494,7 +490,7 @@ TEST(DOMRoot, LoadNestedExplicitCanonicalLink) EXPECT_TRUE(root.Load(testFile).empty()); // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("top", model->Name()); EXPECT_EQ(0u, model->LinkCount()); @@ -542,7 +538,7 @@ TEST(DOMRoot, ModelPlacementFrameAttribute) sdf::Errors errors = root.Load(testFile); EXPECT_TRUE(errors.empty()) << errors; - auto *model = root.ModelByIndex(0); + auto *model = root.Model(); ASSERT_NE(nullptr, model); ignition::math::Pose3d pose; @@ -564,7 +560,7 @@ TEST(DOMRoot, LoadInvalidNestedModelWithoutLinks) for (auto e : errors) std::cout << e << std::endl; EXPECT_FALSE(errors.empty()); - EXPECT_EQ(7u, errors.size()); + ASSERT_EQ(7u, errors.size()); EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::MODEL_WITHOUT_LINK); EXPECT_NE(std::string::npos, errors[0].Message().find("A model must have at least one link")); diff --git a/test/integration/nested_model.cc b/test/integration/nested_model.cc index cb61aa45a..50cf7526c 100644 --- a/test/integration/nested_model.cc +++ b/test/integration/nested_model.cc @@ -1106,7 +1106,7 @@ TEST(NestedReference, PoseRelativeTo) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); auto parentSemPose = model->SemanticPose(); @@ -1229,7 +1229,7 @@ TEST(NestedReference, PlacementFrameAttribute) sdf::Errors errors = root.Load(testFile); EXPECT_TRUE(errors.empty()) << errors; - auto *model = root.ModelByIndex(0); + auto *model = root.Model(); ASSERT_NE(nullptr, model); ignition::math::Pose3d pose; @@ -1325,7 +1325,7 @@ TEST(NestedReference, PlacementFrameElement) sdf::Errors errors = root.LoadSdfString(stream.str()); EXPECT_TRUE(errors.empty()) << errors; - auto *parentModel = root.ModelByIndex(0); + auto *parentModel = root.Model(); ASSERT_NE(nullptr, parentModel); auto *model = parentModel->ModelByIndex(0); ASSERT_NE(nullptr, model); @@ -1356,7 +1356,7 @@ TEST(NestedReference, PlacementFrameElement) sdf::Errors errors = root.LoadSdfString(stream.str()); EXPECT_TRUE(errors.empty()) << errors; - auto *parentModel = root.ModelByIndex(0); + auto *parentModel = root.Model(); ASSERT_NE(nullptr, parentModel); auto *model = parentModel ->ModelByIndex(0); ASSERT_NE(nullptr, model); diff --git a/test/integration/nested_multiple_elements_error.cc b/test/integration/nested_multiple_elements_error.cc index 1fa757ae2..456208220 100644 --- a/test/integration/nested_multiple_elements_error.cc +++ b/test/integration/nested_multiple_elements_error.cc @@ -59,16 +59,15 @@ TEST(IncludesTest, NestedMultipleModelsError) ASSERT_TRUE(errors.empty()); } - ASSERT_EQ(1u, root.ModelCount()); - const auto * model = root.ModelByIndex(0); + const auto * model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("nested_model", model->Name()); ASSERT_EQ(1u, model->LinkCount()); EXPECT_EQ("link1", model->LinkByIndex(0)->Name()); - EXPECT_EQ(0u, root.ActorCount()); - EXPECT_EQ(0u, root.LightCount()); + EXPECT_EQ(nullptr, root.Actor()); + EXPECT_EQ(nullptr, root.Light()); } ////////////////////////////////////////////////// @@ -91,11 +90,10 @@ TEST(IncludesTest, NestedMultipleActorsError) ASSERT_TRUE(errors.empty()); } - EXPECT_EQ(0u, root.ModelCount()); - EXPECT_EQ(0u, root.LightCount()); + EXPECT_EQ(nullptr, root.Model()); + EXPECT_EQ(nullptr, root.Light()); - ASSERT_EQ(1u, root.ActorCount()); - const auto * actor = root.ActorByIndex(0); + const auto * actor = root.Actor(); ASSERT_NE(nullptr, actor); EXPECT_EQ("nested_actor", actor->Name()); ASSERT_EQ(1u, actor->LinkCount()); @@ -122,11 +120,10 @@ TEST(IncludesTest, NestedMultipleLightsError) ASSERT_TRUE(errors.empty()); } - EXPECT_EQ(0u, root.ModelCount()); - EXPECT_EQ(0u, root.ActorCount()); + EXPECT_EQ(nullptr, root.Model()); + EXPECT_EQ(nullptr, root.Actor()); - ASSERT_EQ(1u, root.LightCount()); - const auto * light = root.LightByIndex(0); + const auto * light = root.Light(); ASSERT_NE(nullptr, light); EXPECT_EQ("nested_light", light->Name()); EXPECT_EQ(ignition::math::Vector3d(1, 0, 0), light->Direction()); @@ -152,11 +149,10 @@ TEST(IncludesTest, NestedMultipleElementsError) ASSERT_TRUE(errors.empty()); } - EXPECT_EQ(0u, root.LightCount()); - EXPECT_EQ(0u, root.ActorCount()); + EXPECT_EQ(nullptr, root.Light()); + EXPECT_EQ(nullptr, root.Actor()); - ASSERT_EQ(1u, root.ModelCount()); - const auto * model = root.ModelByIndex(0); + const auto * model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("nested_model", model->Name()); } @@ -180,9 +176,9 @@ TEST(IncludesTest, NestedMultipleElementsErrorWorld) ASSERT_TRUE(errors.empty()); } - EXPECT_EQ(0u, root.LightCount()); - EXPECT_EQ(0u, root.ActorCount()); - EXPECT_EQ(0u, root.ModelCount()); + EXPECT_EQ(nullptr, root.Light()); + EXPECT_EQ(nullptr, root.Actor()); + EXPECT_EQ(nullptr, root.Model()); ASSERT_EQ(1u, root.WorldCount()); const auto * world = root.WorldByIndex(0); diff --git a/test/integration/root_dom.cc b/test/integration/root_dom.cc index f6f06af24..9231d8088 100644 --- a/test/integration/root_dom.cc +++ b/test/integration/root_dom.cc @@ -85,17 +85,12 @@ TEST(DOMRoot, LoadMultipleModels) sdf::Root root; sdf::Errors errors = root.Load(testFile); - EXPECT_TRUE(errors.empty()) << errors; - EXPECT_EQ(3u, root.ModelCount()); - - EXPECT_EQ("robot1", root.ModelByIndex(0)->Name()); - EXPECT_EQ("robot2", root.ModelByIndex(1)->Name()); - EXPECT_EQ("last_robot", root.ModelByIndex(2)->Name()); - EXPECT_FALSE(root.ModelNameExists("robot")); - EXPECT_TRUE(root.ModelNameExists("robot1")); - EXPECT_TRUE(root.ModelNameExists("robot2")); - EXPECT_TRUE(root.ModelNameExists("last_robot")); + // Currently just warnings are issued in this case, eventually they may become + // errors. For now, only the first model is loaded. + EXPECT_TRUE(errors.empty()) << errors; + ASSERT_NE(nullptr, root.Model()); + EXPECT_EQ("robot1", root.Model()->Name()); } ///////////////////////////////////////////////// @@ -107,7 +102,7 @@ TEST(DOMRoot, LoadDuplicateModels) sdf::Root root; sdf::Errors errors = root.Load(testFile); - EXPECT_FALSE(errors.empty()); - EXPECT_EQ(1u, root.ModelCount()); - EXPECT_EQ("robot1", root.ModelByIndex(0)->Name()); + EXPECT_TRUE(errors.empty()) << errors; + EXPECT_NE(nullptr, root.Model()); + EXPECT_EQ("robot1", root.Model()->Name()); } diff --git a/test/integration/surface_dom.cc b/test/integration/surface_dom.cc index 8363704f8..a09129b73 100644 --- a/test/integration/surface_dom.cc +++ b/test/integration/surface_dom.cc @@ -39,7 +39,7 @@ TEST(DOMSurface, Shapes) sdf::Root root; EXPECT_TRUE(root.Load(testFile).empty()); - const auto model = root.ModelByIndex(0); + const auto model = root.Model(); ASSERT_NE(nullptr, model); const auto link = model->LinkByIndex(0); diff --git a/test/integration/visual_dom.cc b/test/integration/visual_dom.cc index b58e2aa4f..f06118d70 100644 --- a/test/integration/visual_dom.cc +++ b/test/integration/visual_dom.cc @@ -71,7 +71,7 @@ TEST(DOMVisual, DoublePendulum) sdf::Root root; EXPECT_TRUE(root.Load(testFile).empty()); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_TRUE(model != nullptr); const sdf::Link *baseLink = model->LinkByIndex(0); @@ -104,7 +104,7 @@ TEST(DOMVisual, Material) sdf::Root root; EXPECT_TRUE(root.Load(testFile).empty()); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); const sdf::Link *link = model->LinkByIndex(0); @@ -189,7 +189,7 @@ TEST(DOMVisual, Transparency) sdf::Root root; EXPECT_TRUE(root.Load(testFile).empty()); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); const sdf::Link *link = model->LinkByIndex(0); @@ -215,7 +215,7 @@ TEST(DOMVisual, LoadModelFramesRelativeToJoint) using Pose = ignition::math::Pose3d; // Get the first model - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); EXPECT_EQ("model_frame_relative_to_joint", model->Name()); EXPECT_EQ(2u, model->LinkCount()); @@ -406,7 +406,7 @@ TEST(DOMVisual, VisibilityFlags) sdf::Root root; EXPECT_TRUE(root.Load(testFile).empty()); - const sdf::Model *model = root.ModelByIndex(0); + const sdf::Model *model = root.Model(); ASSERT_NE(nullptr, model); const sdf::Link *link = model->LinkByIndex(0);