diff --git a/rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp b/rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp index 75adf2ba3d..66f1cc5a35 100644 --- a/rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp +++ b/rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp @@ -64,7 +64,11 @@ std::vector get_input_buffer(const std::string & uri) // Read in buffer, handling accordingly const auto file_pointer = open_file(uri.c_str(), "rb"); if (file_pointer == nullptr) { - throw std::runtime_error{"Error opening file"}; + std::stringstream errmsg; + errmsg << "Error opening file: \"" << uri << + "\" for binary reading! errno(" << errno << ")"; + + throw std::runtime_error{errmsg.str()}; } const auto decompressed_buffer_length = rcutils_get_file_size(uri.c_str()); @@ -73,7 +77,7 @@ std::vector get_input_buffer(const std::string & uri) fclose(file_pointer); std::stringstream errmsg; - errmsg << "Unable to get size of file: " << uri; + errmsg << "Unable to get size of file: \"" << uri << "\""; throw std::runtime_error{errmsg.str()}; } @@ -93,7 +97,11 @@ std::vector get_input_buffer(const std::string & uri) if (ferror(file_pointer)) { fclose(file_pointer); - throw std::runtime_error{"Unable to read file"}; + + std::stringstream errmsg; + errmsg << "Unable to read binary data from file: \"" << uri << "\"!"; + + throw std::runtime_error{errmsg.str()}; } fclose(file_pointer); return decompressed_buffer; @@ -110,7 +118,7 @@ void write_output_buffer( { if (output_buffer.empty()) { std::stringstream errmsg; - errmsg << "Cannot write empty buffer to file: " << uri; + errmsg << "Cannot write empty buffer to file: \"" << uri << "\""; throw std::runtime_error{errmsg.str()}; } @@ -131,7 +139,11 @@ void write_output_buffer( if (ferror(file_pointer)) { fclose(file_pointer); - throw std::runtime_error{"Unable to write compressed file"}; + + std::stringstream errmsg; + errmsg << "Unable to write compressed data to file: \"" << uri << "\"!"; + + throw std::runtime_error{errmsg.str()}; } fclose(file_pointer); } diff --git a/rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp b/rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp index 5e0865fda8..de62e1481b 100644 --- a/rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp +++ b/rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp @@ -67,7 +67,8 @@ std::vector get_input_buffer(const std::string & uri) const auto file_pointer = open_file(uri.c_str(), "rb"); if (file_pointer == nullptr) { std::stringstream errmsg; - errmsg << "Failed to open file: \"" << uri << "\" for binary reading!"; + errmsg << "Failed to open file: \"" << uri << + "\" for binary reading! errno(" << errno << ")"; throw std::runtime_error{errmsg.str()}; } @@ -77,7 +78,7 @@ std::vector get_input_buffer(const std::string & uri) fclose(file_pointer); std::stringstream errmsg; - errmsg << "Unable to get size of file: " << uri; + errmsg << "Unable to get size of file: \"" << uri << "\""; throw std::runtime_error{errmsg.str()}; } @@ -123,7 +124,7 @@ void write_output_buffer( { if (output_buffer.empty()) { std::stringstream errmsg; - errmsg << "Cannot write empty buffer to file: " << uri; + errmsg << "Cannot write empty buffer to file: \"" << uri << "\""; throw std::runtime_error{errmsg.str()}; } @@ -131,7 +132,8 @@ void write_output_buffer( const auto file_pointer = open_file(uri.c_str(), "wb"); if (file_pointer == nullptr) { std::stringstream errmsg; - errmsg << "Failed to open file: \"" << uri << "\" for binary writing!"; + errmsg << "Failed to open file: \"" << uri << + "\" for binary writing! errno(" << errno << ")"; throw std::runtime_error{errmsg.str()}; } diff --git a/rosbag2_compression/test/rosbag2_compression/test_zstd_compressor.cpp b/rosbag2_compression/test/rosbag2_compression/test_zstd_compressor.cpp index a0223acbd1..352d19e621 100644 --- a/rosbag2_compression/test/rosbag2_compression/test_zstd_compressor.cpp +++ b/rosbag2_compression/test/rosbag2_compression/test_zstd_compressor.cpp @@ -102,7 +102,8 @@ TEST_F(CompressionHelperFixture, zstd_compress_file_uri) EXPECT_EQ(compressed_uri, expected_compressed_uri); EXPECT_LT(compressed_file_size, uncompressed_file_size); EXPECT_GT(compressed_file_size, 0u); - EXPECT_TRUE(rcpputils::fs::path(compressed_uri).exists()); + EXPECT_TRUE(rcpputils::fs::exists(compressed_uri)) << + "Expected compressed path: \"" << compressed_uri << "\" to exist!"; } TEST_F(CompressionHelperFixture, zstd_decompress_file_uri) @@ -114,7 +115,10 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_uri) auto zstd_compressor = rosbag2_compression::ZstdCompressor{}; const auto compressed_uri = zstd_compressor.compress_uri(uri); - ASSERT_EQ(0, std::remove(uri.c_str())); // The test is invalid if the initial file is not deleted +// 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!"; auto zstd_decompressor = rosbag2_compression::ZstdDecompressor{}; const auto decompressed_uri = zstd_decompressor.decompress_uri(compressed_uri); @@ -126,7 +130,8 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_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::path(decompressed_uri).exists()); + EXPECT_TRUE(rcpputils::fs::exists(decompressed_uri)) << + "Expected decompressed file: \"" << decompressed_uri << "\" to exist!"; } TEST_F(CompressionHelperFixture, zstd_decompress_file_contents) @@ -134,8 +139,8 @@ 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::path{uri}.exists()) << - "Initial file was not created!"; + ASSERT_TRUE(rcpputils::fs::exists(uri)) << + "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()); @@ -147,15 +152,19 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_contents) auto compressor = rosbag2_compression::ZstdCompressor{}; const auto compressed_uri = compressor.compress_uri(uri); - ASSERT_TRUE(rcpputils::fs::path{compressed_uri}.exists()) << - "Compressed file does not exist!"; - ASSERT_EQ(0, std::remove(uri.c_str())) << "Failed to remove initial file!"; + ASSERT_TRUE(rcpputils::fs::exists(compressed_uri)) << + "Expected compressed file: \"" << compressed_uri << "\" to exist!"; + + ASSERT_EQ(0, std::remove(uri.c_str())) << + "Removal of initial file: \"" << uri << + "\" failed! The remaining tests require \"" << uri << "\" to be deleted."; auto decompressor = rosbag2_compression::ZstdDecompressor{}; const auto decompressed_uri = decompressor.decompress_uri(compressed_uri); - ASSERT_TRUE(rcpputils::fs::path{decompressed_uri}.exists()) << - "Decompressed file must exist!"; + ASSERT_TRUE(rcpputils::fs::exists(decompressed_uri)) << + "Decompressed file: \"" << decompressed_uri << "\" must exist!"; + EXPECT_EQ(uri, decompressed_uri) << "Expected decompressed file name to be same as initial!"; @@ -179,7 +188,8 @@ TEST_F(CompressionHelperFixture, zstd_decompress_fails_on_bad_file) create_garbage_file(uri); auto decompressor = rosbag2_compression::ZstdDecompressor{}; - EXPECT_THROW(decompressor.decompress_uri(uri), std::runtime_error); + EXPECT_THROW(decompressor.decompress_uri(uri), std::runtime_error) << + "Expected decompress(\"" << uri << "\") to fail!"; } TEST_F(CompressionHelperFixture, zstd_decompress_fails_on_bad_uri) @@ -187,5 +197,6 @@ TEST_F(CompressionHelperFixture, zstd_decompress_fails_on_bad_uri) const auto bad_uri = (rcpputils::fs::path(temporary_dir_path_) / "bad_uri.txt").string(); auto decompressor = rosbag2_compression::ZstdDecompressor{}; - EXPECT_THROW(decompressor.decompress_uri(bad_uri), std::runtime_error); + EXPECT_THROW(decompressor.decompress_uri(bad_uri), std::runtime_error) << + "Expected decompress_uri(\"" << bad_uri << "\") to fail!"; }