Skip to content

Commit

Permalink
Enhance E2E tests in Windows (#278)
Browse files Browse the repository at this point in the history
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 <zmichaels11@users.noreply.github.com>
  • Loading branch information
Anas Abou Allaban and zmichaels11 committed Jan 31, 2020
1 parent 430c4e5 commit 1c63b6e
Show file tree
Hide file tree
Showing 3 changed files with 28 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
16 changes: 13 additions & 3 deletions rosbag2_tests/test/rosbag2_tests/record_fixture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,11 @@ TEST_F(RecordFixture, record_end_to_end_test) {

auto test_topic_messages = get_messages_for_topic<test_msgs::msg::Strings>("/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<test_msgs::msg::BasicTypes>("/wrong_topic");
Expand Down Expand Up @@ -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
Expand Down

0 comments on commit 1c63b6e

Please sign in to comment.