diff --git a/rosbag2_storage_mcap/src/mcap_storage.cpp b/rosbag2_storage_mcap/src/mcap_storage.cpp index cbade144c..ce9f7c9c3 100644 --- a/rosbag2_storage_mcap/src/mcap_storage.cpp +++ b/rosbag2_storage_mcap/src/mcap_storage.cpp @@ -42,6 +42,7 @@ #include #include +#include #include #include #include @@ -316,6 +317,7 @@ MCAPStorage::~MCAPStorage() } if (mcap_writer_) { mcap_writer_->close(); + std::filesystem::rename(relative_path_ + ".active", relative_path_); } } @@ -400,7 +402,7 @@ void MCAPStorage::open_impl(const std::string & uri, const std::string & preset_ YAML::convert::decode(yaml_node, options); } - auto status = mcap_writer_->open(relative_path_, options); + auto status = mcap_writer_->open(relative_path_ + ".active", options); if (!status.ok()) { throw std::runtime_error(status.message); } 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 03d886a6a..c8d103511 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 @@ -257,7 +257,6 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file) TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml) { 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,6 +268,7 @@ TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml) rclcpp::Serialization serialization; { + auto expected_bag = std::filesystem::path(temporary_dir_path_) / "bag.mcap.active"; rosbag2_storage::StorageOptions options; options.uri = uri.generic_string(); options.storage_id = storage_id; @@ -302,6 +302,7 @@ TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml) EXPECT_TRUE(std::filesystem::is_regular_file(expected_bag)); } { + auto expected_bag = std::filesystem::path(temporary_dir_path_) / "bag.mcap"; rosbag2_storage::StorageOptions options; options.uri = expected_bag.generic_string(); options.storage_id = storage_id; 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 4ce1e98c4..2f211106a 100644 --- a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp +++ b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp @@ -157,6 +157,9 @@ SqliteStorage::~SqliteStorage() if (active_transaction_) { commit_transaction(); } + if (is_read_write(storage_mode_) && database_) { + std::filesystem::rename(relative_path_ + ".active", relative_path_); + } } SqliteStorage::PresetProfile SqliteStorage::parse_preset_profile(const std::string & profile_string) @@ -210,9 +213,10 @@ void SqliteStorage::open( "Failed to read from bag: File '" + relative_path_ + "' does not exist!"); } } + std::string path = is_read_write(io_flag) ? (relative_path_ + ".active") : relative_path_; try { - database_ = std::make_unique(relative_path_, io_flag, std::move(pragmas)); + database_ = std::make_unique(path, io_flag, std::move(pragmas)); } catch (const SqliteException & e) { throw std::runtime_error("Failed to setup storage. Error: " + std::string(e.what())); } 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 371a798d1..8e79ba3ed 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 @@ -261,7 +261,7 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) { const auto readable_storage = std::make_unique(); const auto db_filename = - (std::filesystem::path(temporary_dir_path_) / "rosbag.db3").generic_string(); + (std::filesystem::path(temporary_dir_path_) / "rosbag.db3.active").generic_string(); readable_storage->open( {db_filename, kPluginID}, @@ -447,26 +447,32 @@ TEST_F(StorageTestFixture, get_relative_file_path_returns_db_name_with_ext) { 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( - {read_write_filename, kPluginID}, - rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE); - EXPECT_EQ(read_write_storage->get_relative_file_path(), storage_filename); - - // READ_ONLY expects uri to be the relative file path to the sqlite3 db. - const auto & read_only_filename = storage_filename; - const auto read_only_storage = std::make_unique(); - read_only_storage->open( - {read_only_filename, kPluginID}, - rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); - EXPECT_EQ(read_only_storage->get_relative_file_path(), storage_filename); - - const auto & append_filename = storage_filename; - const auto append_storage = std::make_unique(); - append_storage->open( - {append_filename, kPluginID}, - rosbag2_storage::storage_interfaces::IOFlag::APPEND); - EXPECT_EQ(append_storage->get_relative_file_path(), storage_filename); + { + const auto read_write_storage = std::make_unique(); + read_write_storage->open( + {read_write_filename, kPluginID}, + rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE); + EXPECT_EQ(read_write_storage->get_relative_file_path(), storage_filename); + } + + { + // READ_ONLY expects uri to be the relative file path to the sqlite3 db. + const auto & read_only_filename = storage_filename; + const auto read_only_storage = std::make_unique(); + read_only_storage->open( + {read_only_filename, kPluginID}, + rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); + EXPECT_EQ(read_only_storage->get_relative_file_path(), storage_filename); + } + + { + const auto & append_filename = storage_filename; + const auto append_storage = std::make_unique(); + append_storage->open( + {append_filename, kPluginID}, + rosbag2_storage::storage_interfaces::IOFlag::APPEND); + EXPECT_EQ(append_storage->get_relative_file_path(), storage_filename); + } } TEST_F(StorageTestFixture, loads_config_file) { diff --git a/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp b/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp index 9a44487f7..ed805bbe4 100644 --- a/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp +++ b/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp @@ -131,7 +131,8 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture void wait_for_storage_file(std::chrono::duration timeout = std::chrono::seconds(10)) { - const auto storage_path = get_bag_file_path(0); + auto storage_path = get_bag_file_path(0); + storage_path += ".active"; const auto start_time = std::chrono::steady_clock::now(); while (std::chrono::steady_clock::now() - start_time < timeout && rclcpp::ok()) { if (std::filesystem::exists(storage_path)) { diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp index 7233b6b84..b4071b7ee 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp @@ -120,7 +120,7 @@ class Rosbag2StorageAPITests : public rosbag2_test_common::ParametrizedTemporary TEST_P(Rosbag2StorageAPITests, get_bagfile_size_read_write_interface) { - const std::string FILE_EXTENSION = (GetParam() == "mcap") ? ".mcap" : ".db3"; + const std::string FILE_EXTENSION = (GetParam() == "mcap") ? ".mcap.active" : ".db3.active"; fs::path full_bagfile_path = root_bag_path_; full_bagfile_path.replace_extension(FILE_EXTENSION); diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp index f1e828a23..7114a601c 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp @@ -73,7 +73,8 @@ class ComposableRecorderIntegrationTests : public CompositionManagerTestFixture void wait_for_storage_file(std::chrono::duration timeout = std::chrono::seconds(10)) { - const auto storage_path = get_bag_file_path(0); + auto storage_path = get_bag_file_path(0); + storage_path += ".active"; const auto start_time = std::chrono::steady_clock::now(); while (std::chrono::steady_clock::now() - start_time < timeout && rclcpp::ok()) { if (fs::exists(storage_path)) {