diff --git a/CMakeLists.txt b/CMakeLists.txt index 897ea591a0..38008583c9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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}) #-------------------------------------- diff --git a/src/Conversions.cc b/src/Conversions.cc index ac2bda406a..c5db3be557 100644 --- a/src/Conversions.cc +++ b/src/Conversions.cc @@ -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; @@ -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; diff --git a/src/Conversions_TEST.cc b/src/Conversions_TEST.cc index f1876943b4..9033949c9d 100644 --- a/src/Conversions_TEST.cc +++ b/src/Conversions_TEST.cc @@ -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(scene); @@ -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(sceneSkyMsg); ASSERT_NE(nullptr, newSceneSky.Sky()); @@ -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()); } /////////////////////////////////////////////////