Skip to content

Commit 07f410e

Browse files
committed
Added a test to check if a custom subscriber was created correctly.
Signed-off-by: olesya <bks-ol@mail.ru>
1 parent 4dfefcf commit 07f410e

File tree

2 files changed

+79
-0
lines changed

2 files changed

+79
-0
lines changed

rclcpp/test/rclcpp/CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -100,6 +100,13 @@ if(TARGET test_create_subscription)
100100
"test_msgs"
101101
)
102102
endif()
103+
ament_add_gtest(test_create_custom_subscription test_create_custom_subscription.cpp)
104+
if(TARGET test_create_custom_subscription)
105+
target_link_libraries(test_create_custom_subscription ${PROJECT_NAME})
106+
ament_target_dependencies(test_create_custom_subscription
107+
"test_msgs"
108+
)
109+
endif()
103110
function(test_add_callback_groups_to_executor_for_rmw_implementation)
104111
set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation})
105112
ament_add_gmock(test_add_callback_groups_to_executor${target_suffix} test_add_callback_groups_to_executor.cpp
Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
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

Comments
 (0)