diff --git a/src/Conversions.cc b/src/Conversions.cc index cc76f158a8..40c57e15b1 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -35,6 +35,7 @@ #include #include #include +#include #include #include @@ -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; @@ -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); } diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index 3d6e3e5861..08ac3e1afd 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -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(sceneSkyMsg); ASSERT_NE(nullptr, newSceneSky.Sky());