From adffc7edb17a2c3e7019a93e98d924e1456ea63f Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Fri, 19 Jul 2024 08:12:31 -0700 Subject: [PATCH] [iron] Bugfix for wrong timestamps in ros2 bag info (backport #1745) (#1753) * Bugfix for wrong timestamps in ros2 bag info (#1745) * Bugfix for wrong timestamps in ros2 bag info - Correctly calculate fractional part for seconds by subtracting `nanoseconds_from_seconds` from `nanoseconds`. Signed-off-by: Michael Orlov * Adjust expectations in the "ros2 bag info" integration tests Signed-off-by: Michael Orlov * Add leading zeros to the fractional seconds in the format_duration(..) Signed-off-by: Michael Orlov * Adjust expectations in info end-to-end tests by adding leading zero The real file duration is: 70633730 nanoseconds. i.e., regex mask shall be "0\\.0706.*s" to match 070633730 nanoseconds. Signed-off-by: Michael Orlov --------- Signed-off-by: Michael Orlov (cherry picked from commit da28c9da82824b8ce5f6fc18935d1a954e52b636) # Conflicts: # rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp * Address merge conflicts Signed-off-by: Michael Orlov --------- Signed-off-by: Michael Orlov Co-authored-by: Michael Orlov --- rosbag2_py/src/rosbag2_py/format_bag_metadata.cpp | 15 +++++++++------ .../test_rosbag2_info_end_to_end.cpp | 6 +++--- 2 files changed, 12 insertions(+), 9 deletions(-) diff --git a/rosbag2_py/src/rosbag2_py/format_bag_metadata.cpp b/rosbag2_py/src/rosbag2_py/format_bag_metadata.cpp index 8f98e87331..5448d72e43 100644 --- a/rosbag2_py/src/rosbag2_py/format_bag_metadata.cpp +++ b/rosbag2_py/src/rosbag2_py/format_bag_metadata.cpp @@ -40,9 +40,12 @@ std::unordered_map format_duration( std::chrono::high_resolution_clock::duration duration) { std::unordered_map formatted_duration; - auto m_seconds = std::chrono::duration_cast(duration); - auto seconds = std::chrono::duration_cast(m_seconds); - std::string fractional_seconds = std::to_string(m_seconds.count() % 1000); + auto seconds = std::chrono::duration_cast(duration); + auto nanoseconds = std::chrono::duration_cast(duration); + auto nanoseconds_from_seconds = std::chrono::duration_cast(seconds); + std::stringstream fractional_seconds_ss; + fractional_seconds_ss << std::setw(9) << std::setfill('0') << + (nanoseconds - nanoseconds_from_seconds).count(); std::time_t std_time_point = seconds.count(); tm time; #ifdef _WIN32 @@ -50,14 +53,14 @@ std::unordered_map format_duration( #else localtime_r(&std_time_point, &time); #endif - std::stringstream formatted_date; std::stringstream formatted_time; formatted_date << std::put_time(&time, "%b %e %Y"); - formatted_time << std::put_time(&time, "%H:%M:%S") << "." << fractional_seconds; + formatted_time << std::put_time(&time, "%H:%M:%S") << "." << fractional_seconds_ss.str(); formatted_duration["date"] = formatted_date.str(); formatted_duration["time"] = formatted_time.str(); - formatted_duration["time_in_sec"] = std::to_string(seconds.count()) + "." + fractional_seconds; + formatted_duration["time_in_sec"] = std::to_string(seconds.count()) + "." + + fractional_seconds_ss.str(); return formatted_duration; } diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp index 8cef314899..6a22b9cdd0 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp @@ -51,9 +51,9 @@ TEST_P(InfoEndToEndTestFixture, info_end_to_end_test) { "\nFiles: " + expected_file + "\nBag size: .*B" "\nStorage id: " + expected_storage + - "\nDuration: 0\\.151s" - "\nStart: Apr .+ 2020 .*:.*:36.763 \\(1586406456\\.763\\)" - "\nEnd: Apr .+ 2020 .*:.*:36.914 \\(1586406456\\.914\\)" + "\nDuration: 0.151137181s" + "\nStart: Apr .+ 2020 .*:.*:36.763032325 \\(1586406456.763032325\\)" + "\nEnd: Apr .+ 2020 .*:.*:36.914169506 \\(1586406456.914169506\\)" "\nMessages: 7" "\nTopic information: ")); EXPECT_THAT(