Skip to content

Commit

Permalink
Use new sky cubemap, instead of header (#2060)
Browse files Browse the repository at this point in the history
Signed-off-by: Nate Koenig <[email protected]>
  • Loading branch information
nkoenig authored Aug 4, 2023
1 parent 9f92360 commit e68ff3b
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 20 deletions.
19 changes: 3 additions & 16 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#include <gz/msgs/plugin.pb.h>
#include <gz/msgs/projector.pb.h>
#include <gz/msgs/spheregeom.pb.h>
#include <gz/msgs/sky.pb.h>
#include <gz/msgs/Utility.hh>

#include <gz/math/Angle.hh>
Expand Down Expand Up @@ -794,15 +795,9 @@ msgs::Scene gz::sim::convert(const sdf::Scene &_in)
skyMsg->set_wind_direction(_in.Sky()->CloudDirection().Radian());
skyMsg->set_humidity(_in.Sky()->CloudHumidity());
skyMsg->set_mean_cloud_size(_in.Sky()->CloudMeanSize());
skyMsg->set_cubemap_uri(_in.Sky()->CubemapUri());
msgs::Set(skyMsg->mutable_cloud_ambient(),
_in.Sky()->CloudAmbient());

if (!_in.Sky()->CubemapUri().empty())
{
auto header = skyMsg->mutable_header()->add_data();
header->set_key("cubemap_uri");
header->add_value(_in.Sky()->CubemapUri());
}
}

return out;
Expand Down Expand Up @@ -833,15 +828,7 @@ sdf::Scene gz::sim::convert(const msgs::Scene &_in)
sky.SetCloudHumidity(_in.sky().humidity());
sky.SetCloudMeanSize(_in.sky().mean_cloud_size());
sky.SetCloudAmbient(msgs::Convert(_in.sky().cloud_ambient()));

for (int i = 0; i < _in.sky().header().data_size(); ++i)
{
auto data = _in.sky().header().data(i);
if (data.key() == "cubemap_uri" && data.value_size() > 0)
{
sky.SetCubemapUri(data.value(0));
}
}
sky.SetCubemapUri(_in.sky().cubemap_uri());

out.SetSky(sky);
}
Expand Down
5 changes: 1 addition & 4 deletions src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -733,10 +733,7 @@ TEST(Conversions, Scene)
EXPECT_DOUBLE_EQ(0.88, sceneSkyMsg.sky().mean_cloud_size());
EXPECT_EQ(math::Color::Red,
msgs::Convert(sceneSkyMsg.sky().cloud_ambient()));
ASSERT_GT(sceneSkyMsg.sky().header().data_size(), 0);
auto header = sceneSkyMsg.sky().header().data(0);
EXPECT_EQ("cubemap_uri", header.key());
EXPECT_EQ("test.dds", header.value(0));
EXPECT_EQ("test.dds", sceneSkyMsg.sky().cubemap_uri());

auto newSceneSky = convert<sdf::Scene>(sceneSkyMsg);
ASSERT_NE(nullptr, newSceneSky.Sky());
Expand Down

0 comments on commit e68ff3b

Please sign in to comment.