diff --git a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp index c1e06088e2..f7e49c8e48 100644 --- a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp +++ b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp @@ -22,6 +22,7 @@ #include "rosbag2_compression/compression_options.hpp" #include "rosbag2_compression/sequential_compression_writer.hpp" +#include "rcpputils/filesystem_helper.hpp" #include "rosbag2_cpp/writer.hpp" #include "mock_converter_factory.hpp" @@ -41,9 +42,12 @@ class SequentialCompressionWriterTest : public Test storage_{std::make_shared>()}, converter_factory_{std::make_shared>()}, metadata_io_{std::make_unique>()}, - storage_options_{}, + tmp_dir_{rcpputils::fs::temp_directory_path() / "SequentialCompressionWriterTest"}, + tmp_dir_storage_options_{}, serialization_format_{"rmw_format"} { + tmp_dir_storage_options_.uri = tmp_dir_.string(); + rcpputils::fs::remove(tmp_dir_); ON_CALL(*storage_factory_, open_read_write(_, _)).WillByDefault(Return(storage_)); EXPECT_CALL(*storage_factory_, open_read_write(_, _)).Times(AtLeast(0)); } @@ -53,10 +57,29 @@ class SequentialCompressionWriterTest : public Test std::shared_ptr> converter_factory_; std::unique_ptr metadata_io_; std::unique_ptr writer_; - rosbag2_cpp::StorageOptions storage_options_; + rcpputils::fs::path tmp_dir_; + rosbag2_cpp::StorageOptions tmp_dir_storage_options_; std::string serialization_format_; }; +TEST_F(SequentialCompressionWriterTest, open_throws_on_empty_storage_options_uri) +{ + rosbag2_compression::CompressionOptions compression_options{ + "zstd", rosbag2_compression::CompressionMode::FILE}; + auto compression_factory = std::make_unique(); + + auto sequential_writer = std::make_unique( + compression_options, + std::move(compression_factory), + std::move(storage_factory_), + converter_factory_, + std::move(metadata_io_)); + writer_ = std::make_unique(std::move(sequential_writer)); + + EXPECT_THROW( + writer_->open(rosbag2_cpp::StorageOptions(), {serialization_format_, serialization_format_}), + std::runtime_error); +} TEST_F(SequentialCompressionWriterTest, open_throws_on_bad_compression_format) { @@ -73,8 +96,10 @@ TEST_F(SequentialCompressionWriterTest, open_throws_on_bad_compression_format) writer_ = std::make_unique(std::move(sequential_writer)); EXPECT_THROW( - writer_->open(rosbag2_cpp::StorageOptions(), {serialization_format_, serialization_format_}), + writer_->open(tmp_dir_storage_options_, {serialization_format_, serialization_format_}), std::invalid_argument); + + EXPECT_TRUE(rcpputils::fs::remove(tmp_dir_)); } TEST_F(SequentialCompressionWriterTest, open_throws_on_invalid_splitting_size) @@ -118,8 +143,14 @@ TEST_F(SequentialCompressionWriterTest, open_succeeds_on_supported_compression_f std::move(metadata_io_)); writer_ = std::make_unique(std::move(sequential_writer)); + auto tmp_dir = rcpputils::fs::temp_directory_path() / "path_not_empty"; + auto storage_options = rosbag2_cpp::StorageOptions(); + storage_options.uri = tmp_dir.string(); + EXPECT_NO_THROW( - writer_->open(rosbag2_cpp::StorageOptions(), {serialization_format_, serialization_format_})); + writer_->open(tmp_dir_storage_options_, {serialization_format_, serialization_format_})); + + EXPECT_TRUE(rcpputils::fs::remove(tmp_dir_)); } TEST_F(SequentialCompressionWriterTest, writer_calls_create_compressor) @@ -136,5 +167,8 @@ TEST_F(SequentialCompressionWriterTest, writer_calls_create_compressor) converter_factory_, std::move(metadata_io_)); writer_ = std::make_unique(std::move(sequential_writer)); - writer_->open(rosbag2_cpp::StorageOptions(), {serialization_format_, serialization_format_}); + + writer_->open(tmp_dir_storage_options_, {serialization_format_, serialization_format_}); + + EXPECT_TRUE(rcpputils::fs::remove(tmp_dir_)); }