Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add skybox URI #1037

Merged
merged 12 commits into from
Jul 6, 2022
10 changes: 10 additions & 0 deletions include/sdf/Sky.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#ifndef SDF_SKY_HH_
#define SDF_SKY_HH_

#include <string>

#include <ignition/math/Color.hh>
#include <ignition/utils/ImplPtr.hh>

Expand Down Expand Up @@ -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.
Expand Down
4 changes: 4 additions & 0 deletions sdf/1.9/scene.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,10 @@
<description>Ambient cloud color</description>
</element>
</element>

<element name="cubemap_uri" type="string" default="" required="0">
<description>The URI to a cubemap texture for a skybox. A .dds file is typically used for the cubemap.</description>
</element>
</element>

<element name="shadows" type="bool" default="true" required="1">
Expand Down
18 changes: 18 additions & 0 deletions src/Sky.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
};
Expand Down Expand Up @@ -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)
{
Expand All @@ -176,6 +191,8 @@ Errors Sky::Load(ElementPtr _sdf)
_sdf->Get<double>("sunrise", this->dataPtr->sunrise).first;
this->dataPtr->sunset =
_sdf->Get<double>("sunset", this->dataPtr->sunset).first;
this->dataPtr->cubemapUri =
_sdf->Get<std::string>("cubemap_uri", this->dataPtr->cubemapUri).first;

if ( _sdf->HasElement("clouds"))
{
Expand Down Expand Up @@ -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());
Expand Down
14 changes: 14 additions & 0 deletions src/Sky_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}

/////////////////////////////////////////////////
Expand All @@ -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());
Expand All @@ -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());
Expand All @@ -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());
Expand All @@ -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());
}

/////////////////////////////////////////////////
Expand All @@ -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);
Expand All @@ -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());
}

/////////////////////////////////////////////////
Expand All @@ -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;
Expand All @@ -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());
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -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());
}

/////////////////////////////////////////////////
Expand All @@ -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);
Expand All @@ -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());
}
1 change: 1 addition & 0 deletions test/integration/scene_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}
1 change: 1 addition & 0 deletions test/sdf/scene_with_sky.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<humidity>0.9</humidity>
<ambient>0.1 0.2 0.3</ambient>
</clouds>
<cubemap_uri>dummyUri</cubemap_uri>
</sky>
</scene>

Expand Down