Skip to content

Commit

Permalink
Remove rcpputils::fs dependencies from rosbag2_storages (#1558)
Browse files Browse the repository at this point in the history
* Remove rcpputils::fs dependencies from rosbag2_storages

Original author: Kenta Yonekura <yoneken@ieee.org>

Signed-off-by: Roman Sokolkov <rsokolkov@gmail.com>

* Use path::generic_string() for Windows compatibility

Co-authored with Kenta Yonekura <yoneken@ieee.org>

Signed-off-by: Roman Sokolkov <rsokolkov@gmail.com>

* Fix linter errors in osbag2_storage_sqlite3

Signed-off-by: Roman Sokolkov <rsokolkov@gmail.com>

---------

Signed-off-by: Roman Sokolkov <rsokolkov@gmail.com>
Co-authored-by: Kenta Yonekura <yoneken@ieee.org>
(cherry picked from commit edda376)

# Conflicts:
#	rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp
#	rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp
#	rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp
  • Loading branch information
r7vme authored and mergify[bot] committed Feb 2, 2024
1 parent 7482089 commit eb4e65a
Show file tree
Hide file tree
Showing 10 changed files with 218 additions and 54 deletions.
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(yaml_cpp_vendor REQUIRED)

Expand All @@ -43,7 +42,6 @@ target_include_directories(${PROJECT_NAME}
)
target_link_libraries(${PROJECT_NAME}
pluginlib::pluginlib
rcpputils::rcpputils
rcutils::rcutils
yaml-cpp
)
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>yaml_cpp_vendor</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();

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
159 changes: 147 additions & 12 deletions rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,12 @@

#include "rclcpp/serialization.hpp"
#include "rclcpp/serialized_message.hpp"
<<<<<<< HEAD
#include "rcpputils/env.hpp"
#include "rcpputils/filesystem_helper.hpp"
=======
#include "rcutils/logging_macros.h"
>>>>>>> edda376 (Remove rcpputils::fs dependencies from rosbag2_storages (#1558))
#include "rosbag2_storage/storage_factory.hpp"
#ifdef ROSBAG2_STORAGE_MCAP_HAS_STORAGE_OPTIONS
#include "rosbag2_storage/storage_options.hpp"
Expand All @@ -27,12 +31,62 @@

#include <gmock/gmock.h>

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

using namespace ::testing; // NOLINT
using TemporaryDirectoryFixture = rosbag2_test_common::TemporaryDirectoryFixture;

<<<<<<< HEAD
=======
class McapStorageTestFixture : public rosbag2_test_common::TemporaryDirectoryFixture
{
public:
McapStorageTestFixture() = default;

std::shared_ptr<rcutils_uint8_array_t> make_serialized_message(const std::string & message)
{
rclcpp::Serialization<std_msgs::msg::String> serialization;

std_msgs::msg::String std_string_msg;
std_string_msg.data = message;
auto serialized_msg = std::make_shared<rclcpp::SerializedMessage>();
serialization.serialize_message(&std_string_msg, serialized_msg.get());

auto ret = std::make_shared<rcutils_uint8_array_t>();
*ret = serialized_msg->release_rcl_serialized_message();
return ret;
}

std::shared_ptr<rosbag2_storage::storage_interfaces::ReadWriteInterface> write_messages_to_mcap(
std::vector<std::tuple<std::string, int64_t, rosbag2_storage::TopicMetadata,
rosbag2_storage::MessageDefinition>> & messages,
std::shared_ptr<rosbag2_storage::storage_interfaces::ReadWriteInterface> rw_storage = nullptr)
{
if (nullptr == rw_storage) {
rosbag2_storage::StorageFactory factory;
rosbag2_storage::StorageOptions options;
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);
}

for (auto msg : messages) {
const rosbag2_storage::TopicMetadata & topic_metadata = std::get<2>(msg);
rw_storage->create_topic(topic_metadata, std::get<3>(msg));
auto bag_message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
bag_message->serialized_data = make_serialized_message(std::get<0>(msg));
bag_message->time_stamp = std::get<1>(msg);
bag_message->topic_name = topic_metadata.name;
rw_storage->write(bag_message);
}
return rw_storage;
}
};

>>>>>>> edda376 (Remove rcpputils::fs dependencies from rosbag2_storages (#1558))
namespace rosbag2_storage
{
bool operator==(const TopicInformation & lhs, const TopicInformation & rhs)
Expand All @@ -41,10 +95,87 @@ bool operator==(const TopicInformation & lhs, const TopicInformation & rhs)
}
} // namespace rosbag2_storage

<<<<<<< HEAD
=======
TEST_F(McapStorageTestFixture, can_store_and_read_metadata_correctly)
{
const std::string storage_id = "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", ""};

std::vector<std::string> string_messages = {"first message", "second message", "third message"};
std::vector<std::string> topics = {"topic1", "topic2"};

rosbag2_storage::TopicMetadata topic_metadata_1 = {
topics[0], "std_msgs/msg/String", "cdr", {rclcpp::QoS(1)}, "type_hash1"};
rosbag2_storage::TopicMetadata topic_metadata_2 = {
topics[1], "std_msgs/msg/String", "cdr", {rclcpp::QoS(2)}, "type_hash2"};

std::vector<std::tuple<std::string, int64_t, rosbag2_storage::TopicMetadata,
rosbag2_storage::MessageDefinition>>
messages = {
std::make_tuple(string_messages[0], static_cast<int64_t>(1e9), topic_metadata_1, definition),
std::make_tuple(string_messages[1], static_cast<int64_t>(2e9), topic_metadata_1, definition),
std::make_tuple(string_messages[2], static_cast<int64_t>(3e9), topic_metadata_2, definition),
};

rosbag2_storage::StorageFactory factory;
rosbag2_storage::StorageOptions options;
options.uri = uri;
options.storage_id = storage_id;

{
auto writer = factory.open_read_write(options);
writer->create_topic({"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {});
writer->create_topic({"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, {});
(void)write_messages_to_mcap(messages, writer);
auto metadata = writer->get_metadata();
metadata.ros_distro = "rolling";
metadata.custom_data["key1"] = "value1";
writer->update_metadata(metadata);
}

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.generic_string()}));

EXPECT_THAT(
metadata.topics_with_message_count,
UnorderedElementsAreArray({
rosbag2_storage::TopicInformation{
rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"},
1u},
rosbag2_storage::TopicInformation{
rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"},
2u},
}));
EXPECT_THAT(metadata.message_count, Eq(3u));

const auto current_distro = "rolling";
EXPECT_EQ(metadata.ros_distro, current_distro);

EXPECT_THAT(
metadata.starting_time,
Eq(std::chrono::time_point<std::chrono::high_resolution_clock>(std::chrono::seconds(1))));
EXPECT_THAT(metadata.duration, Eq(std::chrono::seconds(2)))
<< "metadata.duration=" << metadata.duration.count();

EXPECT_EQ(metadata.custom_data.size(), 1);
EXPECT_THAT(metadata.custom_data,
UnorderedElementsAreArray({std::pair<std::string, std::string>("key1", "value1")}));
}

>>>>>>> edda376 (Remove rcpputils::fs dependencies from rosbag2_storages (#1558))
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 @@ -70,11 +201,11 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
rosbag2_storage::StorageFactory factory;
#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 @@ -94,15 +225,19 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file)
writer->write(serialized_bag_msg);
EXPECT_TRUE(expected_bag.is_regular_file());
}
<<<<<<< HEAD
=======
EXPECT_TRUE(std::filesystem::is_regular_file(expected_bag));
>>>>>>> edda376 (Remove rcpputils::fs dependencies from rosbag2_storages (#1558))
{
rosbag2_storage::StorageFactory factory;
#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 @@ -113,7 +248,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{topic_name, "std_msgs/msg/String", "cdr",
Expand All @@ -138,8 +273,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 @@ -152,7 +287,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 @@ -181,11 +316,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,21 @@
#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"
<<<<<<< HEAD
#include "rcpputils/filesystem_helper.hpp"
=======
#include "rcpputils/scope_exit.hpp"
>>>>>>> edda376 (Remove rcpputils::fs dependencies from rosbag2_storages (#1558))

#include "rosbag2_storage/metadata_io.hpp"
#include "rosbag2_storage/serialized_bag_message.hpp"
Expand Down Expand Up @@ -192,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 @@ -401,9 +406,20 @@ void SqliteStorage::get_all_message_definitions(

uint64_t SqliteStorage::get_bagfile_size() const
{
<<<<<<< HEAD
const auto bag_path = rcpputils::fs::path{get_relative_file_path()};

return bag_path.exists() ? bag_path.file_size() : 0u;
=======
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 = 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_;
}
>>>>>>> edda376 (Remove rcpputils::fs dependencies from rosbag2_storages (#1558))
}

void SqliteStorage::initialize()
Expand Down
Loading

0 comments on commit eb4e65a

Please sign in to comment.