Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Replace deprecated spin_until_future_complete #669

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 8 additions & 8 deletions demo_nodes_cpp/src/events/matched_event_detect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,46 +213,46 @@ int main(int argc, char ** argv)
// MatchedEventDetectNode will output:
// First subscription is connected.
auto sub1 = multi_sub_node->create_one_sub();
executor.spin_until_future_complete(matched_event_detect_node->get_future(), maximum_wait_time);
executor.spin_until_complete(matched_event_detect_node->get_future(), maximum_wait_time);

// MatchedEventDetectNode will output:
// The changed number of connected subscription is 1 and current number of connected subscription
// is 2.
auto sub2 = multi_sub_node->create_one_sub();
executor.spin_until_future_complete(matched_event_detect_node->get_future(), maximum_wait_time);
executor.spin_until_complete(matched_event_detect_node->get_future(), maximum_wait_time);

// MatchedEventDetectNode will output:
// The changed number of connected subscription is -1 and current number of connected subscription
// is 1.
multi_sub_node->destroy_one_sub(sub1);
executor.spin_until_future_complete(matched_event_detect_node->get_future(), maximum_wait_time);
executor.spin_until_complete(matched_event_detect_node->get_future(), maximum_wait_time);

// MatchedEventDetectNode will output:
// Last subscription is disconnected.
multi_sub_node->destroy_one_sub(sub2);
executor.spin_until_future_complete(matched_event_detect_node->get_future(), maximum_wait_time);
executor.spin_until_complete(matched_event_detect_node->get_future(), maximum_wait_time);

// MatchedEventDetectNode will output:
// First publisher is connected.
auto pub1 = multi_pub_node->create_one_pub();
executor.spin_until_future_complete(matched_event_detect_node->get_future(), maximum_wait_time);
executor.spin_until_complete(matched_event_detect_node->get_future(), maximum_wait_time);

// MatchedEventDetectNode will output:
// The changed number of connected publisher is 1 and current number of connected publisher
// is 2.
auto pub2 = multi_pub_node->create_one_pub();
executor.spin_until_future_complete(matched_event_detect_node->get_future(), maximum_wait_time);
executor.spin_until_complete(matched_event_detect_node->get_future(), maximum_wait_time);

// MatchedEventDetectNode will output:
// The changed number of connected publisher is -1 and current number of connected publisher
// is 1.
multi_pub_node->destroy_one_pub(pub1);
executor.spin_until_future_complete(matched_event_detect_node->get_future(), maximum_wait_time);
executor.spin_until_complete(matched_event_detect_node->get_future(), maximum_wait_time);

// MatchedEventDetectNode will output:
// Last publisher is disconnected.
multi_pub_node->destroy_one_pub(pub2);
executor.spin_until_future_complete(matched_event_detect_node->get_future(), maximum_wait_time);
executor.spin_until_complete(matched_event_detect_node->get_future(), maximum_wait_time);

rclcpp::shutdown();
return 0;
Expand Down
4 changes: 2 additions & 2 deletions demo_nodes_cpp/src/logging/use_logger_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ class TestNode : public rclcpp::Node

auto result = logger_set_client_->async_send_request(request);

