From ff1cf21d5085b7b87035ec6d68edf3acb86edb68 Mon Sep 17 00:00:00 2001 From: olesya Date: Mon, 3 Feb 2025 19:27:28 +0000 Subject: [PATCH] Style was fixed. Signed-off-by: olesya --- rclcpp/include/rclcpp/create_subscription.hpp | 8 +++--- .../test_create_custom_subscription.cpp | 28 ++++++++++++++----- 2 files changed, 25 insertions(+), 11 deletions(-) diff --git a/rclcpp/include/rclcpp/create_subscription.hpp b/rclcpp/include/rclcpp/create_subscription.hpp index 08129a2472..481c6940b5 100644 --- a/rclcpp/include/rclcpp/create_subscription.hpp +++ b/rclcpp/include/rclcpp/create_subscription.hpp @@ -120,14 +120,14 @@ create_subscription( } auto factory = rclcpp::create_subscription_factory( + SubscriptionT, MessageMemoryStrategyT, + ROSMessageType + >( std::forward(callback), options, msg_mem_strat, subscription_topic_stats - ); + ); const rclcpp::QoS & actual_qos = options.qos_overriding_options.get_policy_kinds().size() ? rclcpp::detail::declare_qos_parameters( diff --git a/rclcpp/test/rclcpp/test_create_custom_subscription.cpp b/rclcpp/test/rclcpp/test_create_custom_subscription.cpp index dfea57f0a4..894d14a3a2 100644 --- a/rclcpp/test/rclcpp/test_create_custom_subscription.cpp +++ b/rclcpp/test/rclcpp/test_create_custom_subscription.cpp @@ -1,3 +1,17 @@ +// Copyright 2025 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + #include #include @@ -36,14 +50,14 @@ template< AllocatorT >> class CustomSubscription : public rclcpp::Subscription< - MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT> + MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT> { public: - - template - CustomSubscription(Args &&...args) : rclcpp::Subscription< - MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>( - std::forward(args)...) {} + template + explicit CustomSubscription(Args &&... args) + : rclcpp::Subscription< + MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>( + std::forward(args)...) {} }; TEST_F(TestCreateSubscription, create) { @@ -69,4 +83,4 @@ TEST_F(TestCreateSubscription, create) { ASSERT_NE(nullptr, subscription); EXPECT_STREQ("/ns/topic_name", subscription->get_topic_name()); static_assert(std::is_same_v, SubscriptionT>); -} \ No newline at end of file +}