18
18
#include < vector>
19
19
20
20
#include " rclcpp/rclcpp.hpp"
21
+
22
+ #include " rcpputils/filesystem_helper.hpp"
23
+
24
+ #include " rcutils/filesystem.h"
25
+
21
26
#include " rosbag2_compression/zstd_compressor.hpp"
22
27
#include " rosbag2_compression/zstd_decompressor.hpp"
23
- # include " rosbag2_storage/filesystem_helper.hpp "
28
+
24
29
#include " rosbag2_test_common/temporary_directory_fixture.hpp"
25
30
26
31
#include " gmock/gmock.h"
@@ -84,28 +89,27 @@ class CompressionHelperFixture : public rosbag2_test_common::TemporaryDirectoryF
84
89
85
90
TEST_F (CompressionHelperFixture, zstd_compress_file_uri)
86
91
{
87
- const auto uri = rosbag2_storage::FilesystemHelper::concat ({ temporary_dir_path_, " file1.txt" } );
92
+ const auto uri = ( rcpputils::fs::path ( temporary_dir_path_) / " file1.txt" ). string ( );
88
93
create_garbage_file (uri);
89
94
auto zstd_compressor = rosbag2_compression::ZstdCompressor{};
90
95
const auto compressed_uri = zstd_compressor.compress_uri (uri);
91
96
92
97
const auto expected_compressed_uri = uri + " ." + zstd_compressor.get_compression_identifier ();
93
- const auto uncompressed_file_size = rosbag2_storage::FilesystemHelper::get_file_size (uri);
94
- const auto compressed_file_size =
95
- rosbag2_storage::FilesystemHelper::get_file_size (compressed_uri);
98
+ const auto uncompressed_file_size = rcutils_get_file_size (uri.c_str ());
99
+ const auto compressed_file_size = rcutils_get_file_size (compressed_uri.c_str ());
96
100
97
101
EXPECT_NE (compressed_uri, uri);
98
102
EXPECT_EQ (compressed_uri, expected_compressed_uri);
99
103
EXPECT_LT (compressed_file_size, uncompressed_file_size);
100
104
EXPECT_GT (compressed_file_size, 0u );
101
- EXPECT_TRUE (rosbag2_storage::FilesystemHelper::file_exists (compressed_uri));
105
+ EXPECT_TRUE (rcpputils::fs::path (compressed_uri). exists ( ));
102
106
}
103
107
104
108
TEST_F (CompressionHelperFixture, zstd_decompress_file_uri)
105
109
{
106
- const auto uri = rosbag2_storage::FilesystemHelper::concat ({ temporary_dir_path_, " file1.txt" } );
110
+ const auto uri = ( rcpputils::fs::path ( temporary_dir_path_) / " file1.txt" ). string ( );
107
111
create_garbage_file (uri);
108
- const auto initial_file_size = rosbag2_storage::FilesystemHelper::get_file_size (uri);
112
+ const auto initial_file_size = rcutils_get_file_size (uri. c_str () );
109
113
110
114
auto zstd_compressor = rosbag2_compression::ZstdCompressor{};
111
115
const auto compressed_uri = zstd_compressor.compress_uri (uri);
@@ -116,19 +120,18 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_uri)
116
120
const auto decompressed_uri = zstd_decompressor.decompress_uri (compressed_uri);
117
121
118
122
const auto expected_decompressed_uri = uri;
119
- const auto decompressed_file_size =
120
- rosbag2_storage::FilesystemHelper::get_file_size (decompressed_uri);
123
+ const auto decompressed_file_size = rcutils_get_file_size (decompressed_uri.c_str ());
121
124
122
125
EXPECT_NE (compressed_uri, uri);
123
126
EXPECT_NE (decompressed_uri, compressed_uri);
124
127
EXPECT_EQ (uri, expected_decompressed_uri);
125
128
EXPECT_EQ (initial_file_size, decompressed_file_size);
126
- EXPECT_TRUE (rosbag2_storage::FilesystemHelper::file_exists (decompressed_uri));
129
+ EXPECT_TRUE (rcpputils::fs::path (decompressed_uri). exists ( ));
127
130
}
128
131
129
132
TEST_F (CompressionHelperFixture, zstd_decompress_file_contents)
130
133
{
131
- const auto uri = rosbag2_storage::FilesystemHelper::concat ({ temporary_dir_path_, " file2.txt" } );
134
+ const auto uri = ( rcpputils::fs::path ( temporary_dir_path_) / " file2.txt" ). string ( );
132
135
create_garbage_file (uri);
133
136
134
137
auto compressor = rosbag2_compression::ZstdCompressor{};
@@ -138,10 +141,9 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_contents)
138
141
const auto decompressed_uri = decompressor.decompress_uri (compressed_uri);
139
142
140
143
const auto initial_data = read_file (uri);
141
- const auto initial_file_size = rosbag2_storage::FilesystemHelper::get_file_size (uri);
144
+ const auto initial_file_size = rcutils_get_file_size (uri. c_str () );
142
145
const auto decompressed_data = read_file (decompressed_uri);
143
- const auto decompressed_file_size =
144
- rosbag2_storage::FilesystemHelper::get_file_size (decompressed_uri);
146
+ const auto decompressed_file_size = rcutils_get_file_size (decompressed_uri.c_str ());
145
147
146
148
EXPECT_EQ (
147
149
initial_data.size () * sizeof (decltype (initial_data)::value_type),
@@ -154,7 +156,7 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_contents)
154
156
155
157
TEST_F (CompressionHelperFixture, zstd_decompress_fails_on_bad_file)
156
158
{
157
- const auto uri = rosbag2_storage::FilesystemHelper::concat ({ temporary_dir_path_, " file3.txt" } );
159
+ const auto uri = ( rcpputils::fs::path ( temporary_dir_path_) / " file3.txt" ). string ( );
158
160
create_garbage_file (uri);
159
161
160
162
auto decompressor = rosbag2_compression::ZstdDecompressor{};
@@ -163,8 +165,7 @@ TEST_F(CompressionHelperFixture, zstd_decompress_fails_on_bad_file)
163
165
164
166
TEST_F (CompressionHelperFixture, zstd_decompress_fails_on_bad_uri)
165
167
{
166
- const auto bad_uri =
167
- rosbag2_storage::FilesystemHelper::concat ({temporary_dir_path_, " bad_uri.txt" });
168
+ const auto bad_uri = (rcpputils::fs::path (temporary_dir_path_) / " bad_uri.txt" ).string ();
168
169
auto decompressor = rosbag2_compression::ZstdDecompressor{};
169
170
170
171
EXPECT_THROW (decompressor.decompress_uri (bad_uri), std::runtime_error);
0 commit comments