Skip to content

Commit

Permalink
Style was fixed.
Browse files Browse the repository at this point in the history
Signed-off-by: olesya <[email protected]>
  • Loading branch information
bks-ol committed Feb 3, 2025
1 parent 07f410e commit ff1cf21
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 11 deletions.
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,14 +120,14 @@ create_subscription(
}

auto factory = rclcpp::create_subscription_factory<MessageT, CallbackT, AllocatorT,
SubscriptionT, MessageMemoryStrategyT,
ROSMessageType
>(
SubscriptionT, MessageMemoryStrategyT,
ROSMessageType
>(
std::forward<CallbackT>(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(
Expand Down
28 changes: 21 additions & 7 deletions rclcpp/test/rclcpp/test_create_custom_subscription.cpp
Original file line number Diff line number Diff line change
@@ -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 <gtest/gtest.h>

#include <chrono>
Expand Down Expand Up @@ -36,14 +50,14 @@ template<
AllocatorT
>>
class CustomSubscription : public rclcpp::Subscription<
MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>
MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>
{
public:

template <typename... Args>
CustomSubscription(Args &&...args) : rclcpp::Subscription<
MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>(
std::forward<Args>(args)...) {}
template<typename ... Args>
explicit CustomSubscription(Args &&... args)
: rclcpp::Subscription<
MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>(
std::forward<Args>(args)...) {}
};

TEST_F(TestCreateSubscription, create) {
Expand All @@ -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<std::decay_t<decltype(*subscription.get())>, SubscriptionT>);
}
}

0 comments on commit ff1cf21

Please sign in to comment.