Skip to content

Commit

Permalink
Replace rcutils_get_file_size with rcpputils::fs::file_size (ros2#291)
Browse files Browse the repository at this point in the history
* 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 <zmichaels11@gmail.com>
  • Loading branch information
zmichaels11 authored Feb 13, 2020
1 parent 06de965 commit fafbe76
Show file tree
Hide file tree
Showing 7 changed files with 65 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -207,21 +207,20 @@ void SequentialCompressionWriter::compress_last_file()
throw std::runtime_error{"Compressor was not opened!"};
}

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

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

metadata_.relative_file_paths.back() = compressed_uri;

const auto rc = std::remove(to_compress.c_str());
if (rc != 0) {
if (rcpputils::fs::remove(to_compress)) {
ROSBAG2_COMPRESSION_LOG_ERROR_STREAM(
"Failed to remove uncompressed bag: \"" << to_compress << "\"");
"Failed to remove uncompressed bag: \"" << to_compress.string() << "\"");
}
} else {
ROSBAG2_COMPRESSION_LOG_DEBUG_STREAM(
"Removing last file: \"" << to_compress <<
"Removing last file: \"" << to_compress.string() <<
"\" because it either is empty or does not exist.");

metadata_.relative_file_paths.pop_back();
Expand Down Expand Up @@ -311,7 +310,11 @@ void SequentialCompressionWriter::finalize_metadata()
metadata_.bag_size = 0;

for (const auto & path : metadata_.relative_file_paths) {
metadata_.bag_size += rcutils_get_file_size(path.c_str());
const auto bag_path = rcpputils::fs::path{path};

if (bag_path.exists()) {
metadata_.bag_size += bag_path.file_size();
}
}

metadata_.topics_with_message_count.clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <string>
#include <vector>

#include "rcutils/filesystem.h"
#include "rcpputils/filesystem_helper.hpp"

#include "rosbag2_compression/zstd_compressor.hpp"

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

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

if (decompressed_buffer_length == 0) {
fclose(file_pointer);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,6 @@

#include "rcpputils/filesystem_helper.hpp"

#include "rcutils/filesystem.h"

#include "rosbag2_compression/zstd_decompressor.hpp"

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

const auto compressed_buffer_length = rcutils_get_file_size(uri.c_str());
const auto file_path = rcpputils::fs::path{uri};
const auto compressed_buffer_length = file_path.exists() ? file_path.file_size() : 0u;
if (compressed_buffer_length == 0) {
fclose(file_pointer);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,6 @@

#include "rcpputils/filesystem_helper.hpp"

#include "rcutils/filesystem.h"

#include "rosbag2_compression/zstd_compressor.hpp"
#include "rosbag2_compression/zstd_decompressor.hpp"

Expand Down Expand Up @@ -91,12 +89,19 @@ TEST_F(CompressionHelperFixture, zstd_compress_file_uri)
{
const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file1.txt").string();
create_garbage_file(uri);

ASSERT_TRUE(rcpputils::fs::exists(uri)) <<
"Expected uncompressed URI: \"" << uri << "\" to exist.";

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

ASSERT_TRUE(rcpputils::fs::exists(compressed_uri)) <<
"Expected compressed URI: \"" << compressed_uri << "\" to exist.";

const auto expected_compressed_uri = uri + "." + zstd_compressor.get_compression_identifier();
const auto uncompressed_file_size = rcutils_get_file_size(uri.c_str());
const auto compressed_file_size = rcutils_get_file_size(compressed_uri.c_str());
const auto uncompressed_file_size = rcpputils::fs::file_size(rcpputils::fs::path{uri});
const auto compressed_file_size = rcpputils::fs::file_size(rcpputils::fs::path{compressed_uri});

EXPECT_NE(compressed_uri, uri);
EXPECT_EQ(compressed_uri, expected_compressed_uri);
Expand All @@ -110,40 +115,52 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_uri)
{
const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file1.txt").string();
create_garbage_file(uri);
const auto initial_file_size = rcutils_get_file_size(uri.c_str());

const auto initial_file_path = rcpputils::fs::path{uri};

ASSERT_TRUE(initial_file_path.exists()) <<
"Expected initial file: \"" << initial_file_path.string() <<
"\" to exist.";

const auto initial_file_size = initial_file_path.file_size();

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

// The test is invalid if the initial file is not deleted
ASSERT_EQ(0, std::remove(uri.c_str())) <<
"Removal of \"" << uri << "\" failed! The remaining tests require \"" <<
uri << "\" to be deleted!";
// The test is invalid if the initial file is not deleted
ASSERT_TRUE(rcpputils::fs::remove(initial_file_path)) <<
"Removal of \"" << initial_file_path.string() <<
"\" failed! The remaining tests require \"" <<
initial_file_path.string() << "\" to be deleted!";

auto zstd_decompressor = rosbag2_compression::ZstdDecompressor{};
const auto decompressed_uri = zstd_decompressor.decompress_uri(compressed_uri);

const auto decompressed_file_path = rcpputils::fs::path{decompressed_uri};
const auto expected_decompressed_uri = uri;
const auto decompressed_file_size = rcutils_get_file_size(decompressed_uri.c_str());

ASSERT_TRUE(decompressed_file_path.exists()) <<
"Expected decompressed file: \"" << decompressed_file_path.string() <<
"\" to exist.";

const auto decompressed_file_size = decompressed_file_path.file_size();

EXPECT_NE(compressed_uri, uri);
EXPECT_NE(decompressed_uri, compressed_uri);
EXPECT_EQ(uri, expected_decompressed_uri);
EXPECT_EQ(initial_file_size, decompressed_file_size);
EXPECT_TRUE(rcpputils::fs::exists(decompressed_uri)) <<
"Expected decompressed file: \"" << decompressed_uri << "\" to exist!";
}

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

ASSERT_TRUE(rcpputils::fs::exists(uri)) <<
const auto initial_file_path = rcpputils::fs::path{uri};
ASSERT_TRUE(initial_file_path.exists()) <<
"Expected initial file: \"" << uri << "\" to exist!";

const auto initial_data = read_file(uri);
const auto initial_file_size = rcutils_get_file_size(uri.c_str());
const auto initial_file_size = initial_file_path.file_size();

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

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

ASSERT_TRUE(rcpputils::fs::exists(decompressed_uri)) <<
"Decompressed file: \"" << decompressed_uri << "\" must exist!";
ASSERT_TRUE(decompressed_file_path.exists()) <<
"Decompressed file: \"" << decompressed_file_path.string() << "\" must exist!";

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

const auto decompressed_data = read_file(decompressed_uri);
const auto decompressed_file_size = rcutils_get_file_size(decompressed_uri.c_str());
const auto decompressed_file_size = decompressed_file_path.file_size();

EXPECT_EQ(
decompressed_data.size() * sizeof(decltype(initial_data)::value_type),
Expand Down
8 changes: 5 additions & 3 deletions rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,6 @@

#include "rcpputils/filesystem_helper.hpp"

#include "rcutils/filesystem.h"

#include "rosbag2_cpp/info.hpp"
#include "rosbag2_cpp/storage_options.hpp"

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

for (const auto & path : metadata_.relative_file_paths) {
metadata_.bag_size += rcutils_get_file_size(path.c_str());
const auto bag_path = rcpputils::fs::path{path};

if (bag_path.exists()) {
metadata_.bag_size += bag_path.file_size();
}
}

metadata_.topics_with_message_count.clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,6 @@

#include "rcpputils/filesystem_helper.hpp"

#include "rcutils/filesystem.h"

#include "rosbag2_storage/metadata_io.hpp"
#include "rosbag2_storage/serialized_bag_message.hpp"
#include "rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp"
Expand Down Expand Up @@ -158,7 +156,9 @@ std::vector<rosbag2_storage::TopicMetadata> SqliteStorage::get_all_topics_and_ty

uint64_t SqliteStorage::get_bagfile_size() const
{
return rcutils_get_file_size(get_relative_file_path().c_str());
const auto bag_path = rcpputils::fs::path{get_relative_file_path()};

return bag_path.exists() ? bag_path.file_size() : 0u;
}

void SqliteStorage::initialize()
Expand Down Expand Up @@ -287,7 +287,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata()
metadata.starting_time =
std::chrono::time_point<std::chrono::high_resolution_clock>(std::chrono::nanoseconds(min_time));
metadata.duration = std::chrono::nanoseconds(max_time) - std::chrono::nanoseconds(min_time);
metadata.bag_size = rcutils_get_file_size(get_relative_file_path().c_str());
metadata.bag_size = get_bagfile_size();

return metadata;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -282,10 +282,11 @@ TEST_F(RecordFixture, record_end_to_end_with_splitting_bagsize_split_is_at_least

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

const auto actual_split_size = static_cast<int>(rcutils_get_file_size(bagfile_path.c_str()));
const auto actual_split_size = static_cast<int>(bagfile_path.file_size());
// Actual size is guaranteed to be >= bagfile_split size
EXPECT_LT(bagfile_split_size, actual_split_size);
}
Expand Down

0 comments on commit fafbe76

Please sign in to comment.