Skip to content

Commit fafbe76

Browse files
authored
Replace rcutils_get_file_size with rcpputils::fs::file_size (ros2#291)
* Replace rcutils_get_file_size with rcpputils::fs::file_size * Fix behavior difference in rcutils_file_size vs rcpputils::fs::file_size * Check if file exists before executing file_size Signed-off-by: Zachary Michaels <[email protected]>
1 parent 06de965 commit fafbe76

File tree

7 files changed

+65
-41
lines changed

7 files changed

+65
-41
lines changed

rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -207,21 +207,20 @@ void SequentialCompressionWriter::compress_last_file()
207207
throw std::runtime_error{"Compressor was not opened!"};
208208
}
209209

210-
const auto to_compress = metadata_.relative_file_paths.back();
210+
const auto to_compress = rcpputils::fs::path{metadata_.relative_file_paths.back()};
211211

212-
if (rcpputils::fs::exists(to_compress) && rcutils_get_file_size(to_compress.c_str()) > 0) {
213-
const auto compressed_uri = compressor_->compress_uri(to_compress);
212+
if (to_compress.exists() && to_compress.file_size() > 0u) {
213+
const auto compressed_uri = compressor_->compress_uri(to_compress.string());
214214

215215
metadata_.relative_file_paths.back() = compressed_uri;
216216

217-
const auto rc = std::remove(to_compress.c_str());
218-
if (rc != 0) {
217+
if (rcpputils::fs::remove(to_compress)) {
219218
ROSBAG2_COMPRESSION_LOG_ERROR_STREAM(
220-
"Failed to remove uncompressed bag: \"" << to_compress << "\"");
219+
"Failed to remove uncompressed bag: \"" << to_compress.string() << "\"");
221220
}
222221
} else {
223222
ROSBAG2_COMPRESSION_LOG_DEBUG_STREAM(
224-
"Removing last file: \"" << to_compress <<
223+
"Removing last file: \"" << to_compress.string() <<
225224
"\" because it either is empty or does not exist.");
226225

227226
metadata_.relative_file_paths.pop_back();
@@ -311,7 +310,11 @@ void SequentialCompressionWriter::finalize_metadata()
311310
metadata_.bag_size = 0;
312311

313312
for (const auto & path : metadata_.relative_file_paths) {
314-
metadata_.bag_size += rcutils_get_file_size(path.c_str());
313+
const auto bag_path = rcpputils::fs::path{path};
314+
315+
if (bag_path.exists()) {
316+
metadata_.bag_size += bag_path.file_size();
317+
}
315318
}
316319

317320
metadata_.topics_with_message_count.clear();

rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include <string>
1919
#include <vector>
2020

21-
#include "rcutils/filesystem.h"
21+
#include "rcpputils/filesystem_helper.hpp"
2222

2323
#include "rosbag2_compression/zstd_compressor.hpp"
2424

@@ -71,7 +71,8 @@ std::vector<uint8_t> get_input_buffer(const std::string & uri)
7171
throw std::runtime_error{errmsg.str()};
7272
}
7373

74-
const auto decompressed_buffer_length = rcutils_get_file_size(uri.c_str());
74+
const auto file_path = rcpputils::fs::path{uri};
75+
const auto decompressed_buffer_length = file_path.exists() ? file_path.file_size() : 0u;
7576

7677
if (decompressed_buffer_length == 0) {
7778
fclose(file_pointer);

rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -20,8 +20,6 @@
2020

2121
#include "rcpputils/filesystem_helper.hpp"
2222

23-
#include "rcutils/filesystem.h"
24-
2523
#include "rosbag2_compression/zstd_decompressor.hpp"
2624

2725
#include "logging.hpp"
@@ -73,7 +71,8 @@ std::vector<uint8_t> get_input_buffer(const std::string & uri)
7371
throw std::runtime_error{errmsg.str()};
7472
}
7573

76-
const auto compressed_buffer_length = rcutils_get_file_size(uri.c_str());
74+
const auto file_path = rcpputils::fs::path{uri};
75+
const auto compressed_buffer_length = file_path.exists() ? file_path.file_size() : 0u;
7776
if (compressed_buffer_length == 0) {
7877
fclose(file_pointer);
7978

rosbag2_compression/test/rosbag2_compression/test_zstd_compressor.cpp

Lines changed: 36 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,6 @@
2121

2222
#include "rcpputils/filesystem_helper.hpp"
2323

24-
#include "rcutils/filesystem.h"
25-
2624
#include "rosbag2_compression/zstd_compressor.hpp"
2725
#include "rosbag2_compression/zstd_decompressor.hpp"
2826

@@ -91,12 +89,19 @@ TEST_F(CompressionHelperFixture, zstd_compress_file_uri)
9189
{
9290
const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file1.txt").string();
9391
create_garbage_file(uri);
92+
93+
ASSERT_TRUE(rcpputils::fs::exists(uri)) <<
94+
"Expected uncompressed URI: \"" << uri << "\" to exist.";
95+
9496
auto zstd_compressor = rosbag2_compression::ZstdCompressor{};
9597
const auto compressed_uri = zstd_compressor.compress_uri(uri);
9698

99+
ASSERT_TRUE(rcpputils::fs::exists(compressed_uri)) <<
100+
"Expected compressed URI: \"" << compressed_uri << "\" to exist.";
101+
97102
const auto expected_compressed_uri = uri + "." + zstd_compressor.get_compression_identifier();
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());
103+
const auto uncompressed_file_size = rcpputils::fs::file_size(rcpputils::fs::path{uri});
104+
const auto compressed_file_size = rcpputils::fs::file_size(rcpputils::fs::path{compressed_uri});
100105

101106
EXPECT_NE(compressed_uri, uri);
102107
EXPECT_EQ(compressed_uri, expected_compressed_uri);
@@ -110,40 +115,52 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_uri)
110115
{
111116
const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file1.txt").string();
112117
create_garbage_file(uri);
113-
const auto initial_file_size = rcutils_get_file_size(uri.c_str());
118+
119+
const auto initial_file_path = rcpputils::fs::path{uri};
120+
121+
ASSERT_TRUE(initial_file_path.exists()) <<
122+
"Expected initial file: \"" << initial_file_path.string() <<
123+
"\" to exist.";
124+
125+
const auto initial_file_size = initial_file_path.file_size();
114126

115127
auto zstd_compressor = rosbag2_compression::ZstdCompressor{};
116128
const auto compressed_uri = zstd_compressor.compress_uri(uri);
117129

118-
// The test is invalid if the initial file is not deleted
119-
ASSERT_EQ(0, std::remove(uri.c_str())) <<
120-
"Removal of \"" << uri << "\" failed! The remaining tests require \"" <<
121-
uri << "\" to be deleted!";
130+
// The test is invalid if the initial file is not deleted
131+
ASSERT_TRUE(rcpputils::fs::remove(initial_file_path)) <<
132+
"Removal of \"" << initial_file_path.string() <<
133+
"\" failed! The remaining tests require \"" <<
134+
initial_file_path.string() << "\" to be deleted!";
122135

123136
auto zstd_decompressor = rosbag2_compression::ZstdDecompressor{};
124137
const auto decompressed_uri = zstd_decompressor.decompress_uri(compressed_uri);
125-
138+
const auto decompressed_file_path = rcpputils::fs::path{decompressed_uri};
126139
const auto expected_decompressed_uri = uri;
127-
const auto decompressed_file_size = rcutils_get_file_size(decompressed_uri.c_str());
140+
141+
ASSERT_TRUE(decompressed_file_path.exists()) <<
142+
"Expected decompressed file: \"" << decompressed_file_path.string() <<
143+
"\" to exist.";
144+
145+
const auto decompressed_file_size = decompressed_file_path.file_size();
128146

129147
EXPECT_NE(compressed_uri, uri);
130148
EXPECT_NE(decompressed_uri, compressed_uri);
131149
EXPECT_EQ(uri, expected_decompressed_uri);
132150
EXPECT_EQ(initial_file_size, decompressed_file_size);
133-
EXPECT_TRUE(rcpputils::fs::exists(decompressed_uri)) <<
134-
"Expected decompressed file: \"" << decompressed_uri << "\" to exist!";
135151
}
136152

137153
TEST_F(CompressionHelperFixture, zstd_decompress_file_contents)
138154
{
139155
const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file2.txt").string();
140156
create_garbage_file(uri);
141157

142-
ASSERT_TRUE(rcpputils::fs::exists(uri)) <<
158+
const auto initial_file_path = rcpputils::fs::path{uri};
159+
ASSERT_TRUE(initial_file_path.exists()) <<
143160
"Expected initial file: \"" << uri << "\" to exist!";
144161

145162
const auto initial_data = read_file(uri);
146-
const auto initial_file_size = rcutils_get_file_size(uri.c_str());
163+
const auto initial_file_size = initial_file_path.file_size();
147164

148165
EXPECT_EQ(
149166
initial_data.size() * sizeof(decltype(initial_data)::value_type),
@@ -161,15 +178,16 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_contents)
161178

162179
auto decompressor = rosbag2_compression::ZstdDecompressor{};
163180
const auto decompressed_uri = decompressor.decompress_uri(compressed_uri);
181+
const auto decompressed_file_path = rcpputils::fs::path{decompressed_uri};
164182

165-
ASSERT_TRUE(rcpputils::fs::exists(decompressed_uri)) <<
166-
"Decompressed file: \"" << decompressed_uri << "\" must exist!";
183+
ASSERT_TRUE(decompressed_file_path.exists()) <<
184+
"Decompressed file: \"" << decompressed_file_path.string() << "\" must exist!";
167185

168186
EXPECT_EQ(uri, decompressed_uri) <<
169187
"Expected decompressed file name to be same as initial!";
170188

171189
const auto decompressed_data = read_file(decompressed_uri);
172-
const auto decompressed_file_size = rcutils_get_file_size(decompressed_uri.c_str());
190+
const auto decompressed_file_size = decompressed_file_path.file_size();
173191

174192
EXPECT_EQ(
175193
decompressed_data.size() * sizeof(decltype(initial_data)::value_type),

rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,8 +23,6 @@
2323

2424
#include "rcpputils/filesystem_helper.hpp"
2525

26-
#include "rcutils/filesystem.h"
27-
2826
#include "rosbag2_cpp/info.hpp"
2927
#include "rosbag2_cpp/storage_options.hpp"
3028

@@ -222,7 +220,11 @@ void SequentialWriter::finalize_metadata()
222220
metadata_.bag_size = 0;
223221

224222
for (const auto & path : metadata_.relative_file_paths) {
225-
metadata_.bag_size += rcutils_get_file_size(path.c_str());
223+
const auto bag_path = rcpputils::fs::path{path};
224+
225+
if (bag_path.exists()) {
226+
metadata_.bag_size += bag_path.file_size();
227+
}
226228
}
227229

228230
metadata_.topics_with_message_count.clear();

rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,6 @@
2727

2828
#include "rcpputils/filesystem_helper.hpp"
2929

30-
#include "rcutils/filesystem.h"
31-
3230
#include "rosbag2_storage/metadata_io.hpp"
3331
#include "rosbag2_storage/serialized_bag_message.hpp"
3432
#include "rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp"
@@ -158,7 +156,9 @@ std::vector<rosbag2_storage::TopicMetadata> SqliteStorage::get_all_topics_and_ty
158156

159157
uint64_t SqliteStorage::get_bagfile_size() const
160158
{
161-
return rcutils_get_file_size(get_relative_file_path().c_str());
159+
const auto bag_path = rcpputils::fs::path{get_relative_file_path()};
160+
161+
return bag_path.exists() ? bag_path.file_size() : 0u;
162162
}
163163

164164
void SqliteStorage::initialize()
@@ -287,7 +287,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata()
287287
metadata.starting_time =
288288
std::chrono::time_point<std::chrono::high_resolution_clock>(std::chrono::nanoseconds(min_time));
289289
metadata.duration = std::chrono::nanoseconds(max_time) - std::chrono::nanoseconds(min_time);
290-
metadata.bag_size = rcutils_get_file_size(get_relative_file_path().c_str());
290+
metadata.bag_size = get_bagfile_size();
291291

292292
return metadata;
293293
}

rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -282,10 +282,11 @@ TEST_F(RecordFixture, record_end_to_end_with_splitting_bagsize_split_is_at_least
282282

283283
// Don't include the last bagfile since it won't be full
284284
for (int i = 0; i < actual_splits - 1; ++i) {
285-
const auto bagfile_path = metadata.relative_file_paths[i];
286-
EXPECT_TRUE(rcpputils::fs::exists(bagfile_path));
285+
const auto bagfile_path = rcpputils::fs::path{metadata.relative_file_paths[i]};
286+
ASSERT_TRUE(bagfile_path.exists()) <<
287+
"Expected bag file: \"" << bagfile_path.string() << "\" to exist.";
287288

288-
const auto actual_split_size = static_cast<int>(rcutils_get_file_size(bagfile_path.c_str()));
289+
const auto actual_split_size = static_cast<int>(bagfile_path.file_size());
289290
// Actual size is guaranteed to be >= bagfile_split size
290291
EXPECT_LT(bagfile_split_size, actual_split_size);
291292
}

0 commit comments

Comments
 (0)