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

[iron] Fix for regression in open_succeeds_twice and minimal_writer_example tests (backport #1667) #1669

Merged
merged 2 commits into from
May 22, 2024
Merged
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,14 @@

#include <gmock/gmock.h>

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

#include "rcpputils/asserts.hpp"
#include "rcpputils/filesystem_helper.hpp"

#include "rosbag2_compression/compression_options.hpp"
#include "rosbag2_compression/sequential_compression_writer.hpp"
Expand All @@ -39,6 +39,8 @@

using namespace testing; // NOLINT

namespace fs = std::filesystem;

static constexpr const char * DefaultTestCompressor = "fake_comp";

class SequentialCompressionWriterTest : public TestWithParam<uint64_t>
Expand All @@ -49,12 +51,12 @@ class SequentialCompressionWriterTest : public TestWithParam<uint64_t>
storage_{std::make_shared<NiceMock<MockStorage>>()},
converter_factory_{std::make_shared<StrictMock<MockConverterFactory>>()},
metadata_io_{std::make_unique<NiceMock<MockMetadataIo>>()},
tmp_dir_{rcpputils::fs::temp_directory_path() / "SequentialCompressionWriterTest"},
tmp_dir_{fs::temp_directory_path() / "SequentialCompressionWriterTest"},
tmp_dir_storage_options_{},
serialization_format_{"rmw_format"}
{
tmp_dir_storage_options_.uri = tmp_dir_.string();
rcpputils::fs::remove_all(tmp_dir_);
fs::remove_all(tmp_dir_);
ON_CALL(*storage_factory_, open_read_write(_)).WillByDefault(Return(storage_));
EXPECT_CALL(*storage_factory_, open_read_write(_)).Times(AtLeast(0));
// intercept the metadata write so we can analyze it.
Expand All @@ -71,7 +73,7 @@ class SequentialCompressionWriterTest : public TestWithParam<uint64_t>

~SequentialCompressionWriterTest() override
{
rcpputils::fs::remove_all(tmp_dir_);
fs::remove_all(tmp_dir_);
}

void initializeFakeFileStorage()
Expand Down Expand Up @@ -131,7 +133,7 @@ class SequentialCompressionWriterTest : public TestWithParam<uint64_t>
std::shared_ptr<StrictMock<MockConverterFactory>> converter_factory_;
std::unique_ptr<MockMetadataIo> metadata_io_;

rcpputils::fs::path tmp_dir_;
fs::path tmp_dir_;
rosbag2_storage::StorageOptions tmp_dir_storage_options_;
rosbag2_storage::BagMetadata intercepted_write_metadata_;
std::vector<rosbag2_storage::BagMetadata> v_intercepted_update_metadata_;
Expand Down Expand Up @@ -199,7 +201,7 @@ TEST_F(SequentialCompressionWriterTest, open_succeeds_on_supported_compression_f
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads};
initializeWriter(compression_options);

auto tmp_dir = rcpputils::fs::temp_directory_path() / "path_not_empty";
auto tmp_dir = tmp_dir_ / "path_not_empty";
auto storage_options = rosbag2_storage::StorageOptions();
storage_options.uri = tmp_dir.string();

Expand All @@ -214,8 +216,8 @@ TEST_F(SequentialCompressionWriterTest, open_succeeds_twice)
kDefaultCompressionQueueSize, kDefaultCompressionQueueThreads};
initializeWriter(compression_options);

auto tmp_dir = rcpputils::fs::temp_directory_path() / "path_not_empty";
auto tmp_dir_next = rcpputils::fs::temp_directory_path() / "path_not_empty_next";
auto tmp_dir = tmp_dir_ / "path_not_empty";
auto tmp_dir_next = tmp_dir_ / "path_not_empty_next";

auto storage_options = rosbag2_storage::StorageOptions();
auto storage_options_next = rosbag2_storage::StorageOptions();
Expand Down
6 changes: 2 additions & 4 deletions rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_api.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,9 +106,7 @@ TEST_P(TestRosbag2CPPAPI, minimal_writer_example)
writer.open(rosbag_directory_next.string());

// write same topic to different bag
writer.write(
serialized_msg2, "/yet/another/topic", "test_msgs/msg/BasicTypes",
rclcpp::Clock().now());
writer.write(bag_message, "/my/other/topic", "test_msgs/msg/BasicTypes");

// close by scope
}
Expand Down Expand Up @@ -152,7 +150,7 @@ TEST_P(TestRosbag2CPPAPI, minimal_writer_example)
&extracted_serialized_msg, &extracted_test_msg);

EXPECT_EQ(test_msg, extracted_test_msg);
EXPECT_EQ("/yet/another/topic", topic);
EXPECT_EQ("/my/other/topic", topic);
}

// alternative reader
Expand Down
Loading