From acd4aec52f491f6a30c3b14a715c487f117197b5 Mon Sep 17 00:00:00 2001 From: dhood Date: Tue, 5 Dec 2017 15:06:58 -0800 Subject: [PATCH] Update for rclcpp namespace removals (#255) * Remove subscription:: namespace * Remove client:: namespace * Remove service:: namespace * Remove parameter_client:: namespace * Remove parameter_service:: namespace * Remove timer:: namespace * Remove node:: namespace * Remove event:: namespace * Remove utilities:: namespace --- .../test/test_publisher_subscriber.cpp | 4 +-- test_communication/test/test_replier.cpp | 4 +-- test_communication/test/test_subscriber.cpp | 4 +-- test_rclcpp/include/test_rclcpp/utils.hpp | 2 +- test_rclcpp/test/parameter_fixtures.hpp | 8 +++--- test_rclcpp/test/test_client_scope_client.cpp | 2 +- .../test_client_scope_consistency_client.cpp | 2 +- .../test_client_scope_consistency_server.cpp | 2 +- test_rclcpp/test/test_client_scope_server.cpp | 2 +- .../test_client_wait_for_service_shutdown.cpp | 2 +- test_rclcpp/test/test_local_parameters.cpp | 28 +++++++++---------- .../test/test_multiple_service_calls.cpp | 6 ++-- test_rclcpp/test/test_multithreaded.cpp | 18 ++++++------ test_rclcpp/test/test_parameters_server.cpp | 2 +- test_rclcpp/test/test_remote_parameters.cpp | 4 +-- test_rclcpp/test/test_services_client.cpp | 2 +- .../test/test_services_in_constructor.cpp | 12 ++++---- test_rclcpp/test/test_spin.cpp | 4 +-- test_rclcpp/test/test_timer.cpp | 2 +- test_security/test/test_secure_publisher.cpp | 2 +- test_security/test/test_secure_subscriber.cpp | 8 +++--- 21 files changed, 60 insertions(+), 60 deletions(-) diff --git a/test_communication/test/test_publisher_subscriber.cpp b/test_communication/test/test_publisher_subscriber.cpp index b66fdb5b..16bd6468 100644 --- a/test_communication/test/test_publisher_subscriber.cpp +++ b/test_communication/test/test_publisher_subscriber.cpp @@ -54,7 +54,7 @@ void publish( } template -rclcpp::subscription::SubscriptionBase::SharedPtr subscribe( +rclcpp::SubscriptionBase::SharedPtr subscribe( rclcpp::Node::SharedPtr node, const std::string & message_type, std::vector & expected_messages, @@ -115,7 +115,7 @@ int main(int argc, char ** argv) std::string message = argv[1]; auto node = rclcpp::Node::make_shared(std::string("test_publisher_subscriber_") + message); - rclcpp::subscription::SubscriptionBase::SharedPtr subscriber; + rclcpp::SubscriptionBase::SharedPtr subscriber; std::vector received_messages; // collect flags about received messages auto messages_empty = get_messages_empty(); diff --git a/test_communication/test/test_replier.cpp b/test_communication/test/test_replier.cpp index 91b9599c..b2d55709 100644 --- a/test_communication/test/test_replier.cpp +++ b/test_communication/test/test_replier.cpp @@ -23,7 +23,7 @@ #include "test_msgs/service_fixtures.hpp" template -typename rclcpp::service::Service::SharedPtr reply( +typename rclcpp::Service::SharedPtr reply( rclcpp::Node::SharedPtr node, const std::string & service_type, const std::vector< @@ -74,7 +74,7 @@ int main(int argc, char ** argv) auto services_empty = get_services_empty(); auto services_primitives = get_services_primitives(); - rclcpp::service::ServiceBase::SharedPtr server; + rclcpp::ServiceBase::SharedPtr server; if (service == "Empty") { server = reply( diff --git a/test_communication/test/test_subscriber.cpp b/test_communication/test/test_subscriber.cpp index f01248d4..4fe169de 100644 --- a/test_communication/test/test_subscriber.cpp +++ b/test_communication/test/test_subscriber.cpp @@ -23,7 +23,7 @@ template -rclcpp::subscription::SubscriptionBase::SharedPtr subscribe( +rclcpp::SubscriptionBase::SharedPtr subscribe( rclcpp::Node::SharedPtr node, const std::string & message_type, std::vector & expected_messages, @@ -96,7 +96,7 @@ int main(int argc, char ** argv) auto messages_static_array_nested = get_messages_static_array_nested(); auto messages_builtins = get_messages_builtins(); - rclcpp::subscription::SubscriptionBase::SharedPtr subscriber; + rclcpp::SubscriptionBase::SharedPtr subscriber; std::vector received_messages; // collect flags about received messages if (message == "Empty") { subscriber = subscribe( diff --git a/test_rclcpp/include/test_rclcpp/utils.hpp b/test_rclcpp/include/test_rclcpp/utils.hpp index 508c9a00..71b19941 100644 --- a/test_rclcpp/include/test_rclcpp/utils.hpp +++ b/test_rclcpp/include/test_rclcpp/utils.hpp @@ -53,7 +53,7 @@ void wait_for_subscriber( } }; while (!predicate() && time_slept < duration_cast(timeout)) { - rclcpp::event::Event::SharedPtr graph_event = node->get_graph_event(); + rclcpp::Event::SharedPtr graph_event = node->get_graph_event(); node->wait_for_graph_change(graph_event, sleep_period); time_slept = duration_cast(steady_clock::now() - start); } diff --git a/test_rclcpp/test/parameter_fixtures.hpp b/test_rclcpp/test/parameter_fixtures.hpp index 40c09492..d37098c5 100644 --- a/test_rclcpp/test/parameter_fixtures.hpp +++ b/test_rclcpp/test/parameter_fixtures.hpp @@ -28,7 +28,7 @@ const double test_epsilon = 1e-6; void set_test_parameters( - std::shared_ptr parameters_client) + std::shared_ptr parameters_client) { printf("Setting parameters\n"); // Set several differnet types of parameters. @@ -52,7 +52,7 @@ void set_test_parameters( void verify_set_parameters_async( std::shared_ptr node, - std::shared_ptr parameters_client) + std::shared_ptr parameters_client) { printf("Setting parameters\n"); // Set several differnet types of parameters. @@ -75,7 +75,7 @@ void verify_set_parameters_async( } void verify_test_parameters( - std::shared_ptr parameters_client) + std::shared_ptr parameters_client) { printf("Listing parameters with recursive depth\n"); // Test recursive depth (=0) @@ -180,7 +180,7 @@ void verify_test_parameters( void verify_get_parameters_async( std::shared_ptr node, - std::shared_ptr parameters_client) + std::shared_ptr parameters_client) { printf("Listing parameters with recursive depth\n"); // Test recursive depth (=0) diff --git a/test_rclcpp/test/test_client_scope_client.cpp b/test_rclcpp/test/test_client_scope_client.cpp index 07c23714..99814832 100644 --- a/test_rclcpp/test/test_client_scope_client.cpp +++ b/test_rclcpp/test/test_client_scope_client.cpp @@ -31,7 +31,7 @@ using namespace std::chrono_literals; TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_test) { - auto node = rclcpp::node::Node::make_shared("client_scope_regression_test"); + auto node = rclcpp::Node::make_shared("client_scope_regression_test"); // Extra scope so the first client will be deleted afterwards { diff --git a/test_rclcpp/test/test_client_scope_consistency_client.cpp b/test_rclcpp/test/test_client_scope_consistency_client.cpp index 40a7477c..4eaa9b43 100644 --- a/test_rclcpp/test/test_client_scope_consistency_client.cpp +++ b/test_rclcpp/test/test_client_scope_consistency_client.cpp @@ -33,7 +33,7 @@ using namespace std::chrono_literals; // This test is concerned with the consistency of the two clients' behavior, not necessarily whether // or not they are successful. TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_regression_test) { - auto node = rclcpp::node::Node::make_shared("client_scope_consistency_regression_test"); + auto node = rclcpp::Node::make_shared("client_scope_consistency_regression_test"); // Replicate the settings that caused https://github.com/ros2/system_tests/issues/153 rmw_qos_profile_t rmw_qos_profile = diff --git a/test_rclcpp/test/test_client_scope_consistency_server.cpp b/test_rclcpp/test/test_client_scope_consistency_server.cpp index 8e3b65d3..8458df0e 100644 --- a/test_rclcpp/test/test_client_scope_consistency_server.cpp +++ b/test_rclcpp/test/test_client_scope_consistency_server.cpp @@ -31,7 +31,7 @@ int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto node = rclcpp::node::Node::make_shared("client_scope_consistency_regression_test_server"); + auto node = rclcpp::Node::make_shared("client_scope_consistency_regression_test_server"); // Replicate the settings that caused https://github.com/ros2/system_tests/issues/153 rmw_qos_profile_t rmw_qos_profile = diff --git a/test_rclcpp/test/test_client_scope_server.cpp b/test_rclcpp/test/test_client_scope_server.cpp index 0dce4bb9..47a57037 100644 --- a/test_rclcpp/test/test_client_scope_server.cpp +++ b/test_rclcpp/test/test_client_scope_server.cpp @@ -31,7 +31,7 @@ int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto node = rclcpp::node::Node::make_shared("client_scope_server"); + auto node = rclcpp::Node::make_shared("client_scope_server"); auto service = node->create_service( "client_scope", handle_add_two_ints); diff --git a/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp b/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp index d7314df0..3d1906f2 100644 --- a/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp +++ b/test_rclcpp/test/test_client_wait_for_service_shutdown.cpp @@ -31,7 +31,7 @@ using namespace std::chrono_literals; // rclcpp::shutdown() should wake up wait_for_service, even without spin. TEST(CLASSNAME(service_client, RMW_IMPLEMENTATION), wait_for_service_shutdown) { rclcpp::init(0, nullptr); - auto node = rclcpp::node::Node::make_shared("wait_for_service_shutdown"); + auto node = rclcpp::Node::make_shared("wait_for_service_shutdown"); auto client = node->create_client("wait_for_service_shutdown"); diff --git a/test_rclcpp/test/test_local_parameters.cpp b/test_rclcpp/test/test_local_parameters.cpp index c9196c8f..b56171a0 100644 --- a/test_rclcpp/test/test_local_parameters.cpp +++ b/test_rclcpp/test/test_local_parameters.cpp @@ -67,8 +67,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), to_string) { TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) { auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous"); // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); + auto parameter_service = std::make_shared(node); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; } @@ -79,8 +79,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous) { TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_repeated) { auto node = rclcpp::Node::make_shared("test_parameters_local_synchronous_repeated"); // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); + auto parameter_service = std::make_shared(node); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; } @@ -94,8 +94,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_synchronous_rep TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_asynchronous) { auto node = rclcpp::Node::make_shared(std::string("test_parameters_local_asynchronous")); // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); + auto parameter_service = std::make_shared(node); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; } @@ -110,7 +110,7 @@ class ParametersAsyncNode : public rclcpp::Node : Node("test_local_parameters_async_with_callback") { parameters_client_ = - std::make_shared(this); + std::make_shared(this); } void queue_set_parameter_request(rclcpp::executors::SingleThreadedExecutor & executor) @@ -146,7 +146,7 @@ class ParametersAsyncNode : public rclcpp::Node TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_callback) { auto node = std::make_shared(); // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); + auto parameter_service = std::make_shared(node); if (!node->parameters_client_->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; } @@ -160,8 +160,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), local_async_with_call TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) { auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); + auto parameter_service = std::make_shared(node); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; } @@ -265,8 +265,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), helpers) { TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_primitive_type) { auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); + auto parameter_service = std::make_shared(node); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; } @@ -332,8 +332,8 @@ TEST(CLASSNAME(test_local_parameters, RMW_IMPLEMENTATION), get_from_node_variant auto node = rclcpp::Node::make_shared("test_parameters_local_helpers"); // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); + auto parameter_service = std::make_shared(node); + auto parameters_client = std::make_shared(node); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; } diff --git a/test_rclcpp/test/test_multiple_service_calls.cpp b/test_rclcpp/test/test_multiple_service_calls.cpp index 774fdf83..d48e7be1 100644 --- a/test_rclcpp/test/test_multiple_service_calls.cpp +++ b/test_rclcpp/test/test_multiple_service_calls.cpp @@ -103,7 +103,7 @@ TEST(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), recursive_service_ca request2->b = 0; bool second_result_received = false; - using AddTwoIntsSharedFuture = rclcpp::client::Client::SharedFuture; + using AddTwoIntsSharedFuture = rclcpp::Client::SharedFuture; auto first_response_received_callback = [&client, &request2, &second_result_received](AddTwoIntsSharedFuture first_future) { @@ -140,9 +140,9 @@ TEST(CLASSNAME(test_multiple_service_calls, RMW_IMPLEMENTATION), multiple_client "test_multiple_clients", handle_add_two_ints); using ClientRequestPair = std::pair< - rclcpp::client::Client::SharedPtr, + rclcpp::Client::SharedPtr, test_rclcpp::srv::AddTwoInts::Request::SharedPtr>; - using SharedFuture = rclcpp::client::Client::SharedFuture; + using SharedFuture = rclcpp::Client::SharedFuture; std::vector client_request_pairs; for (uint32_t i = 0; i < n; ++i) { diff --git a/test_rclcpp/test/test_multithreaded.cpp b/test_rclcpp/test/test_multithreaded.cpp index d23ab100..8a7bd38a 100644 --- a/test_rclcpp/test/test_multithreaded.cpp +++ b/test_rclcpp/test/test_multithreaded.cpp @@ -96,7 +96,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) // wait for delivery to occur. const std::chrono::milliseconds sleep_per_loop(10); while (subscriptions_size != counter.load()) { - rclcpp::utilities::sleep_for(sleep_per_loop); + rclcpp::sleep_for(sleep_per_loop); executor.spin_some(); } EXPECT_EQ(subscriptions_size, counter.load()); @@ -115,7 +115,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) std::mutex publish_mutex; auto publish_callback = [ msg, &pub, &executor, &counter, &expected_count, &sleep_per_loop, &publish_mutex]( - rclcpp::timer::TimerBase & timer) -> void + rclcpp::TimerBase & timer) -> void { std::lock_guard lock(publish_mutex); ++msg->data; @@ -168,9 +168,9 @@ TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients) "multi_consumer_clients", callback, qos_profile, callback_group); using ClientRequestPair = std::pair< - rclcpp::client::Client::SharedPtr, + rclcpp::Client::SharedPtr, test_rclcpp::srv::AddTwoInts::Request::SharedPtr>; - using SharedFuture = rclcpp::client::Client::SharedFuture; + using SharedFuture = rclcpp::Client::SharedFuture; std::vector client_request_pairs; @@ -186,7 +186,7 @@ TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients) int client_request_pairs_size = static_cast(client_request_pairs.size()); executor.add_node(node); - rclcpp::utilities::sleep_for(5ms); + rclcpp::sleep_for(5ms); executor.spin_some(); // No callbacks should have fired @@ -251,7 +251,7 @@ TEST(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients) static inline void multi_access_publisher(bool intra_process) { // Try to access the same publisher simultaneously - auto context = std::make_shared(); + auto context = std::make_shared(); std::string node_topic_name = "multi_access_publisher"; if (intra_process) { node_topic_name += "_intra_process"; @@ -289,13 +289,13 @@ static inline void multi_access_publisher(bool intra_process) auto timer_callback = [&executor, &pub, &msg, &timer_counter, &subscription_counter, &num_messages]( - rclcpp::timer::TimerBase & timer) + rclcpp::TimerBase & timer) { if (timer_counter.load() >= num_messages) { timer.cancel(); // Wait for pending subscription callbacks to trigger. while (subscription_counter < timer_counter) { - rclcpp::utilities::sleep_for(1ms); + rclcpp::sleep_for(1ms); } executor.cancel(); return; @@ -304,7 +304,7 @@ static inline void multi_access_publisher(bool intra_process) printf("Publishing message %u\n", timer_counter.load()); pub->publish(msg); }; - std::vector timers; + std::vector timers; // timers will fire simultaneously in each thread for (uint32_t i = 0; i < std::min(executor.get_number_of_threads(), 16); ++i) { timers.push_back(node->create_wall_timer(std::chrono::milliseconds(1), timer_callback)); diff --git a/test_rclcpp/test/test_parameters_server.cpp b/test_rclcpp/test/test_parameters_server.cpp index 66ce169a..8ec20ec6 100644 --- a/test_rclcpp/test/test_parameters_server.cpp +++ b/test_rclcpp/test/test_parameters_server.cpp @@ -28,7 +28,7 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared(std::string("test_parameters_server")); // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); + auto parameter_service = std::make_shared(node); rclcpp::spin(node); diff --git a/test_rclcpp/test/test_remote_parameters.cpp b/test_rclcpp/test/test_remote_parameters.cpp index 61fe7956..e03d2228 100644 --- a/test_rclcpp/test/test_remote_parameters.cpp +++ b/test_rclcpp/test/test_remote_parameters.cpp @@ -40,7 +40,7 @@ TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_async) { auto node = rclcpp::Node::make_shared(std::string("test_remote_parameters_async")); - auto parameters_client = std::make_shared(node, + auto parameters_client = std::make_shared(node, test_server_name); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; @@ -56,7 +56,7 @@ TEST(CLASSNAME(parameters, rmw_implementation), test_remote_parameters_sync) { auto node = rclcpp::Node::make_shared(std::string("test_remote_parameters_sync")); - auto parameters_client = std::make_shared(node, + auto parameters_client = std::make_shared(node, test_server_name); if (!parameters_client->wait_for_service(20s)) { ASSERT_TRUE(false) << "service not available after waiting"; diff --git a/test_rclcpp/test/test_services_client.cpp b/test_rclcpp/test/test_services_client.cpp index 40be7729..bfd9830f 100644 --- a/test_rclcpp/test/test_services_client.cpp +++ b/test_rclcpp/test/test_services_client.cpp @@ -86,7 +86,7 @@ TEST(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request) { auto result = client->async_send_request( request, - [](rclcpp::client::Client::SharedFutureWithRequest future) { + [](rclcpp::Client::SharedFutureWithRequest future) { EXPECT_EQ(4, future.get().first->a); EXPECT_EQ(5, future.get().first->b); EXPECT_EQ(9, future.get().second->sum); diff --git a/test_rclcpp/test/test_services_in_constructor.cpp b/test_rclcpp/test/test_services_in_constructor.cpp index 0527687d..dcb98dfc 100644 --- a/test_rclcpp/test/test_services_in_constructor.cpp +++ b/test_rclcpp/test/test_services_in_constructor.cpp @@ -33,11 +33,11 @@ * possible at some point, but should be now. */ -class MyNodeWithService : public rclcpp::node::Node +class MyNodeWithService : public rclcpp::Node { public: MyNodeWithService() - : rclcpp::node::Node("node_with_service") + : rclcpp::Node("node_with_service") { service_ = this->create_service( "test", @@ -50,24 +50,24 @@ class MyNodeWithService : public rclcpp::node::Node } private: - rclcpp::service::ServiceBase::SharedPtr service_; + rclcpp::ServiceBase::SharedPtr service_; }; TEST(CLASSNAME(test_services_in_constructor, RMW_IMPLEMENTATION), service_in_constructor) { auto n = std::make_shared(); } -class MyNodeWithClient : public rclcpp::node::Node +class MyNodeWithClient : public rclcpp::Node { public: MyNodeWithClient() - : rclcpp::node::Node("node_with_client") + : rclcpp::Node("node_with_client") { client_ = this->create_client("test"); } private: - rclcpp::client::ClientBase::SharedPtr client_; + rclcpp::ClientBase::SharedPtr client_; }; TEST(CLASSNAME(test_services_in_constructor, RMW_IMPLEMENTATION), client_in_constructor) { diff --git a/test_rclcpp/test/test_spin.cpp b/test_rclcpp/test/test_spin.cpp index 832b61a5..cd329f16 100644 --- a/test_rclcpp/test/test_spin.cpp +++ b/test_rclcpp/test/test_spin.cpp @@ -131,7 +131,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) { std::shared_future future(promise.get_future()); // Make a timer to complete the promise in the future - auto callback = [&promise](rclcpp::timer::TimerBase & timer) { + auto callback = [&promise](rclcpp::TimerBase & timer) { promise.set_value(true); timer.cancel(); }; @@ -182,7 +182,7 @@ TEST(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_interr // Create a timer that will shut down rclcpp before auto shutdown_callback = []() { - rclcpp::utilities::shutdown(); + rclcpp::shutdown(); }; auto shutdown_timer = node->create_wall_timer(std::chrono::milliseconds(25), shutdown_callback); diff --git a/test_rclcpp/test/test_timer.cpp b/test_rclcpp/test/test_timer.cpp index f9f1be71..b32b24c7 100644 --- a/test_rclcpp/test/test_timer.cpp +++ b/test_rclcpp/test/test_timer.cpp @@ -137,7 +137,7 @@ TEST(CLASSNAME(test_time, RMW_IMPLEMENTATION), finite_timer) { int counter = 0; auto callback = - [&counter](rclcpp::timer::TimerBase & timer) -> void + [&counter](rclcpp::TimerBase & timer) -> void { ++counter; printf(" callback() %d\n", counter); diff --git a/test_security/test/test_secure_publisher.cpp b/test_security/test/test_secure_publisher.cpp index 69fdafd3..f1375d5e 100644 --- a/test_security/test/test_secure_publisher.cpp +++ b/test_security/test/test_secure_publisher.cpp @@ -74,7 +74,7 @@ int main(int argc, char ** argv) std::string namespace_ = argv[2]; std::string node_name = "publisher"; std::string topic_name = "chatter"; - std::shared_ptr node = nullptr; + std::shared_ptr node = nullptr; try { node = rclcpp::Node::make_shared(node_name, namespace_); } catch (std::runtime_error & exc) { diff --git a/test_security/test/test_secure_subscriber.cpp b/test_security/test/test_secure_subscriber.cpp index 1ca551ee..fbba68c6 100644 --- a/test_security/test/test_secure_subscriber.cpp +++ b/test_security/test/test_secure_subscriber.cpp @@ -25,7 +25,7 @@ using namespace std::chrono_literals; template -rclcpp::subscription::SubscriptionBase::SharedPtr attempt_subscribe( +rclcpp::SubscriptionBase::SharedPtr attempt_subscribe( rclcpp::Node::SharedPtr node, const std::string & topic_name, std::vector & expected_messages, @@ -74,7 +74,7 @@ rclcpp::subscription::SubscriptionBase::SharedPtr attempt_subscribe( } template -rclcpp::subscription::SubscriptionBase::SharedPtr attempt_subscribe( +rclcpp::SubscriptionBase::SharedPtr attempt_subscribe( rclcpp::Node::SharedPtr node, const std::string & topic_name, bool & sub_callback_called, @@ -128,7 +128,7 @@ int main(int argc, char ** argv) ((0 == strcmp(argv[2], "false")) || (0 == strcmp(argv[2], "0"))) ? false : true; rclcpp::init(argc, argv); - std::shared_ptr node = nullptr; + std::shared_ptr node = nullptr; try { node = rclcpp::Node::make_shared(node_name, namespace_); } catch (std::runtime_error & exc) { @@ -136,7 +136,7 @@ int main(int argc, char ** argv) rclcpp::shutdown(); return 1; } - rclcpp::subscription::SubscriptionBase::SharedPtr subscriber; + rclcpp::SubscriptionBase::SharedPtr subscriber; if (!should_timeout) { std::vector received_messages; // collect flags about received messages