diff --git a/test_communication/test/test_action_client.cpp b/test_communication/test/test_action_client.cpp index 050597f4..0840235f 100644 --- a/test_communication/test/test_action_client.cpp +++ b/test_communication/test/test_action_client.cpp @@ -81,7 +81,7 @@ send_goals( auto goal_handle_future = action_client->async_send_goal(goal_tests[test_index].goal, send_goal_options); - using rclcpp::executor::FutureReturnCode; + using rclcpp::FutureReturnCode; // wait for the sent goal to be accepted auto status = rclcpp::spin_until_future_complete(node, goal_handle_future, 1000s); if (status != FutureReturnCode::SUCCESS) { diff --git a/test_rclcpp/test/test_client_scope_client.cpp b/test_rclcpp/test/test_client_scope_client.cpp index 53edb9d0..59385038 100644 --- a/test_rclcpp/test/test_client_scope_client.cpp +++ b/test_rclcpp/test/test_client_scope_client.cpp @@ -51,7 +51,7 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test auto result1 = client1->async_send_request(request1); if ( rclcpp::spin_until_future_complete(node, result1) != - rclcpp::executor::FutureReturnCode::SUCCESS) + rclcpp::FutureReturnCode::SUCCESS) { FAIL(); } @@ -78,7 +78,7 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test std::cout.flush(); auto result2 = client2->async_send_request(request2); if (rclcpp::spin_until_future_complete(node, result2) != - rclcpp::executor::FutureReturnCode::SUCCESS) + rclcpp::FutureReturnCode::SUCCESS) { FAIL(); } diff --git a/test_rclcpp/test/test_client_scope_consistency_client.cpp b/test_rclcpp/test/test_client_scope_consistency_client.cpp index 1fb5f04f..193e0a36 100644 --- a/test_rclcpp/test/test_client_scope_consistency_client.cpp +++ b/test_rclcpp/test/test_client_scope_consistency_client.cpp @@ -40,7 +40,7 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_reg // Replicate the settings that caused https://github.com/ros2/system_tests/issues/153 rmw_qos_profile_t rmw_qos_profile = rmw_qos_profile_default; - rclcpp::executor::FutureReturnCode ret1; + rclcpp::FutureReturnCode ret1; // Extra scope so the first client will be deleted afterwards { @@ -60,7 +60,7 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_reg auto result1 = client1->async_send_request(request1); ret1 = rclcpp::spin_until_future_complete(node, result1, 5s); - if (ret1 == rclcpp::executor::FutureReturnCode::SUCCESS) { + if (ret1 == rclcpp::FutureReturnCode::SUCCESS) { printf("received first result\n"); std::cout.flush(); if (3 == result1.get()->sum) { @@ -71,7 +71,7 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_reg std::cout.flush(); } } else { - printf("first result not received: %s\n", rclcpp::executor::to_string(ret1).c_str()); + printf("first result not received: %s\n", rclcpp::to_string(ret1).c_str()); std::cout.flush(); } @@ -96,7 +96,7 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_reg auto result2 = client2->async_send_request(request2); auto ret2 = rclcpp::spin_until_future_complete(node, result2, 5s); - if (ret2 == rclcpp::executor::FutureReturnCode::SUCCESS) { + if (ret2 == rclcpp::FutureReturnCode::SUCCESS) { printf("received second result\n"); std::cout.flush(); if (5 == result2.get()->sum) { @@ -107,7 +107,7 @@ TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_reg std::cout.flush(); } } else { - printf("second result not received: %s\n", rclcpp::executor::to_string(ret2).c_str()); + printf("second result not received: %s\n", rclcpp::to_string(ret2).c_str()); std::cout.flush(); } diff --git a/test_rclcpp/test/test_multithreaded.cpp b/test_rclcpp/test/test_multithreaded.cpp index 39552ece..2d16db73 100644 --- a/test_rclcpp/test/test_multithreaded.cpp +++ b/test_rclcpp/test/test_multithreaded.cpp @@ -51,7 +51,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) auto node = rclcpp::Node::make_shared( node_topic_name, rclcpp::NodeOptions().use_intra_process_comms(intra_process)); auto callback_group = node->create_callback_group( - rclcpp::callback_group::CallbackGroupType::Reentrant); + rclcpp::CallbackGroupType::Reentrant); const size_t num_messages = std::min(executor.get_number_of_threads(), 16); auto pub = node->create_publisher(node_topic_name, 5 * num_messages); @@ -169,7 +169,7 @@ TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients) rmw_qos_profile_t qos_profile = rmw_qos_profile_services_default; qos_profile.depth = std::min(executor.get_number_of_threads(), 16) * 2; auto callback_group = node->create_callback_group( - rclcpp::callback_group::CallbackGroupType::Reentrant); + rclcpp::CallbackGroupType::Reentrant); auto service = node->create_service( "multi_consumer_clients", callback, qos_profile, callback_group); @@ -210,7 +210,7 @@ TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients) // Wait on each future for (uint32_t i = 0; i < results.size(); ++i) { auto result = executor.spin_until_future_complete(results[i]); - ASSERT_EQ(rclcpp::executor::FutureReturnCode::SUCCESS, result); + ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, result); } // Check the status of all futures @@ -269,9 +269,9 @@ static inline void multi_access_publisher(bool intra_process) auto node = rclcpp::Node::make_shared(node_topic_name, options); auto timer_callback_group = node->create_callback_group( - rclcpp::callback_group::CallbackGroupType::Reentrant); + rclcpp::CallbackGroupType::Reentrant); auto sub_callback_group = node->create_callback_group( - rclcpp::callback_group::CallbackGroupType::Reentrant); + rclcpp::CallbackGroupType::Reentrant); rclcpp::executors::MultiThreadedExecutor executor; diff --git a/test_rclcpp/test/test_services_client.cpp b/test_rclcpp/test/test_services_client.cpp index 19424519..ff034812 100644 --- a/test_rclcpp/test/test_services_client.cpp +++ b/test_rclcpp/test/test_services_client.cpp @@ -47,7 +47,7 @@ TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_noreqid) { auto result = client->async_send_request(request); auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. - ASSERT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(3, result.get()->sum); } @@ -68,7 +68,7 @@ TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_reqid) { auto result = client->async_send_request(request); auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. - ASSERT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(9, result.get()->sum); } @@ -96,5 +96,5 @@ TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request) { }); auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. - ASSERT_EQ(ret, rclcpp::executor::FutureReturnCode::SUCCESS); + ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); } diff --git a/test_rclcpp/test/test_spin.cpp b/test_rclcpp/test/test_spin.cpp index b999753d..28b1ade0 100644 --- a/test_rclcpp/test/test_spin.cpp +++ b/test_rclcpp/test/test_spin.cpp @@ -38,7 +38,7 @@ using namespace std::chrono_literals; */ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete_timeout) { if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} - using rclcpp::executor::FutureReturnCode; + using rclcpp::FutureReturnCode; rclcpp::executors::SingleThreadedExecutor executor; // Try passing an already complete future, it should succeed. @@ -143,7 +143,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) { executor.add_node(node); ASSERT_EQ( executor.spin_until_future_complete(future), - rclcpp::executor::FutureReturnCode::SUCCESS); + rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(future.get(), true); } @@ -163,12 +163,12 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_timeou ASSERT_EQ( rclcpp::spin_until_future_complete(node, future, std::chrono::milliseconds(25)), - rclcpp::executor::FutureReturnCode::TIMEOUT); + rclcpp::FutureReturnCode::TIMEOUT); // If we wait a little longer, we should complete the future ASSERT_EQ( rclcpp::spin_until_future_complete(node, future, std::chrono::milliseconds(50)), - rclcpp::executor::FutureReturnCode::SUCCESS); + rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(future.get(), true); } @@ -195,7 +195,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_interr ASSERT_EQ( rclcpp::spin_until_future_complete(node, future, std::chrono::milliseconds(50)), - rclcpp::executor::FutureReturnCode::INTERRUPTED); + rclcpp::FutureReturnCode::INTERRUPTED); } TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), cancel) { diff --git a/test_rclcpp/test/test_subscription.cpp b/test_rclcpp/test/test_subscription.cpp index 3316a00a..dc05ff58 100644 --- a/test_rclcpp/test/test_subscription.cpp +++ b/test_rclcpp/test/test_subscription.cpp @@ -40,12 +40,12 @@ using namespace std::chrono_literals; template void wait_for_future( - rclcpp::executor::Executor & executor, + rclcpp::Executor & executor, std::shared_future & future, const DurationT & timeout) { - using rclcpp::executor::FutureReturnCode; - rclcpp::executor::FutureReturnCode future_ret; + using rclcpp::FutureReturnCode; + rclcpp::FutureReturnCode future_ret; auto start_time = std::chrono::steady_clock::now(); future_ret = executor.spin_until_future_complete(future, timeout); auto elapsed_time = std::chrono::steady_clock::now() - start_time; @@ -163,7 +163,7 @@ TEST(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinning printf("spin_until_future_complete(short timeout) - no callbacks expected\n"); sub_called = std::promise(); sub_called_future = sub_called.get_future(); - using rclcpp::executor::FutureReturnCode; + using rclcpp::FutureReturnCode; FutureReturnCode future_ret = executor.spin_until_future_complete(sub_called_future, 100ms); EXPECT_EQ(FutureReturnCode::TIMEOUT, future_ret); ASSERT_EQ(5, counter); diff --git a/test_rclcpp/test/test_waitable.cpp b/test_rclcpp/test/test_waitable.cpp index 9da1578f..e77e4402 100644 --- a/test_rclcpp/test/test_waitable.cpp +++ b/test_rclcpp/test/test_waitable.cpp @@ -43,7 +43,7 @@ class WaitableWithTimer : public rclcpp::Waitable rcl_ret_t ret = rcl_timer_init( timer_.get(), clock_handle, - rclcpp::contexts::default_context::get_global_default_context()->get_rcl_context().get(), + rclcpp::contexts::get_global_default_context()->get_rcl_context().get(), period_nanoseconds, nullptr, rcl_get_default_allocator()); @@ -93,7 +93,7 @@ TEST(CLASSNAME(test_waitable, RMW_IMPLEMENTATION), waitable_with_timer) { if (!rclcpp::ok()) {rclcpp::init(0, nullptr);} auto node = rclcpp::Node::make_shared("waitable_with_timer"); auto waitable = WaitableWithTimer::make_shared(node->get_clock()); - auto group = node->create_callback_group(rclcpp::callback_group::CallbackGroupType::Reentrant); + auto group = node->create_callback_group(rclcpp::CallbackGroupType::Reentrant); node->get_node_waitables_interface()->add_waitable(waitable, group); std::shared_future fut(waitable->execute_promise_.get_future());