diff --git a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp index 57d79bee..18fae5f5 100644 --- a/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp +++ b/test_rclcpp/test/test_avoid_ros_namespace_conventions_qos.cpp @@ -47,8 +47,7 @@ TEST_F(test_avoid_ros_namespace_conventions_qos, pub_sub_works) // code to create the callback and subscription int counter = 0; auto callback = - [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, - const rclcpp::MessageInfo & info) -> void + [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, const rclcpp::MessageInfo & info) { ++counter; printf(" callback() %d with message data %u\n", counter, msg->data); diff --git a/test_rclcpp/test/test_multithreaded.cpp b/test_rclcpp/test/test_multithreaded.cpp index bcf1dcd6..effd80aa 100644 --- a/test_rclcpp/test/test_multithreaded.cpp +++ b/test_rclcpp/test/test_multithreaded.cpp @@ -66,9 +66,9 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) std::vector::SharedPtr> subscriptions; std::atomic_int counter(0); + using MsgType = test_rclcpp::msg::UInt32; auto callback = - [&counter, &intra_process](test_rclcpp::msg::UInt32::ConstSharedPtr msg, - const rclcpp::MessageInfo & info) -> void + [&counter, &intra_process](MsgType::ConstSharedPtr msg, const rclcpp::MessageInfo & info) { counter.fetch_add(1); printf("callback() %d with message data %u\n", counter.load(), msg->data); @@ -79,7 +79,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) rclcpp::SubscriptionOptions subscription_options; subscription_options.callback_group = callback_group; for (uint32_t i = 0; i < num_messages; ++i) { - auto sub = node->create_subscription( + auto sub = node->create_subscription( node_topic_name, 5 * num_messages, callback, subscription_options); subscriptions.push_back(sub); } @@ -87,7 +87,7 @@ static inline void multi_consumer_pub_sub_test(bool intra_process) int subscriptions_size = static_cast(subscriptions.size()); executor.add_node(node); - test_rclcpp::msg::UInt32 msg; + MsgType msg; msg.data = 0; // wait a moment for everything to initialize @@ -169,8 +169,9 @@ TEST_F(test_multithreaded, multi_consumer_clients) rclcpp::executors::MultiThreadedExecutor executor; std::atomic_int counter(0); - auto callback = [&counter](const std::shared_ptr request, - std::shared_ptr response) + using SrvType = test_rclcpp::srv::AddTwoInts; + auto callback = + [&counter](const SrvType::Request::SharedPtr request, SrvType::Response::SharedPtr response) { printf("Called service callback: %d\n", counter.load()); ++counter; @@ -185,16 +186,15 @@ TEST_F(test_multithreaded, multi_consumer_clients) "multi_consumer_clients", callback, qos_profile, callback_group); using ClientRequestPair = std::pair< - rclcpp::Client::SharedPtr, - test_rclcpp::srv::AddTwoInts::Request::SharedPtr>; - using SharedFuture = rclcpp::Client::SharedFuture; - + rclcpp::Client::SharedPtr, + SrvType::Request::SharedPtr>; + using SharedFuture = rclcpp::Client::SharedFuture; std::vector client_request_pairs; for (uint32_t i = 0; i < 2 * std::min(executor.get_number_of_threads(), 16); ++i) { - auto client = node->create_client( + auto client = node->create_client( "multi_consumer_clients", qos_profile, callback_group); - auto request = std::make_shared(); + auto request = std::make_shared(); request->a = i; request->b = i + 1; client_request_pairs.push_back(ClientRequestPair(client, request)); diff --git a/test_rclcpp/test/test_publisher.cpp b/test_rclcpp/test/test_publisher.cpp index f03edc79..401315b6 100644 --- a/test_rclcpp/test/test_publisher.cpp +++ b/test_rclcpp/test/test_publisher.cpp @@ -47,8 +47,7 @@ TEST_F(test_publisher, publish_with_const_reference) // code to create the callback and subscription int counter = 0; auto callback = - [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, - const rclcpp::MessageInfo & info) -> void + [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, const rclcpp::MessageInfo & info) { ++counter; printf(" callback() %d with message data %u\n", counter, msg->data); diff --git a/test_rclcpp/test/test_subscription.cpp b/test_rclcpp/test/test_subscription.cpp index d6686867..1b7695c2 100644 --- a/test_rclcpp/test/test_subscription.cpp +++ b/test_rclcpp/test/test_subscription.cpp @@ -290,8 +290,7 @@ TEST_F(test_subscription, subscription_shared_ptr_const_with_info) // create the callback and subscription int counter = 0; auto callback = - [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, - const rclcpp::MessageInfo & info) -> void + [&counter](test_rclcpp::msg::UInt32::ConstSharedPtr msg, const rclcpp::MessageInfo & info) { ++counter; printf(" callback() %d with message data %u\n", counter, msg->data);