diff --git a/include/sdf/Sky.hh b/include/sdf/Sky.hh index f9679f0e3..8bb76a5ae 100644 --- a/include/sdf/Sky.hh +++ b/include/sdf/Sky.hh @@ -18,6 +18,8 @@ #ifndef SDF_SKY_HH_ #define SDF_SKY_HH_ +#include + #include #include @@ -99,6 +101,14 @@ namespace sdf /// \param[in] _ambient cloud ambient color public: void SetCloudAmbient(const ignition::math::Color &_ambient); + /// \brief Get the skybox texture URI. + /// \return The URI of the skybox texture. + public: const std::string &CubemapUri() const; + + /// \brief Set the skybox texture URI. + /// \param[in] _uri The URI of the skybox texture. + 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 /// object. diff --git a/sdf/1.9/scene.sdf b/sdf/1.9/scene.sdf index 01b26a7a2..1428d2c92 100644 --- a/sdf/1.9/scene.sdf +++ b/sdf/1.9/scene.sdf @@ -46,6 +46,10 @@ Ambient cloud color + + + The URI to a cubemap texture for a skybox. A .dds file is typically used for the cubemap. + diff --git a/src/Sky.cc b/src/Sky.cc index 21651b07f..a97ae0242 100644 --- a/src/Sky.cc +++ b/src/Sky.cc @@ -48,6 +48,9 @@ class sdf::Sky::Implementation public: ignition::math::Color cloudAmbient = ignition::math::Color(0.8f, 0.8f, 0.8f); + /// \brief Skybox texture URI + public: std::string cubemapUri = ""; + /// \brief The SDF element pointer used during load. public: sdf::ElementPtr sdf; }; @@ -154,6 +157,18 @@ void Sky::SetCloudAmbient(const ignition::math::Color &_ambient) this->dataPtr->cloudAmbient = _ambient; } +////////////////////////////////////////////////// +const std::string &Sky::CubemapUri() const +{ + return this->dataPtr->cubemapUri; +} + +////////////////////////////////////////////////// +void Sky::SetCubemapUri(const std::string &_uri) +{ + this->dataPtr->cubemapUri = _uri; +} + ///////////////////////////////////////////////// Errors Sky::Load(ElementPtr _sdf) { @@ -176,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")) { @@ -213,6 +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("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 e629493e5..81d6a1632 100644 --- a/src/Sky_TEST.cc +++ b/src/Sky_TEST.cc @@ -31,6 +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.CubemapUri()); } ///////////////////////////////////////////////// @@ -48,6 +49,7 @@ TEST(DOMSky, CopyConstruction) sky.SetCloudHumidity(0.9); sky.SetCloudMeanSize(0.123); sky.SetCloudAmbient(ignition::math::Color::Blue); + sky.SetCubemapUri("dummyUri"); sdf::Sky sky2(sky); EXPECT_DOUBLE_EQ(1.0, sky2.Time()); @@ -58,6 +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.CubemapUri()); EXPECT_NE(nullptr, sky2.Element()); EXPECT_EQ(sky.Element(), sky2.Element()); @@ -75,6 +78,7 @@ TEST(DOMSky, MoveConstruction) sky.SetCloudHumidity(0.9); sky.SetCloudMeanSize(0.123); sky.SetCloudAmbient(ignition::math::Color::Blue); + sky.SetCubemapUri("dummyUri"); sdf::Sky sky2(std::move(sky)); EXPECT_DOUBLE_EQ(1.0, sky2.Time()); @@ -85,6 +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.CubemapUri()); } ///////////////////////////////////////////////// @@ -99,6 +104,7 @@ TEST(DOMSky, MoveAssignmentOperator) sky.SetCloudHumidity(0.9); sky.SetCloudMeanSize(0.123); sky.SetCloudAmbient(ignition::math::Color::Blue); + sky.SetCubemapUri("dummyUri"); sdf::Sky sky2; sky2 = std::move(sky); @@ -110,6 +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.CubemapUri()); } ///////////////////////////////////////////////// @@ -124,6 +131,7 @@ TEST(DOMSky, AssignmentOperator) sky.SetCloudHumidity(0.9); sky.SetCloudMeanSize(0.123); sky.SetCloudAmbient(ignition::math::Color::Blue); + sky.SetCubemapUri("dummyUri"); sdf::Sky sky2; sky2 = sky; @@ -135,6 +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.CubemapUri()); } ///////////////////////////////////////////////// @@ -185,6 +194,9 @@ TEST(DOMSky, Set) sky.SetCloudAmbient(ignition::math::Color(0.1f, 0.2f, 0.3f)); EXPECT_EQ(ignition::math::Color(0.1f, 0.2f, 0.3f), sky.CloudAmbient()); + + sky.SetCubemapUri("dummyUri"); + EXPECT_EQ("dummyUri", sky.CubemapUri()); } ///////////////////////////////////////////////// @@ -200,6 +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.SetCubemapUri("dummyUri"); sdf::ElementPtr elem = sky.ToElement(); ASSERT_NE(nullptr, elem); @@ -215,4 +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.CubemapUri(), sky2.CubemapUri()); } diff --git a/test/integration/scene_dom.cc b/test/integration/scene_dom.cc index edcee1acb..fd4579a5d 100644 --- a/test/integration/scene_dom.cc +++ b/test/integration/scene_dom.cc @@ -69,4 +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->CubemapUri()); } diff --git a/test/sdf/scene_with_sky.sdf b/test/sdf/scene_with_sky.sdf index 1f794c443..c3063fe73 100644 --- a/test/sdf/scene_with_sky.sdf +++ b/test/sdf/scene_with_sky.sdf @@ -19,6 +19,7 @@ 0.9 0.1 0.2 0.3 + dummyUri