1
+ #include < gtest/gtest.h>
2
+
3
+ #include < chrono>
4
+ #include < memory>
5
+ #include < type_traits>
6
+
7
+ #include " rclcpp/subscription.hpp"
8
+ #include " rclcpp/create_subscription.hpp"
9
+ #include " rclcpp/node.hpp"
10
+ #include " test_msgs/msg/empty.hpp"
11
+ #include " test_msgs/msg/empty.h"
12
+
13
+ using namespace std ::chrono_literals;
14
+
15
+ class TestCreateSubscription : public ::testing::Test
16
+ {
17
+ public:
18
+ void SetUp () override
19
+ {
20
+ rclcpp::init (0 , nullptr );
21
+ }
22
+
23
+ void TearDown () override
24
+ {
25
+ rclcpp::shutdown ();
26
+ }
27
+ };
28
+
29
+ template <
30
+ typename MessageT,
31
+ typename AllocatorT = std::allocator<void >,
32
+ typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type,
33
+ typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type,
34
+ typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
35
+ ROSMessageT,
36
+ AllocatorT
37
+ >>
38
+ class CustomSubscription : public rclcpp ::Subscription<
39
+ MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>
40
+ {
41
+ public:
42
+
43
+ template <typename ... Args>
44
+ CustomSubscription (Args &&...args) : rclcpp::Subscription<
45
+ MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>(
46
+ std::forward<Args>(args)...) {}
47
+ };
48
+
49
+ TEST_F (TestCreateSubscription, create) {
50
+ using MessageT = test_msgs::msg::Empty;
51
+
52
+ auto node = std::make_shared<rclcpp::Node>(" my_node" , " /ns" );
53
+ const rclcpp::QoS qos (10 );
54
+ auto options = rclcpp::SubscriptionOptions ();
55
+ auto callback = [](MessageT::ConstSharedPtr) {};
56
+
57
+ using CallbackT = std::decay_t <decltype (callback)>;
58
+ using AllocatorT = std::allocator<void >;
59
+ using SubscriptionT = CustomSubscription<MessageT, AllocatorT>;
60
+ using CallbackMessageT =
61
+ typename rclcpp::subscription_traits::has_message_type<CallbackT>::type;
62
+ using MessageMemoryStrategyT =
63
+ rclcpp::message_memory_strategy::MessageMemoryStrategy<CallbackMessageT, AllocatorT>;
64
+
65
+ auto subscription = rclcpp::create_subscription<
66
+ MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>(
67
+ node, " topic_name" , qos, std::move (callback), options);
68
+
69
+ ASSERT_NE (nullptr , subscription);
70
+ EXPECT_STREQ (" /ns/topic_name" , subscription->get_topic_name ());
71
+ static_assert (std::is_same_v<std::decay_t <decltype (*subscription.get ())>, SubscriptionT>);
72
+ }
0 commit comments