From a36e979346e29d0ea12ee6e7f88363e07c2ed4b7 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Tue, 27 Sep 2022 10:18:50 -0700 Subject: [PATCH 1/2] Adds sky cubemap URI to the sky.proto's header Signed-off-by: Nate Koenig --- src/Conversions.cc | 17 +++++++++++++++++ src/Conversions_TEST.cc | 6 ++++++ 2 files changed, 23 insertions(+) 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()); } ///////////////////////////////////////////////// From 5e4c2ec606fc4abdfbc9691c2d1d1bb023a36cc4 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Tue, 27 Sep 2022 11:50:22 -0700 Subject: [PATCH 2/2] Return absolute path when finding a resource Signed-off-by: Nate Koenig --- src/ServerPrivate.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 0381c96660..6f1929b82e 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -490,9 +490,9 @@ bool ServerPrivate::ResourcePathsResolveService( std::string req = _req.data(); // Handle the case where the request is already a valid path - if (common::exists(req)) + if (common::exists(common::absPath(req))) { - _res.set_data(req); + _res.set_data(common::absPath(req)); return true; }