Skip to content

Commit

Permalink
Adjust expectations in failing tests to have ".active" extension
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov committed Jun 8, 2024
1 parent 613a494 commit f5bbd23
Show file tree
Hide file tree
Showing 5 changed files with 34 additions and 25 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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";
Expand All @@ -269,6 +268,7 @@ TEST_F(TemporaryDirectoryFixture, can_write_mcap_with_zstd_configured_from_yaml)
rclcpp::Serialization<std_msgs::msg::String> 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;
Expand Down Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -261,7 +261,7 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) {

const auto readable_storage = std::make_unique<rosbag2_storage_plugins::SqliteStorage>();
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},
Expand Down Expand Up @@ -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<rosbag2_storage_plugins::SqliteStorage>();
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<rosbag2_storage_plugins::SqliteStorage>();
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<rosbag2_storage_plugins::SqliteStorage>();
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<rosbag2_storage_plugins::SqliteStorage>();
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<rosbag2_storage_plugins::SqliteStorage>();
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<rosbag2_storage_plugins::SqliteStorage>();
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) {
Expand Down
3 changes: 2 additions & 1 deletion rosbag2_tests/test/rosbag2_tests/record_fixture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,8 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture

void wait_for_storage_file(std::chrono::duration<float> 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)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,8 @@ class ComposableRecorderIntegrationTests : public CompositionManagerTestFixture

void wait_for_storage_file(std::chrono::duration<float> 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)) {
Expand Down

0 comments on commit f5bbd23

Please sign in to comment.