From 37643ea5d9417709ee93e45e9de3fa976b605b09 Mon Sep 17 00:00:00 2001 From: Christopher Wecht Date: Tue, 2 May 2023 17:43:18 +0200 Subject: [PATCH 1/4] Enable callback group tests for connextdds Signed-off-by: Christopher Wecht --- .../test_add_callback_groups_to_executor.cpp | 63 ------------------- 1 file changed, 63 deletions(-) diff --git a/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp b/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp index 49131638db..9d52d14035 100644 --- a/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp +++ b/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp @@ -99,13 +99,6 @@ TYPED_TEST_SUITE(TestAddCallbackGroupsToExecutorStable, StandardExecutors, Execu TYPED_TEST(TestAddCallbackGroupsToExecutor, add_callback_groups) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } auto node = std::make_shared("my_node", "/ns"); auto timer_callback = []() {}; @@ -155,13 +148,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, add_callback_groups) TYPED_TEST(TestAddCallbackGroupsToExecutor, remove_callback_groups) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } auto node = std::make_shared("my_node", "/ns"); auto timer_callback = []() {}; @@ -193,13 +179,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, remove_callback_groups) TYPED_TEST(TestAddCallbackGroupsToExecutor, add_duplicate_callback_groups) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } ExecutorType executor; auto node = std::make_shared("my_node", "/ns"); @@ -220,13 +199,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, add_duplicate_callback_groups) TYPED_TEST(TestAddCallbackGroupsToExecutor, add_callback_groups_after_add_node_to_executor) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } ExecutorType executor; auto node = std::make_shared("my_node", "/ns"); @@ -263,13 +235,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, add_callback_groups_after_add_node_t TYPED_TEST(TestAddCallbackGroupsToExecutor, add_unallowable_callback_groups) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } ExecutorType executor; auto node = std::make_shared("my_node", "/ns"); @@ -307,13 +272,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, add_unallowable_callback_groups) TYPED_TEST(TestAddCallbackGroupsToExecutor, one_node_many_callback_groups_many_executors) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } ExecutorType timer_executor; ExecutorType sub_executor; @@ -355,13 +313,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, one_node_many_callback_groups_many_e TYPED_TEST(TestAddCallbackGroupsToExecutorStable, subscriber_triggered_to_receive_message) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } auto node = std::make_shared("my_node", "/ns"); @@ -428,13 +379,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutorStable, subscriber_triggered_to_receiv TYPED_TEST(TestAddCallbackGroupsToExecutorStable, callback_group_create_after_spin) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } auto node = std::make_shared("my_node", "/ns"); @@ -481,13 +425,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutorStable, callback_group_create_after_sp TYPED_TEST(TestAddCallbackGroupsToExecutor, remove_callback_group) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } ExecutorType executor; auto node = std::make_shared("my_node", "/ns"); From f87dc7b7a3520935f193dd6e4450917b0bf9fa0c Mon Sep 17 00:00:00 2001 From: Christopher Wecht Date: Wed, 3 May 2023 08:01:30 +0200 Subject: [PATCH 2/4] Enable executors and event executor tests for connextdds Signed-off-by: Christopher Wecht --- .../rclcpp/executors/test_events_executor.cpp | 55 -------- .../test/rclcpp/executors/test_executors.cpp | 120 ------------------ 2 files changed, 175 deletions(-) diff --git a/rclcpp/test/rclcpp/executors/test_events_executor.cpp b/rclcpp/test/rclcpp/executors/test_events_executor.cpp index fbe83fcddc..0d678438ed 100644 --- a/rclcpp/test/rclcpp/executors/test_events_executor.cpp +++ b/rclcpp/test/rclcpp/executors/test_events_executor.cpp @@ -43,11 +43,6 @@ class TestEventsExecutor : public ::testing::Test TEST_F(TestEventsExecutor, run_pub_sub) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto node = std::make_shared("node"); bool msg_received = false; @@ -95,11 +90,6 @@ TEST_F(TestEventsExecutor, run_pub_sub) TEST_F(TestEventsExecutor, run_clients_servers) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto node = std::make_shared("node"); bool request_received = false; @@ -153,11 +143,6 @@ TEST_F(TestEventsExecutor, run_clients_servers) TEST_F(TestEventsExecutor, spin_once_max_duration_timeout) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto node = std::make_shared("node"); EventsExecutor executor; @@ -190,11 +175,6 @@ TEST_F(TestEventsExecutor, spin_once_max_duration_timeout) TEST_F(TestEventsExecutor, spin_once_max_duration_timer) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto node = std::make_shared("node"); EventsExecutor executor; @@ -226,11 +206,6 @@ TEST_F(TestEventsExecutor, spin_once_max_duration_timer) TEST_F(TestEventsExecutor, spin_some_max_duration) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - { auto node = std::make_shared("node"); @@ -277,11 +252,6 @@ TEST_F(TestEventsExecutor, spin_some_max_duration) TEST_F(TestEventsExecutor, spin_some_zero_duration) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto node = std::make_shared("node"); size_t t_runs = 0; @@ -303,11 +273,6 @@ TEST_F(TestEventsExecutor, spin_some_zero_duration) TEST_F(TestEventsExecutor, spin_all_max_duration) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - { auto node = std::make_shared("node"); @@ -358,11 +323,6 @@ TEST_F(TestEventsExecutor, spin_all_max_duration) TEST_F(TestEventsExecutor, cancel_while_timers_running) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto node = std::make_shared("node"); EventsExecutor executor; @@ -402,11 +362,6 @@ TEST_F(TestEventsExecutor, cancel_while_timers_running) TEST_F(TestEventsExecutor, cancel_while_timers_waiting) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto node = std::make_shared("node"); size_t t1_runs = 0; @@ -435,11 +390,6 @@ TEST_F(TestEventsExecutor, destroy_entities) // This test fails on Windows! We skip it for now GTEST_SKIP(); - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - // Create a publisher node and start publishing messages auto node_pub = std::make_shared("node_pub"); auto publisher = node_pub->create_publisher("topic", rclcpp::QoS(10)); @@ -485,11 +435,6 @@ std::string * g_sub_log_msg; std::promise * g_log_msgs_promise; TEST_F(TestEventsExecutor, test_default_incompatible_qos_callbacks) { - // rmw_connextdds doesn't support events-executor - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto node = std::make_shared("node"); rcutils_logging_output_handler_t original_output_handler = rcutils_logging_get_output_handler(); diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 232baaace3..fe509511e8 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -135,14 +135,6 @@ TYPED_TEST_SUITE(TestExecutorsStable, StandardExecutors, ExecutorTypeNames); TYPED_TEST(TestExecutors, detachOnDestruction) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - { ExecutorType executor; executor.add_node(this->node); @@ -159,14 +151,6 @@ TYPED_TEST(TestExecutors, detachOnDestruction) TYPED_TEST(TestExecutorsStable, addTemporaryNode) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; { @@ -187,14 +171,6 @@ TYPED_TEST(TestExecutorsStable, addTemporaryNode) TYPED_TEST(TestExecutors, emptyExecutor) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; std::thread spinner([&]() {EXPECT_NO_THROW(executor.spin());}); std::this_thread::sleep_for(50ms); @@ -206,14 +182,6 @@ TYPED_TEST(TestExecutors, emptyExecutor) TYPED_TEST(TestExecutors, addNodeTwoExecutors) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor1; ExecutorType executor2; EXPECT_NO_THROW(executor1.add_node(this->node)); @@ -225,14 +193,6 @@ TYPED_TEST(TestExecutors, addNodeTwoExecutors) TYPED_TEST(TestExecutors, spinWithTimer) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; bool timer_completed = false; @@ -256,14 +216,6 @@ TYPED_TEST(TestExecutors, spinWithTimer) TYPED_TEST(TestExecutors, spinWhileAlreadySpinning) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; executor.add_node(this->node); @@ -291,14 +243,6 @@ TYPED_TEST(TestExecutors, spinWhileAlreadySpinning) TYPED_TEST(TestExecutors, testSpinUntilFutureComplete) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; executor.add_node(this->node); @@ -322,14 +266,6 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureComplete) TYPED_TEST(TestExecutors, testSpinUntilSharedFutureComplete) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; executor.add_node(this->node); @@ -354,14 +290,6 @@ TYPED_TEST(TestExecutors, testSpinUntilSharedFutureComplete) TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteNoTimeout) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; executor.add_node(this->node); @@ -409,14 +337,6 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteNoTimeout) TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteWithTimeout) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; executor.add_node(this->node); @@ -529,14 +449,6 @@ class TestWaitable : public rclcpp::Waitable TYPED_TEST(TestExecutors, spinAll) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; auto waitable_interfaces = this->node->get_node_waitables_interface(); auto my_waitable = std::make_shared(); @@ -579,14 +491,6 @@ TYPED_TEST(TestExecutors, spinAll) TYPED_TEST(TestExecutors, spinSome) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; auto waitable_interfaces = this->node->get_node_waitables_interface(); auto my_waitable = std::make_shared(); @@ -629,14 +533,6 @@ TYPED_TEST(TestExecutors, spinSome) TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodeBasePtr) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; std::promise promise; @@ -653,14 +549,6 @@ TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodeBasePtr) TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodePtr) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; std::promise promise; @@ -677,14 +565,6 @@ TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodePtr) TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteInterrupted) { using ExecutorType = TypeParam; - // rmw_connextdds doesn't support events-executor - if ( - std::is_same() && - std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) - { - GTEST_SKIP(); - } - ExecutorType executor; executor.add_node(this->node); From 14f6e7ff4c39fd7a5cf6711472bbec55a6f066cf Mon Sep 17 00:00:00 2001 From: Christopher Wecht Date: Wed, 3 May 2023 08:46:46 +0200 Subject: [PATCH 3/4] Enable qos events tests for connextdds Signed-off-by: Christopher Wecht --- rclcpp/test/rclcpp/test_qos_event.cpp | 20 -------------------- 1 file changed, 20 deletions(-) diff --git a/rclcpp/test/rclcpp/test_qos_event.cpp b/rclcpp/test/rclcpp/test_qos_event.cpp index 6b522d7ea2..2405b85033 100644 --- a/rclcpp/test/rclcpp/test_qos_event.cpp +++ b/rclcpp/test/rclcpp/test_qos_event.cpp @@ -314,11 +314,6 @@ TEST_F(TestQosEvent, add_to_wait_set) { TEST_F(TestQosEvent, test_on_new_event_callback) { - // rmw_connextdds doesn't support rmw_event_set_callback() interface - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto offered_deadline = rclcpp::Duration(std::chrono::milliseconds(1)); auto requested_deadline = rclcpp::Duration(std::chrono::milliseconds(2)); @@ -360,11 +355,6 @@ TEST_F(TestQosEvent, test_on_new_event_callback) TEST_F(TestQosEvent, test_invalid_on_new_event_callback) { - // rmw_connextdds doesn't support rmw_event_set_callback() interface - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - auto pub = node->create_publisher(topic_name, 10); auto sub = node->create_subscription(topic_name, 10, message_callback); auto dummy_cb = [](size_t count_events) {(void)count_events;}; @@ -439,11 +429,6 @@ TEST_F(TestQosEvent, test_invalid_on_new_event_callback) TEST_F(TestQosEvent, test_pub_matched_event_by_set_event_callback) { - // rmw_connextdds doesn't support rmw_event_set_callback() interface - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - std::atomic_size_t matched_count = 0; rclcpp::PublisherOptions pub_options; @@ -483,11 +468,6 @@ TEST_F(TestQosEvent, test_pub_matched_event_by_set_event_callback) TEST_F(TestQosEvent, test_sub_matched_event_by_set_event_callback) { - // rmw_connextdds doesn't support rmw_event_set_callback() interface - if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") == 0) { - GTEST_SKIP(); - } - std::atomic_size_t matched_count = 0; rclcpp::SubscriptionOptions sub_options; From 4baae58730e6736811aec548c9c4ad463e36b10f Mon Sep 17 00:00:00 2001 From: Christopher Wecht Date: Tue, 16 May 2023 17:15:25 +0200 Subject: [PATCH 4/4] Less flaky qos_event tests Signed-off-by: Christopher Wecht --- rclcpp/test/rclcpp/test_qos_event.cpp | 56 +++++++++++++++++---------- 1 file changed, 36 insertions(+), 20 deletions(-) diff --git a/rclcpp/test/rclcpp/test_qos_event.cpp b/rclcpp/test/rclcpp/test_qos_event.cpp index 2405b85033..3803a07d65 100644 --- a/rclcpp/test/rclcpp/test_qos_event.cpp +++ b/rclcpp/test/rclcpp/test_qos_event.cpp @@ -436,8 +436,10 @@ TEST_F(TestQosEvent, test_pub_matched_event_by_set_event_callback) auto pub = node->create_publisher( topic_name, 10, pub_options); - auto matched_event_callback = [&matched_count](size_t count) { + std::promise 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); @@ -445,24 +447,27 @@ TEST_F(TestQosEvent, test_pub_matched_event_by_set_event_callback) 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(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(1)); { auto sub2 = node->create_subscription( 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(2)); } - ex.spin_some(timeout); + ex.spin_until_future_complete(prom.get_future(), timeout); + prom = {}; EXPECT_EQ(matched_count, static_cast(3)); } - ex.spin_some(timeout); + ex.spin_until_future_complete(prom.get_future(), timeout); EXPECT_EQ(matched_count, static_cast(4)); } @@ -475,8 +480,10 @@ TEST_F(TestQosEvent, test_sub_matched_event_by_set_event_callback) auto sub = node->create_subscription( topic_name, 10, message_callback, sub_options); - auto matched_event_callback = [&matched_count](size_t count) { + std::promise 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); @@ -484,39 +491,44 @@ TEST_F(TestQosEvent, test_sub_matched_event_by_set_event_callback) 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(topic_name, 10); - ex.spin_some(timeout); + ex.spin_until_future_complete(prom.get_future(), timeout); + prom = {}; EXPECT_EQ(matched_count, static_cast(1)); { auto pub2 = node->create_publisher(topic_name, 10); - ex.spin_some(timeout); + ex.spin_until_future_complete(prom.get_future(), timeout); + prom = {}; EXPECT_EQ(matched_count, static_cast(2)); } - ex.spin_some(timeout); + ex.spin_until_future_complete(prom.get_future(), timeout); + prom = {}; EXPECT_EQ(matched_count, static_cast(3)); } - ex.spin_some(timeout); + ex.spin_until_future_complete(prom.get_future(), timeout); EXPECT_EQ(matched_count, static_cast(4)); } TEST_F(TestQosEvent, test_pub_matched_event_by_option_event_callback) { rmw_matched_status_t matched_expected_result; + std::promise 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( @@ -531,11 +543,12 @@ 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(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; @@ -543,20 +556,22 @@ TEST_F(TestQosEvent, test_pub_matched_event_by_option_event_callback) 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 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( topic_name, 10, message_callback, sub_options); @@ -570,10 +585,11 @@ 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(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; @@ -581,5 +597,5 @@ TEST_F(TestQosEvent, test_sub_matched_event_by_option_event_callback) 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); }