From 1c63b6e1cee433f5453ea3e338252669ac49b1b5 Mon Sep 17 00:00:00 2001 From: Anas Abou Allaban Date: Fri, 31 Jan 2020 10:28:40 -0800 Subject: [PATCH] Enhance E2E tests in Windows (#278) This PR minimizes some of the IO sync issues and delays that occur on windows when writing bags to disk. These regressions were not caught since the CI typically runs tests a few times and so the flakiness was not caught. * Use ctrl-c to stop process in windows * Assert that bagfile split at least once on Windows * Delete leftover bagfiles if they exist on test SetUp * Check if db exists before trying to open it * Replace Each(Pointee(Field with for-each loop Co-authored-by: Zachary Michaels --- .../process_execution_helpers_windows.hpp | 4 ++-- .../test/rosbag2_tests/record_fixture.hpp | 16 +++++++++++++--- .../test_rosbag2_record_end_to_end.cpp | 16 +++++++++++++--- 3 files changed, 28 insertions(+), 8 deletions(-) diff --git a/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp b/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp index 017782c27d..98b4eabb34 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp @@ -110,8 +110,8 @@ void stop_execution(const ProcessHandle & handle) GetExitCodeProcess(handle.process_info.hProcess, &exit_code); // 259 indicates that the process is still active: we want to make sure that the process is // still running properly before killing it. - EXPECT_THAT(exit_code, Eq(259)); - + ASSERT_THAT(exit_code, Eq(259)); + GenerateConsoleCtrlEvent(CTRL_C_EVENT, handle.process_info.dwThreadId); close_process_handles(handle.process_info); CloseHandle(handle.job_handle); } diff --git a/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp b/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp index 3375cd1c05..3b6d80d7ed 100644 --- a/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp +++ b/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp @@ -51,6 +51,14 @@ class RecordFixture : public TemporaryDirectoryFixture std::cout << "Database " << database_path_ << " in " << temporary_dir_path_ << std::endl; } + void SetUp() override + { + const auto path = rcpputils::fs::path{root_bag_path_}; + if (rcpputils::fs::exists(path)) { + remove_directory_recursively(path.string()); + } + } + static void SetUpTestCase() { rclcpp::init(0, nullptr); @@ -66,9 +74,11 @@ class RecordFixture : public TemporaryDirectoryFixture while (true) { try { std::this_thread::sleep_for(50ms); // wait a bit to not query constantly - rosbag2_storage_plugins::SqliteWrapper - db(database_path_, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); - return; + if (rcpputils::fs::exists(rcpputils::fs::path{database_path_})) { + rosbag2_storage_plugins::SqliteWrapper + db(database_path_, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); + return; + } } catch (const rosbag2_storage_plugins::SqliteException & ex) { (void) ex; // still waiting } diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp index 5836610052..f923d5dddc 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp @@ -94,8 +94,11 @@ TEST_F(RecordFixture, record_end_to_end_test) { auto test_topic_messages = get_messages_for_topic("/test_topic"); EXPECT_THAT(test_topic_messages, SizeIs(Ge(expected_test_messages))); - EXPECT_THAT(test_topic_messages, - Each(Pointee(Field(&test_msgs::msg::Strings::string_value, "test")))); + + for (const auto & message : test_topic_messages) { + EXPECT_EQ(message->string_value, "test"); + } + EXPECT_THAT(get_rwm_format_for_topic("/test_topic", db), Eq(rmw_get_serialization_format())); auto wrong_topic_messages = get_messages_for_topic("/wrong_topic"); @@ -333,8 +336,15 @@ TEST_F(RecordFixture, record_end_to_end_with_splitting_splits_bagfile) { const auto bag_path = rcpputils::fs::path(root_bag_path_) / bag_name.str(); - metadata.relative_file_paths.push_back(bag_path.string()); + // There is no guarantee that the bagfile split expected_split times + // due to possible io sync delays. Instead, assert that the bagfile split + // at least once + if (rcpputils::fs::exists(bag_path)) { + metadata.relative_file_paths.push_back(bag_path.string()); + } } + + ASSERT_GE(metadata.relative_file_paths.size(), 1) << "Bagfile never split!"; metadata_io.write_metadata(root_bag_path_, metadata); } #endif