Skip to content

Commit

Permalink
change field name to cubemap_uri
Browse files Browse the repository at this point in the history
Signed-off-by: Mabel Zhang <[email protected]>
  • Loading branch information
mabelzhang committed Jun 7, 2022
1 parent 7c47aee commit 68f1041
Show file tree
Hide file tree
Showing 6 changed files with 29 additions and 31 deletions.
4 changes: 2 additions & 2 deletions include/sdf/Sky.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
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>Skybox texture uri</description>
</element>
</element>

<element name="shadows" type="bool" default="true" required="1">
Expand Down
22 changes: 8 additions & 14 deletions src/Sky.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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;
}

/////////////////////////////////////////////////
Expand All @@ -191,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 All @@ -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<std::string>("uri",
this->dataPtr->uri).first;
}

return errors;
}

Expand All @@ -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());
Expand Down
26 changes: 13 additions & 13 deletions src/Sky_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}

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

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

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

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

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

Expand Down

0 comments on commit 68f1041

Please sign in to comment.