Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove rcpputils::fs dependencies from rosbag2_storages #1558

Merged
merged 3 commits into from
Feb 2, 2024
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 0 additions & 2 deletions rosbag2_storage/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -46,7 +45,6 @@ target_include_directories(${PROJECT_NAME}
)
target_link_libraries(${PROJECT_NAME}
pluginlib::pluginlib
rcpputils::rcpputils
rcutils::rcutils
rclcpp::rclcpp
rmw::rmw
Expand Down
1 change: 0 additions & 1 deletion rosbag2_storage/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>pluginlib</depend>
<depend>rcpputils</depend>
<depend>rcutils</depend>
<depend>rclcpp</depend>
<depend>rmw</depend>
Expand Down
7 changes: 3 additions & 4 deletions rosbag2_storage/src/rosbag2_storage/metadata_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,11 @@

#include "rosbag2_storage/metadata_io.hpp"

#include <filesystem>
#include <fstream>
#include <string>
#include <vector>

#include "rcpputils/filesystem_helper.hpp"

#include "rcutils/filesystem.h"

#include "rosbag2_storage/topic_metadata.hpp"
Expand Down Expand Up @@ -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();
MichaelOrlov marked this conversation as resolved.
Show resolved Hide resolved

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)
Expand Down
1 change: 0 additions & 1 deletion rosbag2_storage_mcap/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down
1 change: 0 additions & 1 deletion rosbag2_storage_mcap/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>rcpputils</test_depend>
<test_depend>rosbag2_test_common</test_depend>
<test_depend>std_msgs</test_depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -25,6 +24,7 @@

#include <gmock/gmock.h>

#include <filesystem>
#include <memory>
#include <string>

Expand Down Expand Up @@ -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);
}
Expand Down Expand Up @@ -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", ""};

Expand Down Expand Up @@ -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,
Expand Down Expand Up @@ -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";
Expand All @@ -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);

Expand All @@ -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();

Expand All @@ -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{
Expand All @@ -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";
Expand All @@ -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;
Expand Down Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,16 +19,16 @@
#include <atomic>
#include <chrono>
#include <cstring>
#include <iostream>
#include <filesystem>
#include <fstream>
#include <iostream>
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

#include "rcpputils/env.hpp"
#include "rcpputils/filesystem_helper.hpp"
#include "rcpputils/scope_exit.hpp"

#include "rosbag2_storage/metadata_io.hpp"
Expand Down Expand Up @@ -197,15 +197,15 @@ 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!");
}
} else { // APPEND and READ_ONLY
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!");
}
Expand Down Expand Up @@ -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_;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <cstdio>
#include <cstring>
#include <iostream>
#include <filesystem>
#include <fstream>
#include <memory>
#include <string>
Expand All @@ -28,8 +29,6 @@
#include <vector>
#include <unordered_map>

#include "rcpputils/filesystem_helper.hpp"

#include "rcutils/logging_macros.h"
#include "rcutils/snprintf.h"

Expand Down Expand Up @@ -99,7 +98,7 @@ class StorageTestFixture : public TemporaryDirectoryFixture
if (nullptr == writable_storage) {
writable_storage = std::make_shared<rosbag2_storage_plugins::SqliteStorage>();

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_});
}
Expand Down Expand Up @@ -128,11 +127,11 @@ class StorageTestFixture : public TemporaryDirectoryFixture
std::tuple<std::string, int64_t, std::string, std::string, std::string>
> & 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!");
}
Expand Down Expand Up @@ -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!");
}
Expand Down Expand Up @@ -251,7 +250,7 @@ class StorageTestFixture : public TemporaryDirectoryFixture
std::unique_ptr<rosbag2_storage::storage_interfaces::ReadOnlyInterface> readable_storage =
std::make_unique<rosbag2_storage_plugins::SqliteStorage>();

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_},
Expand All @@ -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);
Expand Down
Loading