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

Adds sky cubemap URI to the sky.proto's header #1739

Merged
merged 2 commits into from
Sep 28, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ set(CMAKE_POLICY_DEFAULT_CMP0077 NEW)
# as protobuf could be find transitively by any dependency
set(protobuf_MODULE_COMPATIBLE TRUE)

ign_find_package(sdformat12 REQUIRED VERSION 12.4)
ign_find_package(sdformat12 REQUIRED VERSION 12.6)
set(SDF_VER ${sdformat12_VERSION_MAJOR})

#--------------------------------------
Expand Down
17 changes: 17 additions & 0 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -863,6 +863,13 @@ msgs::Scene ignition::gazebo::convert(const sdf::Scene &_in)
skyMsg->set_mean_cloud_size(_in.Sky()->CloudMeanSize());
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 @@ -893,6 +900,16 @@ sdf::Scene ignition::gazebo::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));
}
}

out.SetSky(sky);
}
return out;
Expand Down
6 changes: 6 additions & 0 deletions src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -710,6 +710,7 @@ TEST(Conversions, Scene)
sky.SetCloudHumidity(0.11);
sky.SetCloudMeanSize(0.88);
sky.SetCloudAmbient(math::Color::Red);
sky.SetCubemapUri("test.dds");
scene.SetSky(sky);

auto sceneSkyMsg = convert<msgs::Scene>(scene);
Expand All @@ -723,6 +724,10 @@ 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));

auto newSceneSky = convert<sdf::Scene>(sceneSkyMsg);
ASSERT_NE(nullptr, newSceneSky.Sky());
Expand All @@ -734,6 +739,7 @@ TEST(Conversions, Scene)
EXPECT_DOUBLE_EQ(0.11, newSceneSky.Sky()->CloudHumidity());
EXPECT_DOUBLE_EQ(0.88, newSceneSky.Sky()->CloudMeanSize());
EXPECT_EQ(math::Color::Red, newSceneSky.Sky()->CloudAmbient());
EXPECT_EQ("test.dds", newSceneSky.Sky()->CubemapUri());
}

/////////////////////////////////////////////////
Expand Down