@@ -50,9 +50,9 @@ class CLASSNAME (test_spin, RMW_IMPLEMENTATION) : public ::testing::Test
50
50
};
51
51
52
52
/*
53
- Ensures that the timeout behavior of spin_until_future_complete is correct.
53
+ Ensures that the timeout behavior of spin_until_complete is correct.
54
54
*/
55
- TEST_F (CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete_timeout ) {
55
+ TEST_F (CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_complete_timeout ) {
56
56
using rclcpp::FutureReturnCode;
57
57
rclcpp::executors::SingleThreadedExecutor executor;
58
58
@@ -61,10 +61,10 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete
61
61
std::promise<void > already_set_promise;
62
62
std::shared_future<void > already_complete_future = already_set_promise.get_future ();
63
63
already_set_promise.set_value ();
64
- auto ret = executor.spin_until_future_complete (already_complete_future, 1s);
64
+ auto ret = executor.spin_until_complete (already_complete_future, 1s);
65
65
EXPECT_EQ (FutureReturnCode::SUCCESS, ret);
66
66
// Also try blocking with no timeout (default timeout of -1).
67
- ret = executor.spin_until_future_complete (already_complete_future);
67
+ ret = executor.spin_until_complete (already_complete_future);
68
68
EXPECT_EQ (FutureReturnCode::SUCCESS, ret);
69
69
}
70
70
@@ -73,10 +73,10 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete
73
73
std::promise<void > never_set_promise;
74
74
std::shared_future<void > never_complete_future = never_set_promise.get_future ();
75
75
// Set the timeout just long enough to make sure it isn't incorrectly set.
76
- auto ret = executor.spin_until_future_complete (never_complete_future, 50ms);
76
+ auto ret = executor.spin_until_complete (never_complete_future, 50ms);
77
77
EXPECT_EQ (FutureReturnCode::TIMEOUT, ret);
78
78
// Also try with zero timeout.
79
- ret = executor.spin_until_future_complete (never_complete_future, 0s);
79
+ ret = executor.spin_until_complete (never_complete_future, 0s);
80
80
EXPECT_EQ (FutureReturnCode::TIMEOUT, ret);
81
81
}
82
82
@@ -87,7 +87,7 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete
87
87
[]() {
88
88
std::this_thread::sleep_for (50ms);
89
89
});
90
- auto ret = executor.spin_until_future_complete (async_future, 100ms);
90
+ auto ret = executor.spin_until_complete (async_future, 100ms);
91
91
EXPECT_EQ (FutureReturnCode::SUCCESS, ret);
92
92
}
93
93
@@ -108,10 +108,10 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete
108
108
});
109
109
std::shared_future<void > never_completed_future = never_set_promise.get_future ();
110
110
// Try with a timeout long enough for both timers to fire at least once.
111
- auto ret = executor.spin_until_future_complete (never_completed_future, 75ms);
111
+ auto ret = executor.spin_until_complete (never_completed_future, 75ms);
112
112
EXPECT_EQ (FutureReturnCode::TIMEOUT, ret);
113
113
// Also try with a timeout of zero (nonblocking).
114
- ret = executor.spin_until_future_complete (never_completed_future, 0s);
114
+ ret = executor.spin_until_complete (never_completed_future, 0s);
115
115
EXPECT_EQ (FutureReturnCode::TIMEOUT, ret);
116
116
}
117
117
@@ -129,17 +129,17 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete
129
129
// Do nothing.
130
130
});
131
131
std::shared_future<void > timer_fired_future = timer_fired_promise.get_future ();
132
- auto ret = executor.spin_until_future_complete (timer_fired_future, 100ms);
132
+ auto ret = executor.spin_until_complete (timer_fired_future, 100ms);
133
133
EXPECT_EQ (FutureReturnCode::SUCCESS, ret);
134
- // Also try again with blocking spin_until_future_complete .
134
+ // Also try again with blocking spin_until_complete .
135
135
timer_fired_promise = std::promise<void >();
136
136
timer_fired_future = timer_fired_promise.get_future ();
137
- ret = executor.spin_until_future_complete (timer_fired_future);
137
+ ret = executor.spin_until_complete (timer_fired_future);
138
138
EXPECT_EQ (FutureReturnCode::SUCCESS, ret);
139
139
}
140
140
}
141
141
142
- TEST_F (CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete ) {
142
+ TEST_F (CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete ) {
143
143
auto node = rclcpp::Node::make_shared (" test_spin" );
144
144
145
145
// Construct a fake future to wait on
@@ -156,12 +156,12 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) {
156
156
rclcpp::executors::SingleThreadedExecutor executor;
157
157
executor.add_node (node);
158
158
ASSERT_EQ (
159
- executor.spin_until_future_complete (future),
159
+ executor.spin_until_complete (future),
160
160
rclcpp::FutureReturnCode::SUCCESS);
161
161
EXPECT_EQ (future.get (), true );
162
162
}
163
163
164
- TEST_F (CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_timeout ) {
164
+ TEST_F (CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete_timeout ) {
165
165
auto node = rclcpp::Node::make_shared (" test_spin" );
166
166
167
167
// Construct a fake future to wait on
@@ -175,18 +175,18 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_time
175
175
auto timer = node->create_wall_timer (std::chrono::milliseconds (50 ), callback);
176
176
177
177
ASSERT_EQ (
178
- rclcpp::spin_until_future_complete (node, future, std::chrono::milliseconds (25 )),
178
+ rclcpp::spin_until_complete (node, future, std::chrono::milliseconds (25 )),
179
179
rclcpp::FutureReturnCode::TIMEOUT);
180
180
181
181
// If we wait a little longer, we should complete the future
182
182
ASSERT_EQ (
183
- rclcpp::spin_until_future_complete (node, future, std::chrono::milliseconds (50 )),
183
+ rclcpp::spin_until_complete (node, future, std::chrono::milliseconds (50 )),
184
184
rclcpp::FutureReturnCode::SUCCESS);
185
185
186
186
EXPECT_EQ (future.get (), true );
187
187
}
188
188
189
- TEST_F (CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_interrupted ) {
189
+ TEST_F (CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete_interrupted ) {
190
190
auto node = rclcpp::Node::make_shared (" test_spin" );
191
191
192
192
// Construct a fake future to wait on
@@ -206,7 +206,7 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_inte
206
206
auto shutdown_timer = node->create_wall_timer (std::chrono::milliseconds (25 ), shutdown_callback);
207
207
208
208
ASSERT_EQ (
209
- rclcpp::spin_until_future_complete (node, future, std::chrono::milliseconds (50 )),
209
+ rclcpp::spin_until_complete (node, future, std::chrono::milliseconds (50 )),
210
210
rclcpp::FutureReturnCode::INTERRUPTED);
211
211
}
212
212
0 commit comments