From 34d14a768a09b8ffbcc0d66f2195708f29079653 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Mon, 18 Sep 2023 21:52:58 +0000 Subject: [PATCH 1/8] Re-enable all Windows tests to see what breaks Signed-off-by: Michael Carroll --- include/gz/fuel_tools/Helpers.hh | 13 ++++++------- src/CollectionIdentifier_TEST.cc | 2 +- src/FuelClient.cc | 25 +++++++++++-------------- src/FuelClient_TEST.cc | 16 ++++++++-------- src/Helpers.cc | 13 +++++++++++-- src/Helpers_TEST.cc | 32 +++++++++++++++++++++++++------- src/LocalCache_TEST.cc | 12 ++++++------ 7 files changed, 68 insertions(+), 45 deletions(-) diff --git a/include/gz/fuel_tools/Helpers.hh b/include/gz/fuel_tools/Helpers.hh index 82989018..95f4fc05 100644 --- a/include/gz/fuel_tools/Helpers.hh +++ b/include/gz/fuel_tools/Helpers.hh @@ -35,18 +35,17 @@ #define gz_strdup strdup #endif -namespace gz -{ -namespace fuel_tools +namespace gz::fuel_tools { + +std::string sanitizeAuthority(const std::string &_uriAuthority); + /// \brief Convert a URI to a string suitable to use as a path on disk. /// It strips the scheme and authority's `//` prefix. /// \param[in] _uri URI to convert. /// \return String suitable to use in file paths GZ_FUEL_TOOLS_VISIBLE std::string uriToPath(const gz::common::URI &_uri); -} -} +} // namespace gz::fuel_tools -// GZ_FUEL_TOOLS_HELPERS_HH_ -#endif +#endif // GZ_FUEL_TOOLS_HELPERS_HH_ diff --git a/src/CollectionIdentifier_TEST.cc b/src/CollectionIdentifier_TEST.cc index a7025263..e18b393a 100644 --- a/src/CollectionIdentifier_TEST.cc +++ b/src/CollectionIdentifier_TEST.cc @@ -45,7 +45,7 @@ TEST(CollectionIdentifier, SetFields) ///////////////////////////////////////////////// /// \brief Unique Name // See https://github.com/gazebosim/gz-fuel-tools/issues/231 -TEST(CollectionIdentifier, GZ_UTILS_TEST_DISABLED_ON_WIN32(UniqueName)) +TEST(CollectionIdentifier, UniqueName) { gz::fuel_tools::ServerConfig srv1; srv1.SetUrl(common::URI("https://localhost:8001")); diff --git a/src/FuelClient.cc b/src/FuelClient.cc index 45902eec..4f85e69a 100644 --- a/src/FuelClient.cc +++ b/src/FuelClient.cc @@ -251,22 +251,20 @@ FuelClient::FuelClient(const ClientConfig &_config, const Rest &_rest) this->dataPtr->cache = std::make_unique(&(this->dataPtr->config)); - this->dataPtr->urlModelRegex.reset(new std::regex( - this->dataPtr->kModelUrlRegexStr)); - this->dataPtr->urlWorldRegex.reset(new std::regex( - this->dataPtr->kWorldUrlRegexStr)); - this->dataPtr->urlModelFileRegex.reset(new std::regex( - this->dataPtr->kModelFileUrlRegexStr)); - this->dataPtr->urlWorldFileRegex.reset(new std::regex( - this->dataPtr->kWorldFileUrlRegexStr)); - this->dataPtr->urlCollectionRegex.reset(new std::regex( - this->dataPtr->kCollectionUrlRegexStr)); + this->dataPtr->urlModelRegex = + std::make_unique(this->dataPtr->kModelUrlRegexStr); + this->dataPtr->urlWorldRegex = + std::make_unique(this->dataPtr->kWorldUrlRegexStr); + this->dataPtr->urlModelFileRegex = + std::make_unique(this->dataPtr->kModelFileUrlRegexStr); + this->dataPtr->urlWorldFileRegex = + std::make_unique(this->dataPtr->kWorldFileUrlRegexStr); + this->dataPtr->urlCollectionRegex = + std::make_unique(this->dataPtr->kCollectionUrlRegexStr); } ////////////////////////////////////////////////// -FuelClient::~FuelClient() -{ -} +FuelClient::~FuelClient() = default; ////////////////////////////////////////////////// ClientConfig &FuelClient::Config() @@ -336,7 +334,6 @@ ModelIter FuelClient::Models(const ServerConfig &_server) const Result FuelClient::WorldDetails(const WorldIdentifier &_id, WorldIdentifier &_world) const { - return this->WorldDetails(_id, _world, {}); } diff --git a/src/FuelClient_TEST.cc b/src/FuelClient_TEST.cc index 86350733..3bb63721 100644 --- a/src/FuelClient_TEST.cc +++ b/src/FuelClient_TEST.cc @@ -37,10 +37,10 @@ using namespace gz::fuel_tools; /// Taken from LocalCache_TEST void createLocalModel(ClientConfig &_conf) { - gzdbg << "Creating local model in [" << common::cwd() << "]" << std::endl; - auto modelPath = common::joinPaths( - "test_cache", "localhost:8007", "alice", "models", "My Model"); + "test_cache", + sanitizeAuthority("localhost:8007"), + "alice", "models", "My Model"); ASSERT_TRUE(common::createDirectories( common::joinPaths(modelPath, "2", "meshes"))); @@ -92,10 +92,10 @@ void createLocalModel(ClientConfig &_conf) /// Taken from LocalCache_TEST void createLocalWorld(ClientConfig &_conf) { - gzdbg << "Creating local world in [" << common::cwd() << "]" << std::endl; - auto worldPath = common::joinPaths( - "test_cache", "localhost:8007", "banana", "worlds", "My World"); + "test_cache", + sanitizeAuthority("localhost:8007"), + "banana", "worlds", "My World"); ASSERT_TRUE(common::createDirectories(common::joinPaths(worldPath, "2"))); ASSERT_TRUE(common::createDirectories(common::joinPaths(worldPath, "3"))); @@ -615,7 +615,7 @@ TEST_P(FuelClientDownloadTest, DownloadModel) ///////////////////////////////////////////////// // Windows doesn't support colons in filenames // https://github.com/gazebosim/gz-fuel-tools/issues/106 -TEST_F(FuelClientTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(ModelDependencies)) +TEST_F(FuelClientTest, ModelDependencies) { ClientConfig config; config.SetCacheLocation(common::joinPaths(common::cwd(), "test_cache")); @@ -687,7 +687,7 @@ TEST_F(FuelClientTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(ModelDependencies)) // Windows doesn't support colons in filenames // https://github.com/gazebosim/gz-fuel-tools/issues/106 // See https://github.com/gazebosim/gz-fuel-tools/issues/231 -TEST_F(FuelClientTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(CachedModel)) +TEST_F(FuelClientTest, CachedModel) { ClientConfig config; config.SetCacheLocation(common::joinPaths(common::cwd(), "test_cache")); diff --git a/src/Helpers.cc b/src/Helpers.cc index b8dfc395..eb01f5e8 100644 --- a/src/Helpers.cc +++ b/src/Helpers.cc @@ -19,8 +19,15 @@ #include "gz/fuel_tools/Helpers.hh" -using namespace gz; -using namespace fuel_tools; +////////////////////////////////////////////////// +std::string gz::fuel_tools::sanitizeAuthority(const std::string &_uriAuthority) +{ + // Take an authority of the form userinfo@host:port and turn it into a valid + // subset of characters for a path. + auto output = gz::common::replaceAll(_uriAuthority, ":", "%3A"); + output = gz::common::replaceAll(output, "@", "%40"); + return output; +} ////////////////////////////////////////////////// std::string gz::fuel_tools::uriToPath(const common::URI &_uri) @@ -43,6 +50,8 @@ std::string gz::fuel_tools::uriToPath(const common::URI &_uri) authority = authority.substr(2); } + authority = sanitizeAuthority(authority); + if (authority.empty()) { return path; diff --git a/src/Helpers_TEST.cc b/src/Helpers_TEST.cc index 15171c60..e28b9e9e 100644 --- a/src/Helpers_TEST.cc +++ b/src/Helpers_TEST.cc @@ -22,21 +22,31 @@ using namespace gz; using namespace fuel_tools; +///////////////////////////////////////////////// +TEST(HelpersTEST, SanitizeAuthority) +{ + EXPECT_EQ("localhost%3A8000", sanitizeAuthority("localhost:8000")); + EXPECT_EQ("localhost%3A8001", sanitizeAuthority("localhost:8001")); + EXPECT_EQ("localhost%3A%3A8002", sanitizeAuthority("localhost::8002")); + EXPECT_EQ("gazebo%40localhost", sanitizeAuthority("gazebo@localhost")); +} + ///////////////////////////////////////////////// TEST(HelpersTEST, UriToPathNoAuthority) { -// TO-DO: Update this test after gz-fuel-tools#204 is addressed #ifdef WIN32 + const std::string testStr0 = R"(localhost:8000)"; const std::string testStr1 = R"(localhost:8000\some\path)"; const std::string testStr2 = R"(localhost:8000\some\path\)"; #else + const std::string testStr0 = R"(localhost:8000)"; const std::string testStr1 = R"(localhost:8000/some/path)"; const std::string testStr2 = R"(localhost:8000/some/path/)"; #endif { common::URI uri{"http://localhost:8000"}; - EXPECT_EQ("localhost:8000", uriToPath(uri)); + EXPECT_EQ(testStr0, uriToPath(uri)); } { @@ -53,20 +63,28 @@ TEST(HelpersTEST, UriToPathNoAuthority) ///////////////////////////////////////////////// TEST(HelpersTEST, UriToPathHasAuthority) { +#ifdef WIN32 + const std::string testStr0 = R"(localhost%3A8000)"; + const std::string testStr1 = R"(localhost%3A8000\some\path)"; + const std::string testStr2 = R"(localhost%3A8000\some\path\)"; +#else + const std::string testStr0 = R"(localhost%3A8000)"; + const std::string testStr1 = R"(localhost%3A8000/some/path)"; + const std::string testStr2 = R"(localhost%3A8000/some/path/)"; +#endif + { common::URI uri{"http://localhost:8000", true}; - EXPECT_EQ("localhost:8000", uriToPath(uri)); + EXPECT_EQ(testStr0, uriToPath(uri)); } { common::URI uri{"http://localhost:8000/some/path", true}; - EXPECT_EQ(common::joinPaths("localhost:8000", "some", "path"), - uriToPath(uri)); + EXPECT_EQ(testStr1, uriToPath(uri)); } { common::URI uri{"http://localhost:8000/some/path/", true}; - EXPECT_EQ(common::separator(common::joinPaths("localhost:8000", "some", - "path")), uriToPath(uri)); + EXPECT_EQ(testStr2, uriToPath(uri)); } } diff --git a/src/LocalCache_TEST.cc b/src/LocalCache_TEST.cc index 4e9844b4..844c4d88 100644 --- a/src/LocalCache_TEST.cc +++ b/src/LocalCache_TEST.cc @@ -226,7 +226,7 @@ class LocalCacheTest : public ::testing::Test ///////////////////////////////////////////////// /// \brief Iterate through all models in cache // See https://github.com/gazebosim/gz-fuel-tools/issues/231 -TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(AllModels)) +TEST_F(LocalCacheTest, AllModels) { ClientConfig conf; conf.SetCacheLocation(common::joinPaths(common::cwd(), "test_cache")); @@ -252,7 +252,7 @@ TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(AllModels)) /// \brief Get all models that match some fields /// \brief Iterate through all models in cache // See https://github.com/gazebosim/gz-fuel-tools/issues/307 -TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MatchingModels)) +TEST_F(LocalCacheTest, MatchingModels) { ClientConfig conf; conf.Clear(); @@ -296,7 +296,7 @@ TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MatchingModels)) /// \brief Get a specific model from cache /// \brief Iterate through all models in cache // See https://github.com/gazebosim/gz-fuel-tools/issues/307 -TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MatchingModel)) +TEST_F(LocalCacheTest, MatchingModel) { ClientConfig conf; conf.SetCacheLocation(common::joinPaths(common::cwd(), "test_cache")); @@ -350,7 +350,7 @@ TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MatchingModel)) /// \brief Iterate through all worlds in cache /// \brief Iterate through all models in cache // See https://github.com/gazebosim/gz-fuel-tools/issues/307 -TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(AllWorlds)) +TEST_F(LocalCacheTest, AllWorlds) { ClientConfig conf; conf.SetCacheLocation(common::joinPaths(common::cwd(), "test_cache")); @@ -380,7 +380,7 @@ TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(AllWorlds)) /// \brief Get all worlds that match some fields /// \brief Iterate through all models in cache // See https://github.com/gazebosim/gz-fuel-tools/issues/307 -TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MatchingWorlds)) +TEST_F(LocalCacheTest, MatchingWorlds) { ClientConfig conf; conf.Clear(); @@ -412,7 +412,7 @@ TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MatchingWorlds)) /// \brief Get a specific world from cache /// \brief Iterate through all models in cache // See https://github.com/gazebosim/gz-fuel-tools/issues/307 -TEST_F(LocalCacheTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(MatchingWorld)) +TEST_F(LocalCacheTest, MatchingWorld) { ClientConfig conf; conf.SetCacheLocation(common::joinPaths(common::cwd(), "test_cache")); From a57d7569169f0b8b59b35620158445606f43ca7a Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Mon, 18 Sep 2023 22:58:52 +0000 Subject: [PATCH 2/8] Mark visible and add docs Signed-off-by: Michael Carroll --- include/gz/fuel_tools/Helpers.hh | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/include/gz/fuel_tools/Helpers.hh b/include/gz/fuel_tools/Helpers.hh index 95f4fc05..1bcaf94c 100644 --- a/include/gz/fuel_tools/Helpers.hh +++ b/include/gz/fuel_tools/Helpers.hh @@ -37,7 +37,19 @@ namespace gz::fuel_tools { - +/// \brief Convert the authority portion of a URI to a string +/// suitable to be used as a path on disk for all platforms. +/// +/// It encodes illegal characters on Windows and Linux filesystems with +/// their corresponding URL-encoded values. +/// +/// This assumes an authority of the form: username@host:port +/// "@" is encoded as %40 +/// ":" is encoded as %3A +/// +/// \param[in] _uriAuthority the authority section of the URI to convert. +/// \return String suitable to use in file paths +GZ_FUEL_TOOLS_VISIBLE std::string sanitizeAuthority(const std::string &_uriAuthority); /// \brief Convert a URI to a string suitable to use as a path on disk. From 94fc9dc69e66d5dd69a34fd6e4d09c49d960ae50 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Mon, 18 Sep 2023 23:14:20 +0000 Subject: [PATCH 3/8] Fix local_cache tests Signed-off-by: Michael Carroll --- src/LocalCache_TEST.cc | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/LocalCache_TEST.cc b/src/LocalCache_TEST.cc index 844c4d88..780d9242 100644 --- a/src/LocalCache_TEST.cc +++ b/src/LocalCache_TEST.cc @@ -26,6 +26,7 @@ #include #include "gz/fuel_tools/ClientConfig.hh" +#include "gz/fuel_tools/Helpers.hh" #include "gz/fuel_tools/WorldIdentifier.hh" #include "LocalCache.hh" @@ -38,7 +39,8 @@ void createLocal6Models(ClientConfig &_conf) { gzdbg << "Creating 6 local models in [" << common::cwd() << "]" << std::endl; - auto serverPath = common::joinPaths("test_cache", "localhost:8001"); + auto serverPath = + common::joinPaths("test_cache", sanitizeAuthority("localhost:8001")); ASSERT_TRUE(common::createDirectories(common::joinPaths(serverPath, "alice", "models", "am1", "2"))); ASSERT_TRUE(common::createDirectories(common::joinPaths(serverPath, @@ -90,7 +92,8 @@ void createLocal3Models(ClientConfig &_conf) { gzdbg << "Creating 3 local models in [" << common::cwd() << "]" << std::endl; - auto serverPath = common::joinPaths("test_cache", "localhost:8007"); + auto serverPath = + common::joinPaths("test_cache", sanitizeAuthority("localhost:8007")); ASSERT_TRUE(common::createDirectories(common::joinPaths(serverPath, "alice", "models", "am1", "2"))); ASSERT_TRUE(common::createDirectories(common::joinPaths(serverPath, @@ -124,7 +127,8 @@ void createLocal6Worlds(ClientConfig &_conf) { gzdbg << "Creating 6 local worlds in [" << common::cwd() << "]" << std::endl; - auto serverPath = common::joinPaths("test_cache", "localhost:8001"); + auto serverPath = + common::joinPaths("test_cache", sanitizeAuthority("localhost:8001")); ASSERT_TRUE(common::createDirectories(common::joinPaths(serverPath, "alice", "worlds", "am1", "2"))); ASSERT_TRUE(common::createDirectories(common::joinPaths(serverPath, @@ -176,7 +180,8 @@ void createLocal3Worlds(ClientConfig &_conf) { gzdbg << "Creating 3 local worlds in [" << common::cwd() << "]" << std::endl; - auto serverPath = common::joinPaths("test_cache", "localhost:8007"); + auto serverPath = common::joinPaths( + "test_cache", sanitizeAuthority("localhost:8007")); ASSERT_TRUE(common::createDirectories(common::joinPaths(serverPath, "alice", "worlds", "am1", "2"))); ASSERT_TRUE(common::createDirectories(common::joinPaths(serverPath, @@ -367,13 +372,8 @@ TEST_F(LocalCacheTest, AllWorlds) ++iter; } EXPECT_EQ(9u, uniqueNames.size()); -#ifdef _WIN32 EXPECT_NE(uniqueNames.end(), uniqueNames.find( - gz::common::joinPaths("localhost8001", "alice", "worlds", "am1"))); -#else - EXPECT_NE(uniqueNames.end(), uniqueNames.find( - gz::common::joinPaths("localhost:8001", "alice", "worlds", "am1"))); -#endif + gz::common::joinPaths(sanitizeAuthority("localhost:8001"), "alice", "worlds", "am1"))); } ///////////////////////////////////////////////// From 7af235dddc873ad85a0456396feaac6e99d1ab43 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 20 Sep 2023 17:07:13 +0000 Subject: [PATCH 4/8] Fix server URLs Signed-off-by: Michael Carroll --- src/FuelClient.cc | 12 ++++++-- src/FuelClient_TEST.cc | 62 ++++++++++++++++++++++++------------------ src/LocalCache.cc | 4 +++ src/WorldIdentifier.cc | 3 +- 4 files changed, 50 insertions(+), 31 deletions(-) diff --git a/src/FuelClient.cc b/src/FuelClient.cc index 4f85e69a..e6fbe3a5 100644 --- a/src/FuelClient.cc +++ b/src/FuelClient.cc @@ -1094,7 +1094,11 @@ bool FuelClient::ParseModelUrl(const common::URI &_modelUrl, } // Get remaining server information from config - _id.Server().SetUrl(common::URI(scheme + "://" + server)); + common::URI serverUri; + serverUri.SetScheme(scheme); + serverUri.SetAuthority(gz::common::URIAuthority("//" + server)); + + _id.Server().SetUrl(serverUri); _id.Server().SetVersion(apiVersion); for (const auto &s : this->dataPtr->config.Servers()) { @@ -1160,7 +1164,11 @@ bool FuelClient::ParseWorldUrl(const common::URI &_worldUrl, } // Get remaining server information from config - _id.Server().SetUrl(common::URI(scheme + "://" + server)); + common::URI serverUri; + serverUri.SetScheme(scheme); + serverUri.SetAuthority(gz::common::URIAuthority("//" + server)); + + _id.Server().SetUrl(serverUri); _id.Server().SetVersion(apiVersion); for (const auto &s : this->dataPtr->config.Servers()) { diff --git a/src/FuelClient_TEST.cc b/src/FuelClient_TEST.cc index 3bb63721..d03caae6 100644 --- a/src/FuelClient_TEST.cc +++ b/src/FuelClient_TEST.cc @@ -23,6 +23,7 @@ #include "gz/fuel_tools/FuelClient.hh" #include "gz/fuel_tools/ClientConfig.hh" +#include "gz/fuel_tools/Helpers.hh" #include "gz/fuel_tools/Result.hh" #include "gz/fuel_tools/WorldIdentifier.hh" @@ -82,7 +83,7 @@ void createLocalModel(ClientConfig &_conf) } gz::fuel_tools::ServerConfig srv; - srv.SetUrl(common::URI("http://localhost:8007/")); + srv.SetUrl(common::URI("http://localhost:8007/", true)); _conf.AddServer(srv); } @@ -113,7 +114,7 @@ void createLocalWorld(ClientConfig &_conf) } gz::fuel_tools::ServerConfig srv; - srv.SetUrl(gz::common::URI("http://localhost:8007/")); + srv.SetUrl(gz::common::URI("http://localhost:8007/", true)); _conf.AddServer(srv); } @@ -697,66 +698,69 @@ TEST_F(FuelClientTest, CachedModel) FuelClient client(config); EXPECT_EQ(config.CacheLocation(), client.Config().CacheLocation()); + auto basePath = common::joinPaths(common::cwd(), "test_cache", + sanitizeAuthority("localhost:8007")); + // Cached model (no version) { - common::URI url{"http://localhost:8007/1.0/alice/models/My Model"}; + common::URI url{"http://localhost:8007/1.0/alice/models/My Model", true}; std::string path; auto result = client.CachedModel(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", "localhost:8007", + EXPECT_EQ(common::joinPaths(basePath, "alice", "models", "My Model", "3"), path); } // Cached model (tip) { - common::URI url{"http://localhost:8007/1.0/alice/models/My Model/tip"}; + common::URI url{"http://localhost:8007/1.0/alice/models/My Model/tip", true}; std::string path; auto result = client.CachedModel(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", "localhost:8007", + EXPECT_EQ(common::joinPaths(basePath, "alice", "models", "My Model", "3"), path); } // Cached model (version number) { - common::URI url{"http://localhost:8007/1.0/alice/models/My Model/2"}; + common::URI url{"http://localhost:8007/1.0/alice/models/My Model/2", true}; std::string path; auto result = client.CachedModel(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", "localhost:8007", + EXPECT_EQ(common::joinPaths(basePath, "alice", "models", "My Model", "2"), path); } // Cached model file (tip) { common::URI url{ - "http://localhost:8007/1.0/alice/models/My Model/tip/files/model.sdf"}; + "http://localhost:8007/1.0/alice/models/My Model/tip/files/model.sdf", true}; std::string path; auto result = client.CachedModelFile(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", "localhost:8007", + EXPECT_EQ(common::joinPaths(basePath, "alice", "models", "My Model", "3", "model.sdf"), path); } // Deeper cached model file { common::URI url{"http://localhost:8007/1.0/alice/models/My Model/2/files/" - "meshes/model.dae"}; + "meshes/model.dae", true}; std::string path; auto result = client.CachedModelFile(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", "localhost:8007", + EXPECT_EQ(common::joinPaths(basePath, "alice", "models", "My Model", "2", "meshes", "model.dae"), path); } // Non-cached model { - common::URI url{"http://localhost:8007/1.0/alice/models/Banana"}; + common::URI url{"http://localhost:8007/1.0/alice/models/Banana", true}; std::string path; auto result = client.CachedModel(url, path); EXPECT_FALSE(result); @@ -765,7 +769,7 @@ TEST_F(FuelClientTest, CachedModel) // Non-cached model (when looking for file) { - common::URI url{"http://localhost:8007/1.0/alice/models/Banana/model.sdf"}; + common::URI url{"http://localhost:8007/1.0/alice/models/Banana/model.sdf", true}; std::string path; auto result = client.CachedModelFile(url, path); EXPECT_FALSE(result); @@ -775,7 +779,7 @@ TEST_F(FuelClientTest, CachedModel) // Non-cached model file { common::URI url{"http://localhost:8007/1.0/alice/models/My Model/tip/files/" - "meshes/banana.dae" + "meshes/banana.dae", true }; std::string path; auto result = client.CachedModelFile(url, path); @@ -785,7 +789,7 @@ TEST_F(FuelClientTest, CachedModel) // Model root URL to model file { - common::URI url{"http://localhost:8007/1.0/alice/models/My Model"}; + common::URI url{"http://localhost:8007/1.0/alice/models/My Model", true}; std::string path; auto result = client.CachedModelFile(url, path); EXPECT_FALSE(result); @@ -1158,6 +1162,9 @@ TEST_F(FuelClientTest, CachedWorld) FuelClient client(config); EXPECT_EQ(config.CacheLocation(), client.Config().CacheLocation()); + auto basePath = common::joinPaths(common::cwd(), "test_cache", + sanitizeAuthority("localhost:8007")); + // Cached world (no version) { common::URI url{"http://localhost:8007/1.0/banana/worlds/My World"}; @@ -1165,8 +1172,8 @@ TEST_F(FuelClientTest, CachedWorld) auto result = client.CachedWorld(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", - "localhost:8007", "banana", "worlds", "My World", "3"), path); + EXPECT_EQ(common::joinPaths(basePath, + "banana", "worlds", "My World", "3"), path); } // Cached world (tip) @@ -1176,8 +1183,8 @@ TEST_F(FuelClientTest, CachedWorld) auto result = client.CachedWorld(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", - "localhost:8007", "banana", "worlds", "My World", "3"), path); + EXPECT_EQ(common::joinPaths(basePath, + "banana", "worlds", "My World", "3"), path); } // Cached world (version number) @@ -1187,8 +1194,8 @@ TEST_F(FuelClientTest, CachedWorld) auto result = client.CachedWorld(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", - "localhost:8007", "banana", "worlds", "My World", "2"), path); + EXPECT_EQ(common::joinPaths(basePath, + "banana", "worlds", "My World", "2"), path); } // Cached world file (tip) @@ -1199,8 +1206,8 @@ TEST_F(FuelClientTest, CachedWorld) auto result = client.CachedWorldFile(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", - "localhost:8007", "banana", "worlds", "My World", "3", + EXPECT_EQ(common::joinPaths(basePath, + "banana", "worlds", "My World", "3", "strawberry.world"), path); } @@ -1212,8 +1219,8 @@ TEST_F(FuelClientTest, CachedWorld) auto result = client.CachedWorldFile(url, path); EXPECT_TRUE(result); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, result.Type()); - EXPECT_EQ(common::joinPaths(common::cwd(), "test_cache", - "localhost:8007", "banana", "worlds", "My World", "2", + EXPECT_EQ(common::joinPaths(basePath, + "banana", "worlds", "My World", "2", "strawberry.world"), path); } @@ -1498,7 +1505,8 @@ TEST_F(FuelClientTest, PatchModelFail) // Bad model.config result = client.PatchModel(modelId, headers, - common::joinPaths(common::cwd(), "test_cache", "localhost:8007", + common::joinPaths(common::cwd(), "test_cache", + sanitizeAuthority("localhost:8007"), "alice", "models", "My Model", "3")); EXPECT_EQ(ResultType::UPLOAD_ERROR, result.Type()); diff --git a/src/LocalCache.cc b/src/LocalCache.cc index 60023534..9da08881 100644 --- a/src/LocalCache.cc +++ b/src/LocalCache.cc @@ -232,10 +232,13 @@ ModelIter LocalCache::AllModels() { for (auto &server : this->dataPtr->config->Servers()) { + auto uri = server.Url(); + std::string path = common::joinPaths( this->dataPtr->config->CacheLocation(), uriToPath(server.Url())); auto srvModels = this->dataPtr->ModelsInServer(path); + for (auto &mod : srvModels) { mod.dataPtr->id.SetServer(server); @@ -284,6 +287,7 @@ Model LocalCache::MatchingModel(const ModelIdentifier &_id) for (ModelIter iter = this->AllModels(); iter; ++iter) { ModelIdentifier id = iter->Identification(); + if (_id == id) { if (_id.Version() == id.Version()) diff --git a/src/WorldIdentifier.cc b/src/WorldIdentifier.cc index 9c9296a0..5f290ba0 100644 --- a/src/WorldIdentifier.cc +++ b/src/WorldIdentifier.cc @@ -80,7 +80,7 @@ WorldIdentifier::~WorldIdentifier() ////////////////////////////////////////////////// std::string WorldIdentifier::UniqueName() const { - return common::joinPaths(uriToPath(this->dataPtr->server.Url()), + return common::joinPaths(this->dataPtr->server.Url().Str(), this->dataPtr->owner, "worlds", this->dataPtr->name); @@ -228,4 +228,3 @@ std::string WorldIdentifier::AsPrettyString(const std::string &_prefix) const << this->Server().AsPrettyString(_prefix + " "); return out.str(); } - From 103c074a26bdf92385d42d26d5d90c0d3e3ba011 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 20 Sep 2023 18:39:57 +0000 Subject: [PATCH 5/8] Additional fixes Signed-off-by: Michael Carroll --- src/ClientConfig.cc | 2 +- src/FuelClient.cc | 20 +++++++++++++++++--- src/FuelClient_TEST.cc | 13 +++++++++---- src/LocalCache.cc | 14 +++++++++----- src/ModelIdentifier.cc | 2 +- src/WorldIdentifier.cc | 2 +- 6 files changed, 38 insertions(+), 15 deletions(-) diff --git a/src/ClientConfig.cc b/src/ClientConfig.cc index 0a2764f1..02ba8a13 100644 --- a/src/ClientConfig.cc +++ b/src/ClientConfig.cc @@ -83,7 +83,7 @@ class gz::fuel_tools::ServerConfigPrivate } /// \brief URL to reach server - public: common::URI url{"https://fuel.gazebosim.org"}; + public: common::URI url{"https://fuel.gazebosim.org", true}; /// \brief A key to auth with the server public: std::string key = ""; diff --git a/src/FuelClient.cc b/src/FuelClient.cc index e6fbe3a5..aa643eee 100644 --- a/src/FuelClient.cc +++ b/src/FuelClient.cc @@ -713,7 +713,9 @@ Result FuelClient::DownloadModel(const ModelIdentifier &_id, // Save // Note that the save function doesn't return the path if (zipData.empty() || !this->dataPtr->cache->SaveModel(newId, zipData, true)) + { return Result(ResultType::FETCH_ERROR); + } return this->ModelDependencies(_id, _dependencies); } @@ -1236,7 +1238,11 @@ bool FuelClient::ParseModelFileUrl(const common::URI &_modelFileUrl, } // Get remaining server information from config - _id.Server().SetUrl(common::URI(scheme + "://" + server)); + common::URI serverUri; + serverUri.SetScheme(scheme); + serverUri.SetAuthority(gz::common::URIAuthority("//" + server)); + + _id.Server().SetUrl(serverUri); _id.Server().SetVersion(apiVersion); for (const auto &s : this->dataPtr->config.Servers()) { @@ -1305,7 +1311,11 @@ bool FuelClient::ParseWorldFileUrl(const common::URI &_worldFileUrl, } // Get remaining server information from config - _id.Server().SetUrl(common::URI(scheme + "://" + server)); + common::URI serverUri; + serverUri.SetScheme(scheme); + serverUri.SetAuthority(gz::common::URIAuthority("//" + server)); + + _id.Server().SetUrl(serverUri); _id.Server().SetVersion(apiVersion); for (const auto &s : this->dataPtr->config.Servers()) { @@ -1372,7 +1382,11 @@ bool FuelClient::ParseCollectionUrl(const common::URI &_url, } // Get remaining server information from config - _id.Server().SetUrl(common::URI(scheme + "://" + server)); + common::URI serverUri; + serverUri.SetScheme(scheme); + serverUri.SetAuthority(gz::common::URIAuthority("//" + server)); + + _id.Server().SetUrl(serverUri); _id.Server().SetVersion(apiVersion); for (const auto &s : this->dataPtr->config.Servers()) { diff --git a/src/FuelClient_TEST.cc b/src/FuelClient_TEST.cc index d03caae6..990d6b4a 100644 --- a/src/FuelClient_TEST.cc +++ b/src/FuelClient_TEST.cc @@ -131,6 +131,11 @@ class FuelClientTest: public ::testing::Test ASSERT_FALSE(common::exists("test_cache")); ASSERT_TRUE(common::createDirectories("test_cache")); ASSERT_TRUE(common::isDirectory("test_cache")); + + ASSERT_FALSE(common::exists("test_cache/fuel.gazebosim.org")); + ASSERT_TRUE(common::createDirectories("test_cache/fuel.gazebosim.org")); + ASSERT_TRUE(common::isDirectory("test_cache/fuel.gazebosim.org")); + } public: std::shared_ptr tempDir; @@ -1167,7 +1172,7 @@ TEST_F(FuelClientTest, CachedWorld) // Cached world (no version) { - common::URI url{"http://localhost:8007/1.0/banana/worlds/My World"}; + common::URI url{"http://localhost:8007/1.0/banana/worlds/My World", true}; std::string path; auto result = client.CachedWorld(url, path); EXPECT_TRUE(result); @@ -1178,7 +1183,7 @@ TEST_F(FuelClientTest, CachedWorld) // Cached world (tip) { - common::URI url{"http://localhost:8007/1.0/banana/worlds/My World/tip"}; + common::URI url{"http://localhost:8007/1.0/banana/worlds/My World/tip", true}; std::string path; auto result = client.CachedWorld(url, path); EXPECT_TRUE(result); @@ -1189,7 +1194,7 @@ TEST_F(FuelClientTest, CachedWorld) // Cached world (version number) { - common::URI url{"http://localhost:8007/1.0/banana/worlds/My World/2"}; + common::URI url{"http://localhost:8007/1.0/banana/worlds/My World/2", true}; std::string path; auto result = client.CachedWorld(url, path); EXPECT_TRUE(result); @@ -1201,7 +1206,7 @@ TEST_F(FuelClientTest, CachedWorld) // Cached world file (tip) { common::URI url{"http://localhost:8007/1.0/banana/worlds/My World/tip/" - "files/strawberry.world"}; + "files/strawberry.world", true}; std::string path; auto result = client.CachedWorldFile(url, path); EXPECT_TRUE(result); diff --git a/src/LocalCache.cc b/src/LocalCache.cc index 9da08881..b6be379c 100644 --- a/src/LocalCache.cc +++ b/src/LocalCache.cc @@ -392,8 +392,9 @@ bool LocalCache::SaveModel( std::string cacheLocation = this->dataPtr->config->CacheLocation(); - std::string modelRootDir = common::joinPaths(cacheLocation, - uriToPath(_id.Server().Url()), _id.Owner(), "models", _id.Name()); + std::string modelRootDir = + common::joinPaths(cacheLocation, _id.UniqueName()); + std::string modelVersionedDir = common::joinPaths(modelRootDir, _id.VersionStr()); @@ -744,10 +745,13 @@ bool LocalCache::SaveWorld( return false; } - auto cacheLocation = this->dataPtr->config->CacheLocation(); + std::string cacheLocation = this->dataPtr->config->CacheLocation(); + + std::string worldRootDir = + common::joinPaths(cacheLocation, _id.UniqueName()); - auto worldRootDir = common::joinPaths(cacheLocation, _id.UniqueName()); - auto worldVersionedDir = common::joinPaths(worldRootDir, _id.VersionStr()); + std::string worldVersionedDir = + common::joinPaths(worldRootDir , _id.VersionStr()); // Is it already in the cache? if (common::isDirectory(worldVersionedDir) && !_overwrite) diff --git a/src/ModelIdentifier.cc b/src/ModelIdentifier.cc index 45df4b4d..c533bc75 100644 --- a/src/ModelIdentifier.cc +++ b/src/ModelIdentifier.cc @@ -149,7 +149,7 @@ ModelIdentifier::~ModelIdentifier() ////////////////////////////////////////////////// std::string ModelIdentifier::UniqueName() const { - return common::joinPaths(this->dataPtr->server.Url().Str(), + return common::joinPaths(uriToPath(this->dataPtr->server.Url()), this->dataPtr->owner, "models", this->dataPtr->name); } diff --git a/src/WorldIdentifier.cc b/src/WorldIdentifier.cc index 5f290ba0..03486b1f 100644 --- a/src/WorldIdentifier.cc +++ b/src/WorldIdentifier.cc @@ -80,7 +80,7 @@ WorldIdentifier::~WorldIdentifier() ////////////////////////////////////////////////// std::string WorldIdentifier::UniqueName() const { - return common::joinPaths(this->dataPtr->server.Url().Str(), + return common::joinPaths(uriToPath(this->dataPtr->server.Url()), this->dataPtr->owner, "worlds", this->dataPtr->name); From 91e6ccfe059035a0e2408a1dc2eb1322f32f78fc Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Tue, 26 Sep 2023 21:32:06 +0000 Subject: [PATCH 6/8] More Windows work Signed-off-by: Michael Carroll --- include/gz/fuel_tools/FuelClient.hh | 7 ++++ include/gz/fuel_tools/WorldIdentifier.hh | 1 + src/FuelClient.cc | 42 +++++++++++------------- src/FuelClient_TEST.cc | 3 ++ src/LocalCache.cc | 4 +++ src/LocalCache_TEST.cc | 30 ++++++++--------- src/ModelIdentifier.cc | 12 +++---- src/ModelIdentifier_TEST.cc | 20 +++++------ src/WorldIdentifier.cc | 13 ++++---- src/WorldIdentifier_TEST.cc | 17 ++++------ 10 files changed, 76 insertions(+), 73 deletions(-) diff --git a/include/gz/fuel_tools/FuelClient.hh b/include/gz/fuel_tools/FuelClient.hh index d148de47..703d3032 100644 --- a/include/gz/fuel_tools/FuelClient.hh +++ b/include/gz/fuel_tools/FuelClient.hh @@ -315,6 +315,13 @@ namespace gz const std::vector &_ids, size_t _jobs = 2); + /// \brief Check if a model is already present in the local cache. + /// \param[in] _id The model identifier + /// \param[out] _path Local path where the model can be found. + /// \return FETCH_ERROR if not cached, FETCH_ALREADY_EXISTS if cached. + public: Result CachedModel(const ModelIdentifier &_id, + std::string &_path); + /// \brief Check if a model is already present in the local cache. /// \param[in] _modelUrl The unique URL of the model on a Fuel server. /// E.g.: https://fuel.gazebosim.org/1.0/caguero/models/Beer diff --git a/include/gz/fuel_tools/WorldIdentifier.hh b/include/gz/fuel_tools/WorldIdentifier.hh index d4579248..00d6f45f 100644 --- a/include/gz/fuel_tools/WorldIdentifier.hh +++ b/include/gz/fuel_tools/WorldIdentifier.hh @@ -133,6 +133,7 @@ namespace gz /// \return Unique world name. public: std::string UniqueName() const; + // /// \brief Sets the SHA 2 256 hash of the world // /// \param[in] _hash a 256 bit SHA 2 hash // /// \returns true if successful diff --git a/src/FuelClient.cc b/src/FuelClient.cc index aa643eee..4e7b21c9 100644 --- a/src/FuelClient.cc +++ b/src/FuelClient.cc @@ -717,6 +717,7 @@ Result FuelClient::DownloadModel(const ModelIdentifier &_id, return Result(ResultType::FETCH_ERROR); } + std::cout << "Getting dependencies" << std::endl; return this->ModelDependencies(_id, _dependencies); } @@ -729,7 +730,8 @@ Result FuelClient::ModelDependencies(const ModelIdentifier &_id, // Locate any dependencies from the input model and download them. std::string path; gz::msgs::FuelMetadata meta; - if (this->CachedModel(gz::common::URI(_id.UniqueName()), path)) + + if (this->CachedModel(_id, path)) { std::string metadataPath = gz::common::joinPaths(path, "metadata.pbtxt"); @@ -1433,9 +1435,6 @@ Result FuelClient::DownloadModel(const common::URI &_modelUrl, if (!result) return result; - // TODO(anyone) We shouldn't need to reconstruct the path, SaveModel should - // be changed to return it - // We need to figure out the version for the tip if (id.Version() == 0 || id.VersionStr() == "tip") { @@ -1444,8 +1443,7 @@ Result FuelClient::DownloadModel(const common::URI &_modelUrl, } _path = gz::common::joinPaths(this->Config().CacheLocation(), - id.Server().Url().Path().Str(), id.Owner(), "models", id.Name(), - id.VersionStr()); + id.UniqueName(), id.VersionStr()); return result; } @@ -1472,15 +1470,23 @@ Result FuelClient::DownloadWorld(const common::URI &_worldUrl, } ////////////////////////////////////////////////// -bool FuelClient::CachedModel(const common::URI &_modelUrl) +Result FuelClient::CachedModel(const ModelIdentifier &_id, + std::string &_path) { - // Get data from URL - ModelIdentifier id; - if (!this->ParseModelUrl(_modelUrl, id)) - return Result(ResultType::FETCH_ERROR); + auto modelIter = this->dataPtr->cache->MatchingModel(_id); + if (modelIter) + { + _path = modelIter.PathToModel(); + return Result(ResultType::FETCH_ALREADY_EXISTS); + } + return Result(ResultType::FETCH_ERROR); +} - // Check local cache - return this->dataPtr->cache->MatchingModel(id) ? true : false; +////////////////////////////////////////////////// +bool FuelClient::CachedModel(const common::URI &_modelUrl) +{ + std::string path; + return this->CachedModel(_modelUrl, path).Type() != ResultType::FETCH_ERROR; } ////////////////////////////////////////////////// @@ -1494,15 +1500,7 @@ Result FuelClient::CachedModel(const common::URI &_modelUrl, return Result(ResultType::FETCH_ERROR); } - // Check local cache - auto modelIter = this->dataPtr->cache->MatchingModel(id); - if (modelIter) - { - _path = modelIter.PathToModel(); - return Result(ResultType::FETCH_ALREADY_EXISTS); - } - - return Result(ResultType::FETCH_ERROR); + return this->CachedModel(id, _path); } ////////////////////////////////////////////////// diff --git a/src/FuelClient_TEST.cc b/src/FuelClient_TEST.cc index 990d6b4a..21f2ca92 100644 --- a/src/FuelClient_TEST.cc +++ b/src/FuelClient_TEST.cc @@ -541,17 +541,20 @@ TEST_P(FuelClientDownloadTest, DownloadModel) EXPECT_FALSE(res2); EXPECT_EQ(ResultType::FETCH_ERROR, res2.Type()); + std::cout << "Download model" << std::endl; // Download std::string path; Result res3 = client.DownloadModel(url, path); EXPECT_TRUE(res3); EXPECT_EQ(ResultType::FETCH, res3.Type()); + std::cout << "Check cache for url " << std::endl; // Check it is cached Result res4 = client.CachedModel(url, cachedPath); EXPECT_TRUE(res4); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, res4.Type()); + std::cout << "Check cache for depurl " << std::endl; // Check the dependency is cached Result res5 = client.CachedModel(depUrl, cachedPath); EXPECT_TRUE(res5); diff --git a/src/LocalCache.cc b/src/LocalCache.cc index b6be379c..efc6acef 100644 --- a/src/LocalCache.cc +++ b/src/LocalCache.cc @@ -284,10 +284,14 @@ Model LocalCache::MatchingModel(const ModelIdentifier &_id) bool tip = (_id.Version() == 0); Model tipModel; + std::cout << "Searching for: " << _id.UniqueName() << std::endl; + for (ModelIter iter = this->AllModels(); iter; ++iter) { ModelIdentifier id = iter->Identification(); + std::cout << "Found: " << id.UniqueName() << std::endl; + if (_id == id) { if (_id.Version() == id.Version()) diff --git a/src/LocalCache_TEST.cc b/src/LocalCache_TEST.cc index 780d9242..52649e88 100644 --- a/src/LocalCache_TEST.cc +++ b/src/LocalCache_TEST.cc @@ -83,7 +83,7 @@ void createLocal6Models(ClientConfig &_conf) "trudy", "models", "tm2", "2", "model.config"))); gz::fuel_tools::ServerConfig srv; - srv.SetUrl(common::URI("http://localhost:8001/")); + srv.SetUrl(common::URI("http://localhost:8001/", true)); _conf.AddServer(srv); } @@ -118,7 +118,7 @@ void createLocal3Models(ClientConfig &_conf) "trudy", "models", "tm1", "3", "model.config"))); gz::fuel_tools::ServerConfig srv; - srv.SetUrl(gz::common::URI("http://localhost:8007/")); + srv.SetUrl(gz::common::URI("http://localhost:8007/", true)); _conf.AddServer(srv); } @@ -171,7 +171,7 @@ void createLocal6Worlds(ClientConfig &_conf) "trudy", "worlds", "tm2", "2", "world.world"))); gz::fuel_tools::ServerConfig srv; - srv.SetUrl(gz::common::URI("http://localhost:8001/")); + srv.SetUrl(gz::common::URI("http://localhost:8001/", true)); _conf.AddServer(srv); } @@ -206,7 +206,7 @@ void createLocal3Worlds(ClientConfig &_conf) "trudy", "worlds", "tm1", "3", "world.world"))); gz::fuel_tools::ServerConfig srv; - srv.SetUrl(common::URI("http://localhost:8007/")); + srv.SetUrl(common::URI("http://localhost:8007/", true)); _conf.AddServer(srv); } @@ -223,6 +223,10 @@ class LocalCacheTest : public ::testing::Test ASSERT_FALSE(common::exists("test_cache")); ASSERT_TRUE(common::createDirectories("test_cache")); ASSERT_TRUE(common::isDirectory("test_cache")); + + // This suppresses some unnecessary console spam. + common::createDirectories( + common::joinPaths("test_cache", "fuel.gazebosim.org")); } public: std::shared_ptr tempDir; @@ -230,7 +234,6 @@ class LocalCacheTest : public ::testing::Test ///////////////////////////////////////////////// /// \brief Iterate through all models in cache -// See https://github.com/gazebosim/gz-fuel-tools/issues/231 TEST_F(LocalCacheTest, AllModels) { ClientConfig conf; @@ -250,13 +253,12 @@ TEST_F(LocalCacheTest, AllModels) EXPECT_EQ(9u, uniqueNames.size()); EXPECT_NE(uniqueNames.end(), uniqueNames.find( - "http://localhost:8001/alice/models/am1")); + "localhost%3A8001/alice/models/am1")); } ///////////////////////////////////////////////// /// \brief Get all models that match some fields /// \brief Iterate through all models in cache -// See https://github.com/gazebosim/gz-fuel-tools/issues/307 TEST_F(LocalCacheTest, MatchingModels) { ClientConfig conf; @@ -300,7 +302,6 @@ TEST_F(LocalCacheTest, MatchingModels) ///////////////////////////////////////////////// /// \brief Get a specific model from cache /// \brief Iterate through all models in cache -// See https://github.com/gazebosim/gz-fuel-tools/issues/307 TEST_F(LocalCacheTest, MatchingModel) { ClientConfig conf; @@ -310,10 +311,10 @@ TEST_F(LocalCacheTest, MatchingModel) gz::fuel_tools::LocalCache cache(&conf); gz::fuel_tools::ServerConfig srv1; - srv1.SetUrl(common::URI("http://localhost:8001/")); + srv1.SetUrl(common::URI("http://localhost:8001/", true)); gz::fuel_tools::ServerConfig srv2; - srv2.SetUrl(common::URI("http://localhost:8002/")); + srv2.SetUrl(common::URI("http://localhost:8002/", true)); ModelIdentifier am1; am1.SetServer(srv1); @@ -354,7 +355,6 @@ TEST_F(LocalCacheTest, MatchingModel) ///////////////////////////////////////////////// /// \brief Iterate through all worlds in cache /// \brief Iterate through all models in cache -// See https://github.com/gazebosim/gz-fuel-tools/issues/307 TEST_F(LocalCacheTest, AllWorlds) { ClientConfig conf; @@ -373,13 +373,12 @@ TEST_F(LocalCacheTest, AllWorlds) } EXPECT_EQ(9u, uniqueNames.size()); EXPECT_NE(uniqueNames.end(), uniqueNames.find( - gz::common::joinPaths(sanitizeAuthority("localhost:8001"), "alice", "worlds", "am1"))); + sanitizeAuthority("localhost:8001") + "/alice/worlds/am1")); } ///////////////////////////////////////////////// /// \brief Get all worlds that match some fields /// \brief Iterate through all models in cache -// See https://github.com/gazebosim/gz-fuel-tools/issues/307 TEST_F(LocalCacheTest, MatchingWorlds) { ClientConfig conf; @@ -411,7 +410,6 @@ TEST_F(LocalCacheTest, MatchingWorlds) ///////////////////////////////////////////////// /// \brief Get a specific world from cache /// \brief Iterate through all models in cache -// See https://github.com/gazebosim/gz-fuel-tools/issues/307 TEST_F(LocalCacheTest, MatchingWorld) { ClientConfig conf; @@ -421,10 +419,10 @@ TEST_F(LocalCacheTest, MatchingWorld) gz::fuel_tools::LocalCache cache(&conf); gz::fuel_tools::ServerConfig srv1; - srv1.SetUrl(gz::common::URI("http://localhost:8001/")); + srv1.SetUrl(gz::common::URI("http://localhost:8001/", true)); gz::fuel_tools::ServerConfig srv2; - srv2.SetUrl(gz::common::URI("http://localhost:8002/")); + srv2.SetUrl(gz::common::URI("http://localhost:8002/", true)); WorldIdentifier am1; am1.SetServer(srv1); diff --git a/src/ModelIdentifier.cc b/src/ModelIdentifier.cc index c533bc75..211d8b87 100644 --- a/src/ModelIdentifier.cc +++ b/src/ModelIdentifier.cc @@ -21,6 +21,7 @@ #include #include +#include #include #include "gz/fuel_tools/ClientConfig.hh" @@ -142,16 +143,15 @@ bool ModelIdentifier::operator!=(const ModelIdentifier &_rhs) const } ////////////////////////////////////////////////// -ModelIdentifier::~ModelIdentifier() -{ -} +ModelIdentifier::~ModelIdentifier() = default; ////////////////////////////////////////////////// std::string ModelIdentifier::UniqueName() const { - return common::joinPaths(uriToPath(this->dataPtr->server.Url()), - this->dataPtr->owner, "models", - this->dataPtr->name); + return common::copyToUnixPath(common::joinPaths( + uriToPath(this->dataPtr->server.Url()), + this->dataPtr->owner, "models", + this->dataPtr->name)); } ////////////////////////////////////////////////// diff --git a/src/ModelIdentifier_TEST.cc b/src/ModelIdentifier_TEST.cc index 8e27299d..deabbcd3 100644 --- a/src/ModelIdentifier_TEST.cc +++ b/src/ModelIdentifier_TEST.cc @@ -56,32 +56,28 @@ TEST(ModelIdentifier, SetFields) ///////////////////////////////////////////////// /// \brief Unique Name -// See https://github.com/gazebosim/gz-fuel-tools/issues/231 -TEST(ModelIdentifier, GZ_UTILS_TEST_DISABLED_ON_WIN32(UniqueName)) +TEST(ModelIdentifier, UniqueName) { gz::fuel_tools::ServerConfig srv1; - srv1.SetUrl(common::URI("https://localhost:8001")); + srv1.SetUrl(common::URI("https://localhost:8001", true)); gz::fuel_tools::ServerConfig srv2; - srv2.SetUrl(common::URI("https://localhost:8002")); + srv2.SetUrl(common::URI("https://localhost:8002", true)); gz::fuel_tools::ServerConfig srv3; - srv3.SetUrl(common::URI("https://localhost:8003")); + srv3.SetUrl(common::URI("https://localhost:8003", true)); ModelIdentifier id; id.SetName("hello"); id.SetOwner("alice"); id.SetServer(srv1); - EXPECT_EQ(common::joinPaths("https://localhost:8001", "alice", "models", - "hello"), id.UniqueName()); + EXPECT_EQ("localhost%3A8001/alice/models/hello", id.UniqueName()); id.SetServer(srv2); - EXPECT_EQ(common::joinPaths("https://localhost:8002", "alice", "models", - "hello"), id.UniqueName()); + EXPECT_EQ("localhost%3A8002/alice/models/hello", id.UniqueName()); id.SetServer(srv3); - EXPECT_EQ(common::joinPaths("https://localhost:8003", "alice", "models", - "hello"), id.UniqueName()); + EXPECT_EQ("localhost%3A8003/alice/models/hello", id.UniqueName()); } ///////////////////////////////////////////////// @@ -156,7 +152,7 @@ TEST(ModelIdentifier, AsString) "Name: \n"\ "Owner: \n"\ "Version: tip\n"\ - "Unique name: https://fuel.gazebosim.org/models/\n" + "Unique name: fuel.gazebosim.org/models/\n" "Description: \n" "File size: 0\n" "Upload date: 0\n" diff --git a/src/WorldIdentifier.cc b/src/WorldIdentifier.cc index 03486b1f..ab2e9288 100644 --- a/src/WorldIdentifier.cc +++ b/src/WorldIdentifier.cc @@ -20,6 +20,7 @@ #include #include +#include #include #include "gz/fuel_tools/ClientConfig.hh" @@ -73,17 +74,15 @@ bool WorldIdentifier::operator==(const WorldIdentifier &_rhs) const } ////////////////////////////////////////////////// -WorldIdentifier::~WorldIdentifier() -{ -} +WorldIdentifier::~WorldIdentifier() = default; ////////////////////////////////////////////////// std::string WorldIdentifier::UniqueName() const { - return common::joinPaths(uriToPath(this->dataPtr->server.Url()), - this->dataPtr->owner, - "worlds", - this->dataPtr->name); + return common::copyToUnixPath(common::joinPaths( + uriToPath(this->dataPtr->server.Url()), + this->dataPtr->owner, "worlds", + this->dataPtr->name)); } ////////////////////////////////////////////////// diff --git a/src/WorldIdentifier_TEST.cc b/src/WorldIdentifier_TEST.cc index 947d8fd1..fc0b7698 100644 --- a/src/WorldIdentifier_TEST.cc +++ b/src/WorldIdentifier_TEST.cc @@ -44,29 +44,26 @@ TEST(WorldIdentifier, SetFields) TEST(WorldIdentifier, UniqueName) { gz::fuel_tools::ServerConfig srv1; - srv1.SetUrl(gz::common::URI("https://localhost:8001/")); + srv1.SetUrl(gz::common::URI("https://localhost:8001/", true)); gz::fuel_tools::ServerConfig srv2; - srv2.SetUrl(gz::common::URI("https://localhost:8002")); + srv2.SetUrl(gz::common::URI("https://localhost:8002", true)); gz::fuel_tools::ServerConfig srv3; - - srv3.SetUrl(gz::common::URI("https://localhost:8003/")); + srv3.SetUrl(gz::common::URI("https://localhost:8003/", true)); WorldIdentifier id; id.SetName("hello"); id.SetOwner("alice"); + id.SetServer(srv1); - EXPECT_EQ(common::joinPaths("localhost:8001", "alice", "worlds", "hello"), - id.UniqueName()); + EXPECT_EQ("localhost%3A8001/alice/worlds/hello", id.UniqueName()); id.SetServer(srv2); - EXPECT_EQ(common::joinPaths("localhost:8002", "alice", "worlds", "hello"), - id.UniqueName()); + EXPECT_EQ("localhost%3A8002/alice/worlds/hello", id.UniqueName()); id.SetServer(srv3); - EXPECT_EQ(common::joinPaths("localhost:8003", "alice", "worlds", "hello"), - id.UniqueName()); + EXPECT_EQ("localhost%3A8003/alice/worlds/hello", id.UniqueName()); } ///////////////////////////////////////////////// From b5e7312ac05c1f95c0666165cee7334dcebacbf0 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 27 Sep 2023 13:55:39 +0000 Subject: [PATCH 7/8] Remove windows-specific test Signed-off-by: Michael Carroll --- src/WorldIdentifier_TEST.cc | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/src/WorldIdentifier_TEST.cc b/src/WorldIdentifier_TEST.cc index fc0b7698..91c2d963 100644 --- a/src/WorldIdentifier_TEST.cc +++ b/src/WorldIdentifier_TEST.cc @@ -112,7 +112,6 @@ TEST(WorldIdentifier, AsString) common::Console::SetVerbosity(4); { WorldIdentifier id; -#ifndef _WIN32 std::string str = "Name: \n"\ "Owner: \n"\ @@ -123,18 +122,6 @@ TEST(WorldIdentifier, AsString) " URL: https://fuel.gazebosim.org\n" " Version: 1.0\n" " API key: \n"; -#else - std::string str = - "Name: \n"\ - "Owner: \n"\ - "Version: tip\n"\ - "Unique name: fuel.gazebosim.org\\worlds\\\n" - "Local path: \n" - "Server:\n" - " URL: https://fuel.gazebosim.org\n" - " Version: 1.0\n" - " API key: \n"; -#endif EXPECT_EQ(str, id.AsString()); } From 839deaee8250f248adb8ac02293c2b4e7b1a3f2d Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 27 Sep 2023 13:59:35 +0000 Subject: [PATCH 8/8] Minimize diff Signed-off-by: Michael Carroll --- include/gz/fuel_tools/Helpers.hh | 10 ++++++--- include/gz/fuel_tools/WorldIdentifier.hh | 1 - src/FuelClient.cc | 28 ++++++++++++------------ src/FuelClient_TEST.cc | 9 ++++---- src/Helpers.cc | 1 - src/LocalCache.cc | 22 +++++-------------- src/ModelIdentifier.cc | 4 +++- src/WorldIdentifier.cc | 4 +++- 8 files changed, 36 insertions(+), 43 deletions(-) diff --git a/include/gz/fuel_tools/Helpers.hh b/include/gz/fuel_tools/Helpers.hh index 1bcaf94c..96df74b9 100644 --- a/include/gz/fuel_tools/Helpers.hh +++ b/include/gz/fuel_tools/Helpers.hh @@ -35,7 +35,9 @@ #define gz_strdup strdup #endif -namespace gz::fuel_tools +namespace gz +{ +namespace fuel_tools { /// \brief Convert the authority portion of a URI to a string /// suitable to be used as a path on disk for all platforms. @@ -58,6 +60,8 @@ std::string sanitizeAuthority(const std::string &_uriAuthority); /// \return String suitable to use in file paths GZ_FUEL_TOOLS_VISIBLE std::string uriToPath(const gz::common::URI &_uri); -} // namespace gz::fuel_tools +} +} -#endif // GZ_FUEL_TOOLS_HELPERS_HH_ +// GZ_FUEL_TOOLS_HELPERS_HH_ +#endif diff --git a/include/gz/fuel_tools/WorldIdentifier.hh b/include/gz/fuel_tools/WorldIdentifier.hh index 00d6f45f..d4579248 100644 --- a/include/gz/fuel_tools/WorldIdentifier.hh +++ b/include/gz/fuel_tools/WorldIdentifier.hh @@ -133,7 +133,6 @@ namespace gz /// \return Unique world name. public: std::string UniqueName() const; - // /// \brief Sets the SHA 2 256 hash of the world // /// \param[in] _hash a 256 bit SHA 2 hash // /// \returns true if successful diff --git a/src/FuelClient.cc b/src/FuelClient.cc index 4e7b21c9..28e5bf47 100644 --- a/src/FuelClient.cc +++ b/src/FuelClient.cc @@ -251,20 +251,22 @@ FuelClient::FuelClient(const ClientConfig &_config, const Rest &_rest) this->dataPtr->cache = std::make_unique(&(this->dataPtr->config)); - this->dataPtr->urlModelRegex = - std::make_unique(this->dataPtr->kModelUrlRegexStr); - this->dataPtr->urlWorldRegex = - std::make_unique(this->dataPtr->kWorldUrlRegexStr); - this->dataPtr->urlModelFileRegex = - std::make_unique(this->dataPtr->kModelFileUrlRegexStr); - this->dataPtr->urlWorldFileRegex = - std::make_unique(this->dataPtr->kWorldFileUrlRegexStr); - this->dataPtr->urlCollectionRegex = - std::make_unique(this->dataPtr->kCollectionUrlRegexStr); + this->dataPtr->urlModelRegex.reset(new std::regex( + this->dataPtr->kModelUrlRegexStr)); + this->dataPtr->urlWorldRegex.reset(new std::regex( + this->dataPtr->kWorldUrlRegexStr)); + this->dataPtr->urlModelFileRegex.reset(new std::regex( + this->dataPtr->kModelFileUrlRegexStr)); + this->dataPtr->urlWorldFileRegex.reset(new std::regex( + this->dataPtr->kWorldFileUrlRegexStr)); + this->dataPtr->urlCollectionRegex.reset(new std::regex( + this->dataPtr->kCollectionUrlRegexStr)); } ////////////////////////////////////////////////// -FuelClient::~FuelClient() = default; +FuelClient::~FuelClient() +{ +} ////////////////////////////////////////////////// ClientConfig &FuelClient::Config() @@ -334,6 +336,7 @@ ModelIter FuelClient::Models(const ServerConfig &_server) const Result FuelClient::WorldDetails(const WorldIdentifier &_id, WorldIdentifier &_world) const { + return this->WorldDetails(_id, _world, {}); } @@ -713,11 +716,8 @@ Result FuelClient::DownloadModel(const ModelIdentifier &_id, // Save // Note that the save function doesn't return the path if (zipData.empty() || !this->dataPtr->cache->SaveModel(newId, zipData, true)) - { return Result(ResultType::FETCH_ERROR); - } - std::cout << "Getting dependencies" << std::endl; return this->ModelDependencies(_id, _dependencies); } diff --git a/src/FuelClient_TEST.cc b/src/FuelClient_TEST.cc index 21f2ca92..c7569f75 100644 --- a/src/FuelClient_TEST.cc +++ b/src/FuelClient_TEST.cc @@ -38,6 +38,8 @@ using namespace gz::fuel_tools; /// Taken from LocalCache_TEST void createLocalModel(ClientConfig &_conf) { + gzdbg << "Creating local model in [" << common::cwd() << "]" << std::endl; + auto modelPath = common::joinPaths( "test_cache", sanitizeAuthority("localhost:8007"), @@ -93,6 +95,8 @@ void createLocalModel(ClientConfig &_conf) /// Taken from LocalCache_TEST void createLocalWorld(ClientConfig &_conf) { + gzdbg << "Creating local world in [" << common::cwd() << "]" << std::endl; + auto worldPath = common::joinPaths( "test_cache", sanitizeAuthority("localhost:8007"), @@ -131,11 +135,9 @@ class FuelClientTest: public ::testing::Test ASSERT_FALSE(common::exists("test_cache")); ASSERT_TRUE(common::createDirectories("test_cache")); ASSERT_TRUE(common::isDirectory("test_cache")); - ASSERT_FALSE(common::exists("test_cache/fuel.gazebosim.org")); ASSERT_TRUE(common::createDirectories("test_cache/fuel.gazebosim.org")); ASSERT_TRUE(common::isDirectory("test_cache/fuel.gazebosim.org")); - } public: std::shared_ptr tempDir; @@ -541,20 +543,17 @@ TEST_P(FuelClientDownloadTest, DownloadModel) EXPECT_FALSE(res2); EXPECT_EQ(ResultType::FETCH_ERROR, res2.Type()); - std::cout << "Download model" << std::endl; // Download std::string path; Result res3 = client.DownloadModel(url, path); EXPECT_TRUE(res3); EXPECT_EQ(ResultType::FETCH, res3.Type()); - std::cout << "Check cache for url " << std::endl; // Check it is cached Result res4 = client.CachedModel(url, cachedPath); EXPECT_TRUE(res4); EXPECT_EQ(ResultType::FETCH_ALREADY_EXISTS, res4.Type()); - std::cout << "Check cache for depurl " << std::endl; // Check the dependency is cached Result res5 = client.CachedModel(depUrl, cachedPath); EXPECT_TRUE(res5); diff --git a/src/Helpers.cc b/src/Helpers.cc index eb01f5e8..e9be8d35 100644 --- a/src/Helpers.cc +++ b/src/Helpers.cc @@ -51,7 +51,6 @@ std::string gz::fuel_tools::uriToPath(const common::URI &_uri) } authority = sanitizeAuthority(authority); - if (authority.empty()) { return path; diff --git a/src/LocalCache.cc b/src/LocalCache.cc index efc6acef..481da466 100644 --- a/src/LocalCache.cc +++ b/src/LocalCache.cc @@ -232,13 +232,10 @@ ModelIter LocalCache::AllModels() { for (auto &server : this->dataPtr->config->Servers()) { - auto uri = server.Url(); - std::string path = common::joinPaths( this->dataPtr->config->CacheLocation(), uriToPath(server.Url())); auto srvModels = this->dataPtr->ModelsInServer(path); - for (auto &mod : srvModels) { mod.dataPtr->id.SetServer(server); @@ -284,14 +281,9 @@ Model LocalCache::MatchingModel(const ModelIdentifier &_id) bool tip = (_id.Version() == 0); Model tipModel; - std::cout << "Searching for: " << _id.UniqueName() << std::endl; - for (ModelIter iter = this->AllModels(); iter; ++iter) { ModelIdentifier id = iter->Identification(); - - std::cout << "Found: " << id.UniqueName() << std::endl; - if (_id == id) { if (_id.Version() == id.Version()) @@ -396,8 +388,8 @@ bool LocalCache::SaveModel( std::string cacheLocation = this->dataPtr->config->CacheLocation(); - std::string modelRootDir = - common::joinPaths(cacheLocation, _id.UniqueName()); + std::string modelRootDir = common::joinPaths(cacheLocation, + _id.UniqueName()); std::string modelVersionedDir = common::joinPaths(modelRootDir, _id.VersionStr()); @@ -749,13 +741,9 @@ bool LocalCache::SaveWorld( return false; } - std::string cacheLocation = this->dataPtr->config->CacheLocation(); - - std::string worldRootDir = - common::joinPaths(cacheLocation, _id.UniqueName()); - - std::string worldVersionedDir = - common::joinPaths(worldRootDir , _id.VersionStr()); + auto cacheLocation = this->dataPtr->config->CacheLocation(); + auto worldRootDir = common::joinPaths(cacheLocation, _id.UniqueName()); + auto worldVersionedDir = common::joinPaths(worldRootDir, _id.VersionStr()); // Is it already in the cache? if (common::isDirectory(worldVersionedDir) && !_overwrite) diff --git a/src/ModelIdentifier.cc b/src/ModelIdentifier.cc index 211d8b87..39c536e0 100644 --- a/src/ModelIdentifier.cc +++ b/src/ModelIdentifier.cc @@ -143,7 +143,9 @@ bool ModelIdentifier::operator!=(const ModelIdentifier &_rhs) const } ////////////////////////////////////////////////// -ModelIdentifier::~ModelIdentifier() = default; +ModelIdentifier::~ModelIdentifier() +{ +} ////////////////////////////////////////////////// std::string ModelIdentifier::UniqueName() const diff --git a/src/WorldIdentifier.cc b/src/WorldIdentifier.cc index ab2e9288..6af8c802 100644 --- a/src/WorldIdentifier.cc +++ b/src/WorldIdentifier.cc @@ -74,7 +74,9 @@ bool WorldIdentifier::operator==(const WorldIdentifier &_rhs) const } ////////////////////////////////////////////////// -WorldIdentifier::~WorldIdentifier() = default; +WorldIdentifier::~WorldIdentifier() +{ +} ////////////////////////////////////////////////// std::string WorldIdentifier::UniqueName() const