From 2397628a9bc4ccc603ccc6ae03c1bfed359b27cf Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 2 Apr 2024 15:19:49 -0700 Subject: [PATCH] Replace deprecated spin_until_future_complete Signed-off-by: Christophe Bedard --- .../include/rosbag2_test_common/client_manager.hpp | 2 +- .../composition_manager_test_fixture.hpp | 2 +- .../test/rosbag2_transport/test_composable_player.cpp | 8 ++++---- .../test/rosbag2_transport/test_composable_recorder.cpp | 2 +- .../rosbag2_transport/test_load_composable_components.cpp | 4 ++-- 5 files changed, 9 insertions(+), 9 deletions(-) diff --git a/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp b/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp index c9078fe946..9c29a3d3a5 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/client_manager.hpp @@ -111,7 +111,7 @@ class ClientManager : public rclcpp::Node auto request = std::make_shared(); auto result = client->async_send_request(request); // Wait for the result. - if (rclcpp::executors::spin_node_until_future_complete( + if (rclcpp::executors::spin_node_until_complete( exec_, get_node_base_interface(), result, timeout) != rclcpp::FutureReturnCode::SUCCESS) { RCLCPP_INFO( diff --git a/rosbag2_transport/test/rosbag2_transport/composition_manager_test_fixture.hpp b/rosbag2_transport/test/rosbag2_transport/composition_manager_test_fixture.hpp index f58f598164..dcd5896bbd 100644 --- a/rosbag2_transport/test/rosbag2_transport/composition_manager_test_fixture.hpp +++ b/rosbag2_transport/test/rosbag2_transport/composition_manager_test_fixture.hpp @@ -83,7 +83,7 @@ class CompositionManagerTestFixture auto unload_node_future = unload_node_client_->async_send_request(unload_node_request); // Wait for the response auto unload_node_ret = - exec_->spin_until_future_complete(unload_node_future, std::chrono::seconds(10)); + exec_->spin_until_complete(unload_node_future, std::chrono::seconds(10)); auto unload_node_response = unload_node_future.get(); EXPECT_EQ(unload_node_ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(unload_node_response->success, true); diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp index 70826d4189..ed58ce3c81 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp @@ -70,7 +70,7 @@ class ComposablePlayerIntegrationTests : public CompositionManagerTestFixture EXPECT_TRUE(is_paused_client_->wait_for_service(std::chrono::seconds(10))); auto is_paused_request = std::make_shared(); auto is_paused_future = is_paused_client_->async_send_request(is_paused_request); - auto ret = exec_->spin_until_future_complete(is_paused_future, 10s); // Wait for the result. + auto ret = exec_->spin_until_complete(is_paused_future, 10s); // Wait for the result. EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = std::make_shared(); EXPECT_NO_THROW({result = is_paused_future.get();}); @@ -84,7 +84,7 @@ class ComposablePlayerIntegrationTests : public CompositionManagerTestFixture EXPECT_TRUE(resume_client_->wait_for_service(std::chrono::seconds(10))); auto resume_request = std::make_shared(); auto resume_future = resume_client_->async_send_request(resume_request); - auto ret = exec_->spin_until_future_complete(resume_future, 10s); // Wait for the result. + auto ret = exec_->spin_until_complete(resume_future, 10s); // Wait for the result. EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = std::make_shared(); EXPECT_NO_THROW({result = resume_future.get();}); @@ -100,7 +100,7 @@ class ComposablePlayerIntegrationTests : public CompositionManagerTestFixture play_request->playback_until_timestamp = rclcpp::Time(0, -1); play_request->playback_duration = rclcpp::Duration(-1, 0); auto play_future = play_client_->async_send_request(play_request); - auto ret = exec_->spin_until_future_complete(play_future, 10s); // Wait for the result. + auto ret = exec_->spin_until_complete(play_future, 10s); // Wait for the result. EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = std::make_shared(); EXPECT_NO_THROW({result = play_future.get();}); @@ -192,7 +192,7 @@ TEST_P(ComposablePlayerIntegrationTests, player_can_automatically_play_file_afte load_node_request->parameters.push_back(start_paused.to_parameter_msg()); auto load_node_future = load_node_client_->async_send_request(load_node_request); - auto ret = exec_->spin_until_future_complete(load_node_future, 10s); // Wait for the result. + auto ret = exec_->spin_until_complete(load_node_future, 10s); // Wait for the result. ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = load_node_future.get(); EXPECT_EQ(result->success, true); diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp index 4445813631..6f3a8edb43 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp @@ -292,7 +292,7 @@ TEST_P( auto load_node_future = load_node_client_->async_send_request(load_node_request); // Wait for the response - auto load_node_ret = exec_->spin_until_future_complete(load_node_future, 10s); + auto load_node_ret = exec_->spin_until_complete(load_node_future, 10s); ASSERT_EQ(load_node_ret, rclcpp::FutureReturnCode::SUCCESS); auto load_node_response = load_node_future.get(); EXPECT_EQ(load_node_response->success, true); diff --git a/rosbag2_transport/test/rosbag2_transport/test_load_composable_components.cpp b/rosbag2_transport/test/rosbag2_transport/test_load_composable_components.cpp index db6c554dc3..ca4659433c 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_load_composable_components.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_load_composable_components.cpp @@ -46,7 +46,7 @@ TEST_P(CompositionManagerTestFixture, test_load_play_component) request->parameters.push_back(storage_id.to_parameter_msg()); auto future = load_node_client_->async_send_request(request); - auto ret = exec_->spin_until_future_complete(future, 10s); // Wait for the result. + auto ret = exec_->spin_until_complete(future, 10s); // Wait for the result. ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = future.get(); EXPECT_EQ(result->success, true); @@ -80,7 +80,7 @@ TEST_P(CompositionManagerTestFixture, test_load_record_component) request->parameters.push_back(storage_id.to_parameter_msg()); auto future = load_node_client_->async_send_request(request); - auto ret = exec_->spin_until_future_complete(future, 10s); // Wait for the result. + auto ret = exec_->spin_until_complete(future, 10s); // Wait for the result. ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = future.get(); EXPECT_EQ(result->success, true);