From 68f1041ce7da225bf019adb59c3339f266541241 Mon Sep 17 00:00:00 2001 From: Mabel Zhang Date: Tue, 7 Jun 2022 04:16:10 -0400 Subject: [PATCH] change field name to cubemap_uri Signed-off-by: Mabel Zhang --- include/sdf/Sky.hh | 4 ++-- sdf/1.9/scene.sdf | 4 ++++ src/Sky.cc | 22 ++++++++-------------- src/Sky_TEST.cc | 26 +++++++++++++------------- test/integration/scene_dom.cc | 2 +- test/sdf/scene_with_sky.sdf | 2 +- 6 files changed, 29 insertions(+), 31 deletions(-) diff --git a/include/sdf/Sky.hh b/include/sdf/Sky.hh index 038a9f902..ab1f21922 100644 --- a/include/sdf/Sky.hh +++ b/include/sdf/Sky.hh @@ -103,11 +103,11 @@ namespace sdf /// \brief Get the skybox texture URI. /// \return The URI of the skybox texture. - public: std::string Uri() const; + public: std::string CubemapUri() const; /// \brief Set the skybox texture URI. /// \param[in] _uri The URI of the skybox texture. - public: void SetUri(const std::string &_uri); + public: void SetCubemapUri(const std::string &_uri); /// \brief Load the sky based on a element pointer. This is *not* the /// usual entry point. Typical usage of the SDF DOM is through the Root diff --git a/sdf/1.9/scene.sdf b/sdf/1.9/scene.sdf index 01b26a7a2..13da7702b 100644 --- a/sdf/1.9/scene.sdf +++ b/sdf/1.9/scene.sdf @@ -46,6 +46,10 @@ Ambient cloud color + + + Skybox texture uri + diff --git a/src/Sky.cc b/src/Sky.cc index 095749760..901316ad5 100644 --- a/src/Sky.cc +++ b/src/Sky.cc @@ -49,7 +49,7 @@ class sdf::Sky::Implementation ignition::math::Color(0.8f, 0.8f, 0.8f); /// \brief Skybox texture URI - public: std::string uri = "__default__"; + public: std::string cubemapUri = ""; /// \brief The SDF element pointer used during load. public: sdf::ElementPtr sdf; @@ -158,15 +158,15 @@ void Sky::SetCloudAmbient(const ignition::math::Color &_ambient) } ////////////////////////////////////////////////// -std::string Sky::Uri() const +std::string Sky::CubemapUri() const { - return this->dataPtr->uri; + return this->dataPtr->cubemapUri; } ////////////////////////////////////////////////// -void Sky::SetUri(const std::string &_uri) +void Sky::SetCubemapUri(const std::string &_uri) { - this->dataPtr->uri = _uri; + this->dataPtr->cubemapUri = _uri; } ///////////////////////////////////////////////// @@ -191,6 +191,8 @@ Errors Sky::Load(ElementPtr _sdf) _sdf->Get("sunrise", this->dataPtr->sunrise).first; this->dataPtr->sunset = _sdf->Get("sunset", this->dataPtr->sunset).first; + this->dataPtr->cubemapUri = + _sdf->Get("cubemap_uri", this->dataPtr->cubemapUri).first; if ( _sdf->HasElement("clouds")) { @@ -209,14 +211,6 @@ Errors Sky::Load(ElementPtr _sdf) this->dataPtr->cloudAmbient).first; } - // Optional uri element. If not provided, assume there is some default in - // downstream implementation. - if (_sdf->HasElement("uri")) - { - this->dataPtr->uri = _sdf->Get("uri", - this->dataPtr->uri).first; - } - return errors; } @@ -236,7 +230,7 @@ sdf::ElementPtr Sky::ToElement() const elem->GetElement("time")->Set(this->Time()); elem->GetElement("sunrise")->Set(this->Sunrise()); elem->GetElement("sunset")->Set(this->Sunset()); - elem->GetElement("uri")->Set(this->Uri()); + elem->GetElement("cubemap_uri")->Set(this->CubemapUri()); sdf::ElementPtr cloudElem = elem->GetElement("clouds"); cloudElem->GetElement("speed")->Set(this->CloudSpeed()); diff --git a/src/Sky_TEST.cc b/src/Sky_TEST.cc index f1d2393ac..81d6a1632 100644 --- a/src/Sky_TEST.cc +++ b/src/Sky_TEST.cc @@ -31,7 +31,7 @@ TEST(DOMSky, Construction) EXPECT_DOUBLE_EQ(0.5, sky.CloudMeanSize()); EXPECT_EQ(ignition::math::Color(0.8f, 0.8f, 0.8f), sky.CloudAmbient()); - EXPECT_EQ("", sky.Uri()); + EXPECT_EQ("", sky.CubemapUri()); } ///////////////////////////////////////////////// @@ -49,7 +49,7 @@ TEST(DOMSky, CopyConstruction) sky.SetCloudHumidity(0.9); sky.SetCloudMeanSize(0.123); sky.SetCloudAmbient(ignition::math::Color::Blue); - sky.SetUri("dummyUri"); + sky.SetCubemapUri("dummyUri"); sdf::Sky sky2(sky); EXPECT_DOUBLE_EQ(1.0, sky2.Time()); @@ -60,7 +60,7 @@ TEST(DOMSky, CopyConstruction) EXPECT_DOUBLE_EQ(0.9, sky2.CloudHumidity()); EXPECT_DOUBLE_EQ(0.123, sky2.CloudMeanSize()); EXPECT_EQ(ignition::math::Color::Blue, sky2.CloudAmbient()); - EXPECT_EQ("dummyUri", sky2.Uri()); + EXPECT_EQ("dummyUri", sky2.CubemapUri()); EXPECT_NE(nullptr, sky2.Element()); EXPECT_EQ(sky.Element(), sky2.Element()); @@ -78,7 +78,7 @@ TEST(DOMSky, MoveConstruction) sky.SetCloudHumidity(0.9); sky.SetCloudMeanSize(0.123); sky.SetCloudAmbient(ignition::math::Color::Blue); - sky.SetUri("dummyUri"); + sky.SetCubemapUri("dummyUri"); sdf::Sky sky2(std::move(sky)); EXPECT_DOUBLE_EQ(1.0, sky2.Time()); @@ -89,7 +89,7 @@ TEST(DOMSky, MoveConstruction) EXPECT_DOUBLE_EQ(0.9, sky2.CloudHumidity()); EXPECT_DOUBLE_EQ(0.123, sky2.CloudMeanSize()); EXPECT_EQ(ignition::math::Color::Blue, sky2.CloudAmbient()); - EXPECT_EQ("dummyUri", sky2.Uri()); + EXPECT_EQ("dummyUri", sky2.CubemapUri()); } ///////////////////////////////////////////////// @@ -104,7 +104,7 @@ TEST(DOMSky, MoveAssignmentOperator) sky.SetCloudHumidity(0.9); sky.SetCloudMeanSize(0.123); sky.SetCloudAmbient(ignition::math::Color::Blue); - sky.SetUri("dummyUri"); + sky.SetCubemapUri("dummyUri"); sdf::Sky sky2; sky2 = std::move(sky); @@ -116,7 +116,7 @@ TEST(DOMSky, MoveAssignmentOperator) EXPECT_DOUBLE_EQ(0.9, sky2.CloudHumidity()); EXPECT_DOUBLE_EQ(0.123, sky2.CloudMeanSize()); EXPECT_EQ(ignition::math::Color::Blue, sky2.CloudAmbient()); - EXPECT_EQ("dummyUri", sky2.Uri()); + EXPECT_EQ("dummyUri", sky2.CubemapUri()); } ///////////////////////////////////////////////// @@ -131,7 +131,7 @@ TEST(DOMSky, AssignmentOperator) sky.SetCloudHumidity(0.9); sky.SetCloudMeanSize(0.123); sky.SetCloudAmbient(ignition::math::Color::Blue); - sky.SetUri("dummyUri"); + sky.SetCubemapUri("dummyUri"); sdf::Sky sky2; sky2 = sky; @@ -143,7 +143,7 @@ TEST(DOMSky, AssignmentOperator) EXPECT_DOUBLE_EQ(0.9, sky2.CloudHumidity()); EXPECT_DOUBLE_EQ(0.123, sky2.CloudMeanSize()); EXPECT_EQ(ignition::math::Color::Blue, sky2.CloudAmbient()); - EXPECT_EQ("dummyUri", sky2.Uri()); + EXPECT_EQ("dummyUri", sky2.CubemapUri()); } ///////////////////////////////////////////////// @@ -195,8 +195,8 @@ TEST(DOMSky, Set) EXPECT_EQ(ignition::math::Color(0.1f, 0.2f, 0.3f), sky.CloudAmbient()); - sky.SetUri("dummyUri"); - EXPECT_EQ("dummyUri", sky.Uri()); + sky.SetCubemapUri("dummyUri"); + EXPECT_EQ("dummyUri", sky.CubemapUri()); } ///////////////////////////////////////////////// @@ -212,7 +212,7 @@ TEST(DOMSky, ToElement) sky.SetCloudHumidity(0.2); sky.SetCloudMeanSize(0.5); sky.SetCloudAmbient(ignition::math::Color(0.1f, 0.2f, 0.3f, 1.0f)); - sky.SetUri("dummyUri"); + sky.SetCubemapUri("dummyUri"); sdf::ElementPtr elem = sky.ToElement(); ASSERT_NE(nullptr, elem); @@ -228,5 +228,5 @@ TEST(DOMSky, ToElement) EXPECT_DOUBLE_EQ(sky.CloudHumidity(), sky2.CloudHumidity()); EXPECT_DOUBLE_EQ(sky.CloudMeanSize(), sky2.CloudMeanSize()); EXPECT_EQ(sky.CloudAmbient(), sky2.CloudAmbient()); - EXPECT_EQ(sky.Uri(), sky2.Uri()); + EXPECT_EQ(sky.CubemapUri(), sky2.CubemapUri()); } diff --git a/test/integration/scene_dom.cc b/test/integration/scene_dom.cc index b0831ff2f..fd4579a5d 100644 --- a/test/integration/scene_dom.cc +++ b/test/integration/scene_dom.cc @@ -69,5 +69,5 @@ TEST(DOMScene, LoadScene) EXPECT_DOUBLE_EQ(0.2, sky->CloudMeanSize()); EXPECT_DOUBLE_EQ(0.9, sky->CloudHumidity()); EXPECT_EQ(ignition::math::Color(0.1f, 0.2f, 0.3f), sky->CloudAmbient()); - EXPECT_EQ("dummyUri", sky->Uri()); + EXPECT_EQ("dummyUri", sky->CubemapUri()); } diff --git a/test/sdf/scene_with_sky.sdf b/test/sdf/scene_with_sky.sdf index df9de7fa5..c3063fe73 100644 --- a/test/sdf/scene_with_sky.sdf +++ b/test/sdf/scene_with_sky.sdf @@ -19,7 +19,7 @@ 0.9 0.1 0.2 0.3 - dummyUri + dummyUri