Skip to content

Commit

Permalink
Less flaky qos_event tests
Browse files Browse the repository at this point in the history
Signed-off-by: Christopher Wecht <[email protected]>
  • Loading branch information
cwecht committed May 16, 2023
1 parent 14f6e7f commit 4baae58
Showing 1 changed file with 36 additions and 20 deletions.
56 changes: 36 additions & 20 deletions rclcpp/test/rclcpp/test_qos_event.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -436,33 +436,38 @@ TEST_F(TestQosEvent, test_pub_matched_event_by_set_event_callback)
auto pub = node->create_publisher<test_msgs::msg::Empty>(
topic_name, 10, pub_options);

auto matched_event_callback = [&matched_count](size_t count) {
std::promise<void> prom;
auto matched_event_callback = [&matched_count, &prom](size_t count) {
matched_count += count;
prom.set_value();
};

pub->set_on_new_qos_event_callback(matched_event_callback, RCL_PUBLISHER_MATCHED);

rclcpp::executors::SingleThreadedExecutor ex;
ex.add_node(node->get_node_base_interface());

const auto timeout = std::chrono::milliseconds(200);
const auto timeout = std::chrono::seconds(10);

{
auto sub1 = node->create_subscription<test_msgs::msg::Empty>(topic_name, 10, message_callback);
ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
prom = {};
EXPECT_EQ(matched_count, static_cast<size_t>(1));

{
auto sub2 = node->create_subscription<test_msgs::msg::Empty>(
topic_name, 10, message_callback);
ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
prom = {};
EXPECT_EQ(matched_count, static_cast<size_t>(2));
}
ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
prom = {};
EXPECT_EQ(matched_count, static_cast<size_t>(3));
}

ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
EXPECT_EQ(matched_count, static_cast<size_t>(4));
}

Expand All @@ -475,48 +480,55 @@ TEST_F(TestQosEvent, test_sub_matched_event_by_set_event_callback)
auto sub = node->create_subscription<test_msgs::msg::Empty>(
topic_name, 10, message_callback, sub_options);

auto matched_event_callback = [&matched_count](size_t count) {
std::promise<void> prom;
auto matched_event_callback = [&matched_count, &prom](size_t count) {
matched_count += count;
prom.set_value();
};

sub->set_on_new_qos_event_callback(matched_event_callback, RCL_SUBSCRIPTION_MATCHED);

rclcpp::executors::SingleThreadedExecutor ex;
ex.add_node(node->get_node_base_interface());

const auto timeout = std::chrono::milliseconds(200);
const auto timeout = std::chrono::seconds(10000);

{
auto pub1 = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);

ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
prom = {};
EXPECT_EQ(matched_count, static_cast<size_t>(1));

{
auto pub2 = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
prom = {};
EXPECT_EQ(matched_count, static_cast<size_t>(2));
}

ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
prom = {};
EXPECT_EQ(matched_count, static_cast<size_t>(3));
}

ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
EXPECT_EQ(matched_count, static_cast<size_t>(4));
}

TEST_F(TestQosEvent, test_pub_matched_event_by_option_event_callback)
{
rmw_matched_status_t matched_expected_result;
std::promise<void> prom;

rclcpp::PublisherOptions pub_options;
pub_options.event_callbacks.matched_callback =
[&matched_expected_result](rmw_matched_status_t & s) {
[&matched_expected_result, &prom](rmw_matched_status_t & s) {
EXPECT_EQ(s.total_count, matched_expected_result.total_count);
EXPECT_EQ(s.total_count_change, matched_expected_result.total_count_change);
EXPECT_EQ(s.current_count, matched_expected_result.current_count);
EXPECT_EQ(s.current_count_change, matched_expected_result.current_count_change);
prom.set_value();
};

auto pub = node->create_publisher<test_msgs::msg::Empty>(
Expand All @@ -531,32 +543,35 @@ TEST_F(TestQosEvent, test_pub_matched_event_by_option_event_callback)
matched_expected_result.current_count = 1;
matched_expected_result.current_count_change = 1;

const auto timeout = std::chrono::milliseconds(200);
const auto timeout = std::chrono::seconds(10);

{
auto sub = node->create_subscription<test_msgs::msg::Empty>(topic_name, 10, message_callback);
ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
prom = {};

// destroy a connected subscription
matched_expected_result.total_count = 1;
matched_expected_result.total_count_change = 0;
matched_expected_result.current_count = 0;
matched_expected_result.current_count_change = -1;
}
ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
}

TEST_F(TestQosEvent, test_sub_matched_event_by_option_event_callback)
{
rmw_matched_status_t matched_expected_result;

std::promise<void> prom;
rclcpp::SubscriptionOptions sub_options;
sub_options.event_callbacks.matched_callback =
[&matched_expected_result](rmw_matched_status_t & s) {
[&matched_expected_result, &prom](rmw_matched_status_t & s) {
EXPECT_EQ(s.total_count, matched_expected_result.total_count);
EXPECT_EQ(s.total_count_change, matched_expected_result.total_count_change);
EXPECT_EQ(s.current_count, matched_expected_result.current_count);
EXPECT_EQ(s.current_count_change, matched_expected_result.current_count_change);
prom.set_value();
};
auto sub = node->create_subscription<test_msgs::msg::Empty>(
topic_name, 10, message_callback, sub_options);
Expand All @@ -570,16 +585,17 @@ TEST_F(TestQosEvent, test_sub_matched_event_by_option_event_callback)
matched_expected_result.current_count = 1;
matched_expected_result.current_count_change = 1;

const auto timeout = std::chrono::milliseconds(200);
const auto timeout = std::chrono::seconds(10);
{
auto pub1 = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
prom = {};

// destroy a connected publisher
matched_expected_result.total_count = 1;
matched_expected_result.total_count_change = 0;
matched_expected_result.current_count = 0;
matched_expected_result.current_count_change = -1;
}
ex.spin_some(timeout);
ex.spin_until_future_complete(prom.get_future(), timeout);
}

0 comments on commit 4baae58

Please sign in to comment.