if (rclcpp::spin_until_future_complete(this->shared_from_this(), result) !=
if (rclcpp::spin_until_complete(this->shared_from_this(), result) !=
rclcpp::FutureReturnCode::SUCCESS)
{
return false;
Expand All @@ -109,7 +109,7 @@ class TestNode : public rclcpp::Node
auto request = std::make_shared<rcl_interfaces::srv::GetLoggerLevels::Request>();
request->names.emplace_back(remote_node_name_);
auto result = logger_get_client_->async_send_request(request);
if (rclcpp::spin_until_future_complete(shared_from_this(), result) !=
if (rclcpp::spin_until_complete(shared_from_this(), result) !=
rclcpp::FutureReturnCode::SUCCESS)
{
return false;
Expand Down
4 changes: 2 additions & 2 deletions demo_nodes_cpp/src/parameters/list_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,13 @@ int main(int argc, char ** argv)
rclcpp::Parameter("foobar", true),
});
// Wait for the result.
rclcpp::spin_until_future_complete(node, results);
rclcpp::spin_until_complete(node, results);

RCLCPP_INFO(node->get_logger(), "Listing parameters...");
// List the details of a few parameters up to a namespace depth of 10.
auto parameter_list_future = parameters_client->list_parameters({"foo", "bar"}, 10);

if (rclcpp::spin_until_future_complete(node, parameter_list_future) !=
if (rclcpp::spin_until_complete(node, parameter_list_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "service call failed, exiting tutorial.");
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/parameters/parameter_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ int main(int argc, char ** argv)

// TODO(wjwwood): Create and use delete_parameter

rclcpp::spin_until_future_complete(node, events_received_future.share());
rclcpp::spin_until_complete(node, events_received_future.share());
rclcpp::shutdown();

return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ int main(int argc, char ** argv)
rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
});
// Wait for the results.
if (rclcpp::spin_until_future_complete(node, results) !=
if (rclcpp::spin_until_complete(node, results) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "set_parameters service call failed. Exiting tutorial.");
Expand All @@ -73,7 +73,7 @@ int main(int argc, char ** argv)

// Get a few of the parameters just set.
auto parameters = parameters_client->get_parameters({"foo", "baz", "foobarbaz", "toto"});
if (rclcpp::spin_until_future_complete(node, parameters) !=
if (rclcpp::spin_until_complete(node, parameters) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "get_parameters service call failed. Exiting tutorial.");
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/services/add_two_ints_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ example_interfaces::srv::AddTwoInts::Response::SharedPtr send_request(
{
auto result = client->async_send_request(request);
// Wait for the result.
if (rclcpp::spin_until_future_complete(node, result) ==
if (rclcpp::spin_until_complete(node, result) ==
rclcpp::FutureReturnCode::SUCCESS)
{
return result.get();
Expand Down
16 changes: 8 additions & 8 deletions demo_nodes_py/demo_nodes_py/events/matched_event_detect.py
Original file line number Diff line number Diff line change
Expand Up @@ -154,46 +154,46 @@ def main(args=None):
# MatchedEventDetectNode will output:
# First subscription is connected.
sub1 = multi_subs_node.create_one_sub()
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
executor.spin_until_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected subscription is 1 and current number of connected
# subscription is 2.
sub2 = multi_subs_node.create_one_sub()
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
executor.spin_until_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected subscription is -1 and current number of connected
# subscription is 1.
multi_subs_node.destroy_one_sub(sub1)
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
executor.spin_until_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# Last subscription is disconnected.
multi_subs_node.destroy_one_sub(sub2)
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
executor.spin_until_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# First publisher is connected.
pub1 = multi_pubs_node.create_one_pub()
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
executor.spin_until_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected publisher is 1 and current number of connected publisher
# is 2.
pub2 = multi_pubs_node.create_one_pub()
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
executor.spin_until_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# The changed number of connected publisher is -1 and current number of connected publisher
# is 1.
multi_pubs_node.destroy_one_pub(pub1)
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
executor.spin_until_complete(matched_event_detect_node.get_future(), maximum_wait_time)

# MatchedEventDetectNode will output:
# Last publisher is disconnected.
multi_pubs_node.destroy_one_pub(pub2)
executor.spin_until_future_complete(matched_event_detect_node.get_future(), maximum_wait_time)
executor.spin_until_complete(matched_event_detect_node.get_future(), maximum_wait_time)

multi_pubs_node.destroy_node()
multi_subs_node.destroy_node()
Expand Down
4 changes: 2 additions & 2 deletions demo_nodes_py/demo_nodes_py/logging/use_logger_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def set_logger_level_on_remote_node(self, logger_level) -> bool:
request.levels.append(set_logger_level)

future = self._logger_set_client.call_async(request)
rclpy.spin_until_future_complete(self, future)
rclpy.spin_until_complete(self, future)

ret_results = future.result()
if not ret_results:
Expand All @@ -88,7 +88,7 @@ def get_logger_level_on_remote_node(self):
request.names.append(self._remote_node_name)

future = self.logger_get_client.call_async(request)
rclpy.spin_until_future_complete(self, future)
rclpy.spin_until_complete(self, future)

ret_results = future.result()
if not ret_results:
Expand Down
10 changes: 5 additions & 5 deletions demo_nodes_py/demo_nodes_py/parameters/async_param_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ def main(args=None):
Parameter('int_parameter', Parameter.Type.INTEGER, 10),
Parameter('bool_parameter', Parameter.Type.BOOL, False),
Parameter('string_parameter', Parameter.Type.STRING, 'Fee Fi Fo Fum'), ])
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_complete(node, future)
set_parameters_result = future.result()
if set_parameters_result is not None:
for i, v in enumerate(set_parameters_result.results):
Expand All @@ -48,7 +48,7 @@ def main(args=None):

node.get_logger().info('Listing Parameters:')
future = client.list_parameters(param_list, 10)
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_complete(node, future)
list_parameters_result = future.result()
if list_parameters_result is not None:
for param_name in list_parameters_result.result.names:
Expand All @@ -58,7 +58,7 @@ def main(args=None):

node.get_logger().info('Getting parameters:')
future = client.get_parameters(param_list)
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_complete(node, future)
get_parameters_result = future.result()
if get_parameters_result is not None:
for i, v in enumerate(get_parameters_result.values):
Expand All @@ -70,7 +70,7 @@ def main(args=None):
param_dir = get_package_share_directory('demo_nodes_py')
param_file_path = os.path.join(param_dir, 'params.yaml')
future = client.load_parameter_file(param_file_path)
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_complete(node, future)
load_parameter_results = future.result()
if load_parameter_results is not None:
param_file_dict = parameter_dict_from_yaml_file(param_file_path)
Expand All @@ -86,7 +86,7 @@ def main(args=None):
node.get_logger().info('Deleting parameters: ')
params_to_delete = ['other_int_parameter', 'other_string_parameter', 'string_parameter']
future = client.delete_parameters(params_to_delete)
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_complete(node, future)
delete_parameters_result = future.result()
if delete_parameters_result is not None:
for i, v in enumerate(delete_parameters_result.results):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ def main(args=None):
req.a = 2
req.b = 3
future = cli.call_async(req)
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_complete(node, future)
if future.result() is not None:
node.get_logger().info('Result of add_two_ints: %d' % future.result().sum)
else:
Expand Down
2 changes: 1 addition & 1 deletion lifecycle/src/lifecycle_service_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -340,7 +340,7 @@ int main(int argc, char ** argv)
std::ref(exe)
);

exe.spin_until_future_complete(script);
exe.spin_until_complete(script);

rclcpp::shutdown();

Expand Down