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

avoid new deprecations #426

Merged
merged 2 commits into from
Apr 23, 2020
Merged
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
2 changes: 1 addition & 1 deletion test_communication/test/test_action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_client_scope_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand All @@ -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();
}
Expand Down
10 changes: 5 additions & 5 deletions test_rclcpp/test/test_client_scope_consistency_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand All @@ -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) {
Expand All @@ -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();
}

Expand All @@ -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) {
Expand All @@ -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();
}

Expand Down
10 changes: 5 additions & 5 deletions test_rclcpp/test/test_multithreaded.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<size_t>(executor.get_number_of_threads(), 16);
auto pub = node->create_publisher<test_rclcpp::msg::UInt32>(node_topic_name, 5 * num_messages);

Expand Down Expand Up @@ -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<size_t>(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<test_rclcpp::srv::AddTwoInts>(
"multi_consumer_clients", callback, qos_profile, callback_group);

Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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;

Expand Down
6 changes: 3 additions & 3 deletions test_rclcpp/test/test_services_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand All @@ -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);
}
Expand Down Expand Up @@ -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);
}
10 changes: 5 additions & 5 deletions test_rclcpp/test/test_spin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -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);
}

Expand All @@ -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);
}
Expand All @@ -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) {
Expand Down
8 changes: 4 additions & 4 deletions test_rclcpp/test/test_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,12 +40,12 @@ using namespace std::chrono_literals;

template<typename DurationT>
void wait_for_future(
rclcpp::executor::Executor & executor,
rclcpp::Executor & executor,
std::shared_future<void> & 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;
Expand Down Expand Up @@ -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<void>();
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);
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down Expand Up @@ -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<bool> fut(waitable->execute_promise_.get_future());
Expand Down