From edda3769ffe0986d75cabe4464597a516f7aa969 Mon Sep 17 00:00:00 2001 From: Roman Date: Fri, 2 Feb 2024 21:29:02 +0300 Subject: [PATCH] Remove rcpputils::fs dependencies from rosbag2_storages (#1558) * Remove rcpputils::fs dependencies from rosbag2_storages Original author: Kenta Yonekura Signed-off-by: Roman Sokolkov * Use path::generic_string() for Windows compatibility Co-authored with Kenta Yonekura Signed-off-by: Roman Sokolkov * Fix linter errors in osbag2_storage_sqlite3 Signed-off-by: Roman Sokolkov --------- Signed-off-by: Roman Sokolkov Co-authored-by: Kenta Yonekura --- rosbag2_storage/CMakeLists.txt | 2 - rosbag2_storage/package.xml | 1 - .../src/rosbag2_storage/metadata_io.cpp | 7 ++- rosbag2_storage_mcap/CMakeLists.txt | 1 - rosbag2_storage_mcap/package.xml | 1 - .../test_mcap_storage.cpp | 40 ++++++++-------- .../sqlite_storage.cpp | 12 ++--- .../storage_test_fixture.hpp | 21 ++++----- .../test_sqlite_storage.cpp | 47 +++++++++++-------- .../test_sqlite_wrapper.cpp | 5 +- 10 files changed, 68 insertions(+), 69 deletions(-) diff --git a/rosbag2_storage/CMakeLists.txt b/rosbag2_storage/CMakeLists.txt index 38ff4a22f4..84070f5465 100644 --- a/rosbag2_storage/CMakeLists.txt +++ b/rosbag2_storage/CMakeLists.txt @@ -23,7 +23,6 @@ endif() find_package(ament_cmake REQUIRED) find_package(pluginlib REQUIRED) -find_package(rcpputils REQUIRED) find_package(rcutils REQUIRED) find_package(rclcpp REQUIRED) find_package(rmw REQUIRED) @@ -46,7 +45,6 @@ target_include_directories(${PROJECT_NAME} ) target_link_libraries(${PROJECT_NAME} pluginlib::pluginlib - rcpputils::rcpputils rcutils::rcutils rclcpp::rclcpp rmw::rmw diff --git a/rosbag2_storage/package.xml b/rosbag2_storage/package.xml index 3d5889074d..dfaa5f2235 100644 --- a/rosbag2_storage/package.xml +++ b/rosbag2_storage/package.xml @@ -13,7 +13,6 @@ ament_cmake pluginlib - rcpputils rcutils rclcpp rmw diff --git a/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp b/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp index 763901e8ab..5dae0a85b7 100644 --- a/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp +++ b/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp @@ -14,12 +14,11 @@ #include "rosbag2_storage/metadata_io.hpp" +#include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rcutils/filesystem.h" #include "rosbag2_storage/topic_metadata.hpp" @@ -56,14 +55,14 @@ BagMetadata MetadataIo::read_metadata(const std::string & uri) std::string MetadataIo::get_metadata_file_name(const std::string & uri) { - std::string metadata_file = (rcpputils::fs::path(uri) / metadata_filename).string(); + std::string metadata_file = (std::filesystem::path(uri) / metadata_filename).generic_string(); return metadata_file; } bool MetadataIo::metadata_file_exists(const std::string & uri) { - return rcpputils::fs::exists(rcpputils::fs::path(get_metadata_file_name(uri))); + return std::filesystem::exists(std::filesystem::path(get_metadata_file_name(uri))); } std::string MetadataIo::serialize_metadata(const BagMetadata & metadata) diff --git a/rosbag2_storage_mcap/CMakeLists.txt b/rosbag2_storage_mcap/CMakeLists.txt index 4edde5df30..5a5a057702 100644 --- a/rosbag2_storage_mcap/CMakeLists.txt +++ b/rosbag2_storage_mcap/CMakeLists.txt @@ -90,7 +90,6 @@ install( if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) find_package(ament_lint_auto REQUIRED) - find_package(rcpputils REQUIRED) find_package(rosbag2_test_common REQUIRED) find_package(std_msgs REQUIRED) diff --git a/rosbag2_storage_mcap/package.xml b/rosbag2_storage_mcap/package.xml index 8a0f59cfd2..0a18868622 100644 --- a/rosbag2_storage_mcap/package.xml +++ b/rosbag2_storage_mcap/package.xml @@ -22,7 +22,6 @@ ament_cmake_gmock ament_lint_auto ament_lint_common - rcpputils rosbag2_test_common std_msgs diff --git a/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp b/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp index 4daba43f2b..719546d887 100644 --- a/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp +++ b/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp @@ -14,7 +14,6 @@ #include "rclcpp/serialization.hpp" #include "rclcpp/serialized_message.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rcutils/logging_macros.h" #include "rosbag2_storage/storage_factory.hpp" #ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS @@ -25,6 +24,7 @@ #include +#include #include #include @@ -58,8 +58,8 @@ class McapStorageTestFixture : public rosbag2_test_common::TemporaryDirectoryFix if (nullptr == rw_storage) { rosbag2_storage::StorageFactory factory; rosbag2_storage::StorageOptions options; - auto uri = rcpputils::fs::path(temporary_dir_path_) / "bag"; - options.uri = uri.string(); + auto uri = std::filesystem::path(temporary_dir_path_) / "bag"; + options.uri = uri.generic_string(); options.storage_id = "mcap"; rw_storage = factory.open_read_write(options); } @@ -88,8 +88,8 @@ bool operator==(const TopicInformation & lhs, const TopicInformation & rhs) TEST_F(McapStorageTestFixture, can_store_and_read_metadata_correctly) { const std::string storage_id = "mcap"; - auto uri = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); - auto expected_bag = rcpputils::fs::path(temporary_dir_path_) / "rosbag.mcap"; + auto uri = (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); + auto expected_bag = std::filesystem::path(temporary_dir_path_) / "rosbag.mcap"; const rosbag2_storage::MessageDefinition definition = {"std_msgs/msg/String", "ros2msg", "string data", ""}; @@ -125,13 +125,13 @@ TEST_F(McapStorageTestFixture, can_store_and_read_metadata_correctly) writer->update_metadata(metadata); } - options.uri = expected_bag.string(); + options.uri = expected_bag.generic_string(); options.storage_id = storage_id; auto reader = factory.open_read_only(options); const auto metadata = reader->get_metadata(); EXPECT_THAT(metadata.storage_identifier, Eq("mcap")); - EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({expected_bag.string()})); + EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({expected_bag.generic_string()})); EXPECT_THAT( metadata.topics_with_message_count, @@ -161,8 +161,8 @@ TEST_F(McapStorageTestFixture, can_store_and_read_metadata_correctly) TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file) { - auto uri = rcpputils::fs::path(temporary_dir_path_) / "bag"; - auto expected_bag = rcpputils::fs::path(temporary_dir_path_) / "bag.mcap"; + auto uri = std::filesystem::path(temporary_dir_path_) / "bag"; + auto expected_bag = std::filesystem::path(temporary_dir_path_) / "bag.mcap"; const int64_t timestamp_nanos = 100; // arbitrary value rcutils_time_point_value_t time_stamp{timestamp_nanos}; const std::string topic_name = "test_topic"; @@ -188,11 +188,11 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file) #ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS rosbag2_storage::StorageOptions options; - options.uri = uri.string(); + options.uri = uri.generic_string(); options.storage_id = storage_id; auto writer = factory.open_read_write(options); #else - auto writer = factory.open_read_write(uri.string(), storage_id); + auto writer = factory.open_read_write(uri.generic_string(), storage_id); #endif writer->create_topic(topic_metadata, definition); @@ -211,15 +211,15 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file) serialized_bag_msg->topic_name = topic_name; writer->write(serialized_bag_msg); } - EXPECT_TRUE(expected_bag.is_regular_file()); + EXPECT_TRUE(std::filesystem::is_regular_file(expected_bag)); { #ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS rosbag2_storage::StorageOptions options; - options.uri = expected_bag.string(); + options.uri = expected_bag.generic_string(); options.storage_id = storage_id; auto reader = factory.open_read_only(options); #else - auto reader = factory.open_read_only(expected_bag.string(), storage_id); + auto reader = factory.open_read_only(expected_bag.generic_string(), storage_id); #endif auto topics_and_types = reader->get_all_topics_and_types(); @@ -230,7 +230,7 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file) const auto metadata = reader->get_metadata(); EXPECT_THAT(metadata.storage_identifier, Eq("mcap")); - EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({expected_bag.string()})); + EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({expected_bag.generic_string()})); EXPECT_THAT(metadata.topics_with_message_count, ElementsAreArray({rosbag2_storage::TopicInformation{ rosbag2_storage::TopicMetadata{ @@ -255,8 +255,8 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file) // This test disabled on Foxy since StorageOptions doesn't have storage_config_uri field on it TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml) { - auto uri = rcpputils::fs::path(temporary_dir_path_) / "bag"; - auto expected_bag = rcpputils::fs::path(temporary_dir_path_) / "bag.mcap"; + auto uri = std::filesystem::path(temporary_dir_path_) / "bag"; + auto expected_bag = std::filesystem::path(temporary_dir_path_) / "bag.mcap"; const int64_t timestamp_nanos = 100; // arbitrary value rcutils_time_point_value_t time_stamp{timestamp_nanos}; const std::string topic_name = "test_topic"; @@ -269,7 +269,7 @@ TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml) { rosbag2_storage::StorageOptions options; - options.uri = uri.string(); + options.uri = uri.generic_string(); options.storage_id = storage_id; options.storage_config_uri = config_path + "/mcap_writer_options_zstd.yaml"; rosbag2_storage::TopicMetadata topic_metadata; @@ -298,11 +298,11 @@ TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml) serialized_bag_msg->topic_name = topic_name; writer->write(serialized_bag_msg); writer->write(serialized_bag_msg); - EXPECT_TRUE(expected_bag.is_regular_file()); + EXPECT_TRUE(std::filesystem::is_regular_file(expected_bag)); } { rosbag2_storage::StorageOptions options; - options.uri = expected_bag.string(); + options.uri = expected_bag.generic_string(); options.storage_id = storage_id; rosbag2_storage::StorageFactory factory; diff --git a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp index 998d248cd5..bf8d012084 100644 --- a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp +++ b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp @@ -19,8 +19,9 @@ #include #include #include -#include +#include #include +#include #include #include #include @@ -28,7 +29,6 @@ #include #include "rcpputils/env.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rcpputils/scope_exit.hpp" #include "rosbag2_storage/metadata_io.hpp" @@ -197,7 +197,7 @@ void SqliteStorage::open( relative_path_ = storage_options.uri + FILE_EXTENSION; // READ_WRITE requires the DB to not exist. - if (rcpputils::fs::path(relative_path_).exists()) { + if (std::filesystem::exists(std::filesystem::path(relative_path_))) { throw std::runtime_error( "Failed to create bag: File '" + relative_path_ + "' already exists!"); } @@ -205,7 +205,7 @@ void SqliteStorage::open( relative_path_ = storage_options.uri; // APPEND and READ_ONLY require the DB to exist - if (!rcpputils::fs::path(relative_path_).exists()) { + if (!std::filesystem::exists(std::filesystem::path(relative_path_))) { throw std::runtime_error( "Failed to read from bag: File '" + relative_path_ + "' does not exist!"); } @@ -423,8 +423,8 @@ uint64_t SqliteStorage::get_bagfile_size() const if (!database_ || !page_count_statement_) { // Trying to call get_bagfile_size when SqliteStorage::open was not called or db // failed to open. Fallback to the filesystem call. - const auto bag_path = rcpputils::fs::path{get_relative_file_path()}; - return bag_path.exists() ? bag_path.file_size() : 0u; + const auto bag_path = std::filesystem::path{get_relative_file_path()}; + return std::filesystem::exists(bag_path) ? std::filesystem::file_size(bag_path) : 0u; } else { return db_file_size_; } diff --git a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp index 5c99f9e9b2..aacd3d8b26 100644 --- a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp +++ b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include #include @@ -28,8 +29,6 @@ #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rcutils/logging_macros.h" #include "rcutils/snprintf.h" @@ -99,7 +98,7 @@ class StorageTestFixture : public TemporaryDirectoryFixture if (nullptr == writable_storage) { writable_storage = std::make_shared(); - auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + auto db_file = (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({db_file, plugin_id_}); } @@ -128,11 +127,11 @@ class StorageTestFixture : public TemporaryDirectoryFixture std::tuple > & messages) { - auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + auto db_file = (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); std::string relative_path = db_file + ".db3"; // READ_WRITE requires the DB to not exist. - if (rcpputils::fs::path(relative_path).exists()) { + if (std::filesystem::exists(std::filesystem::path(relative_path))) { throw std::runtime_error( "Failed to create bag: File '" + relative_path + "' already exists!"); } @@ -203,11 +202,11 @@ class StorageTestFixture : public TemporaryDirectoryFixture void create_new_db3_file_with_schema_version_2() { - auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + auto db_file = (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); std::string relative_path = db_file + ".db3"; // READ_WRITE requires the DB to not exist. - if (rcpputils::fs::path(relative_path).exists()) { + if (std::filesystem::exists(std::filesystem::path(relative_path))) { throw std::runtime_error( "Failed to create bag: File '" + relative_path + "' already exists!"); } @@ -251,7 +250,7 @@ class StorageTestFixture : public TemporaryDirectoryFixture std::unique_ptr readable_storage = std::make_unique(); - auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + auto db_file = (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open( {db_file, plugin_id_}, @@ -269,9 +268,9 @@ class StorageTestFixture : public TemporaryDirectoryFixture const std::string & config_yaml, const std::string & plugin_id) { - auto temp_dir = rcpputils::fs::path(temporary_dir_path_); - const auto storage_uri = (temp_dir / "rosbag").string(); - const auto yaml_config = (temp_dir / "sqlite_config.yaml").string(); + auto temp_dir = std::filesystem::path(temporary_dir_path_); + const auto storage_uri = (temp_dir / "rosbag").generic_string(); + const auto yaml_config = (temp_dir / "sqlite_config.yaml").generic_string(); { // populate temporary config file std::ofstream out(yaml_config); diff --git a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp index 9070d85bae..75fff7b304 100644 --- a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp +++ b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp @@ -15,6 +15,7 @@ #include #include +#include #include #include #include @@ -24,8 +25,6 @@ #include "rcpputils/env.hpp" -#include "rcpputils/filesystem_helper.hpp" - #include "rcutils/snprintf.h" #include "rosbag2_storage/storage_filter.hpp" @@ -87,7 +86,7 @@ TEST_F(StorageTestFixture, has_next_return_false_if_there_are_no_more_messages) std::unique_ptr readable_storage = std::make_unique(); - auto db_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + auto db_filename = (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open({db_filename, kPluginID}); EXPECT_TRUE(readable_storage->has_next()); @@ -107,7 +106,7 @@ TEST_F(StorageTestFixture, get_next_returns_messages_in_timestamp_order) { std::unique_ptr readable_storage = std::make_unique(); - auto db_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + auto db_filename = (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open({db_filename, kPluginID}); EXPECT_TRUE(readable_storage->has_next()); @@ -130,7 +129,7 @@ TEST_F(StorageTestFixture, read_next_returns_filtered_messages) { std::unique_ptr readable_storage = std::make_unique(); - auto db_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + auto db_filename = (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open({db_filename, kPluginID}); rosbag2_storage::StorageFilter storage_filter; @@ -171,7 +170,8 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector) std::make_unique(); // extension is omitted since storage is being created; io_flag = READ_WRITE - const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + const auto read_write_filename = + (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({read_write_filename, kPluginID}); writable_storage->create_topic({"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {}); @@ -202,7 +202,8 @@ TEST_F(StorageTestFixture, get_all_message_definitions_returns_the_correct_vecto std::make_unique(); // extension is omitted since storage is being created; io_flag = READ_WRITE - const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + const auto read_write_filename = + (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({read_write_filename, kPluginID}); writable_storage->create_topic( @@ -236,7 +237,8 @@ TEST_F(StorageTestFixture, get_all_message_definitions_returns_the_correct_vecto TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) { auto writable_storage = std::make_shared(); - auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + auto read_write_filename = + (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({read_write_filename, kPluginID}); writable_storage->create_topic({"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {}); writable_storage->create_topic({"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, {}); @@ -254,7 +256,8 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) { write_messages_to_sqlite(messages, writable_storage); const auto readable_storage = std::make_unique(); - const auto db_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + const auto db_filename = + (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open( {db_filename, kPluginID}, @@ -293,7 +296,8 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct_for_prefoxy_db_sc write_messages_to_sqlite_in_pre_foxy_format(messages); const auto readable_storage = std::make_unique(); - const auto db_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + const auto db_filename = + (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open( {db_filename, kPluginID}, @@ -344,7 +348,7 @@ TEST_F(StorageTestFixture, get_db_schema_version_returns_correct_value) { auto writable_storage = std::make_shared(); EXPECT_EQ(writable_storage->get_db_schema_version(), -1); - auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + auto db_file = (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({db_file, plugin_id_}); EXPECT_GE(writable_storage->get_db_schema_version(), 3); @@ -352,7 +356,7 @@ TEST_F(StorageTestFixture, get_db_schema_version_returns_correct_value) { TEST_F(StorageTestFixture, metadata_ros_distro_returns_correct_value) { auto writable_storage = std::make_shared(); - auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + auto db_file = (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({db_file, plugin_id_}); std::string current_ros_distro = rcpputils::get_env_var("ROS_DISTRO"); @@ -366,7 +370,7 @@ TEST_F(StorageTestFixture, check_backward_compatibility_with_schema_version_2) { EXPECT_EQ(readable_storage->get_db_schema_version(), -1); - auto db_file = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + auto db_file = (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open( {db_file, plugin_id_}, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); @@ -379,7 +383,8 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct_if_no_messages) { write_messages_to_sqlite({}); const auto readable_storage = std::make_unique(); - const auto db_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + const auto db_filename = + (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open( {db_filename, kPluginID}, @@ -402,7 +407,8 @@ TEST_F(StorageTestFixture, remove_topics_and_types_returns_the_empty_vector) { std::make_unique(); // extension is omitted since storage is created; io_flag = READ_WRITE - const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + const auto read_write_filename = + (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({read_write_filename, kPluginID}); writable_storage->create_topic({"topic1", "type1", "rmw1", {}, "hash"}, {}); @@ -433,7 +439,8 @@ TEST_F(StorageTestFixture, get_relative_file_path_returns_db_name_with_ext) { // check that storage::get_relative_file_path returns the relative path to the sqlite3 db // and that uri is handled properly when storage::open is called with different io_flags // READ_WRITE expects uri to not end in extension - const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); + const auto read_write_filename = + (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); const auto storage_filename = read_write_filename + ".db3"; const auto read_write_storage = std::make_unique(); read_write_storage->open( @@ -493,8 +500,8 @@ TEST_F(StorageTestFixture, storage_preset_profile_applies_over_defaults) { // Check that "resilient" values override default optimized ones const auto writable_storage = std::make_unique(); - auto temp_dir = rcpputils::fs::path(temporary_dir_path_); - const auto storage_uri = (temp_dir / "rosbag").string(); + auto temp_dir = std::filesystem::path(temporary_dir_path_); + const auto storage_uri = (temp_dir / "rosbag").generic_string(); rosbag2_storage::StorageOptions options{storage_uri, kPluginID, 0, 0, 0, {}, ""}; options.storage_preset_profile = "resilient"; @@ -562,7 +569,7 @@ TEST_F(StorageTestFixture, read_next_returns_filtered_messages_regex) { std::unique_ptr readable_storage = std::make_unique(); - auto db_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + auto db_filename = (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open({db_filename, kPluginID}); rosbag2_storage::StorageFilter storage_filter; @@ -608,7 +615,7 @@ TEST_F(StorageTestFixture, read_next_returns_filtered_messages_topics_regex_to_e std::unique_ptr readable_storage = std::make_unique(); - auto db_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag.db3").string(); + auto db_filename = (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); readable_storage->open({db_filename, kPluginID}); rosbag2_storage::StorageFilter storage_filter; diff --git a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_wrapper.cpp b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_wrapper.cpp index 12b32c0481..4f0e58bfe8 100644 --- a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_wrapper.cpp +++ b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_wrapper.cpp @@ -14,12 +14,11 @@ #include +#include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rcutils/types.h" #include "rosbag2_storage_sqlite3/sqlite_wrapper.hpp" @@ -34,7 +33,7 @@ class SqliteWrapperTestFixture : public StorageTestFixture SqliteWrapperTestFixture() : StorageTestFixture(), db_( - (rcpputils::fs::path(temporary_dir_path_) / "test.db3").string(), + (std::filesystem::path(temporary_dir_path_) / "test.db3").generic_string(), rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE) {}